Browse Source

调整log和Mavlink频率

tf-1.12-print_test
那个Zeng 3 years ago
parent
commit
bdf33f23e3
  1. 9
      src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.cpp
  2. 2
      src/modules/logger/logged_topics.cpp
  3. 3
      src/modules/mavlink/mavlink_main.cpp

9
src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.cpp

@ -39,6 +39,7 @@
#include <float.h> #include <float.h>
#include <mathlib/mathlib.h> #include <mathlib/mathlib.h>
#include <ecl/geo/geo.h> #include <ecl/geo/geo.h>
#include <drivers/drv_hrt.h>
using namespace matrix; using namespace matrix;
@ -376,5 +377,13 @@ bool FlightTaskManualAltitude::update()
_updateSetpoints(); _updateSetpoints();
_constraints.want_takeoff = _checkTakeoff(); _constraints.want_takeoff = _checkTakeoff();
static uint64_t delay_1s = hrt_absolute_time();
static uint64_t delt_time;
if (hrt_absolute_time() - delay_1s > 1 * 1000000ULL)
{
printf("update,delt:%dms \n",(hrt_absolute_time() - delt_time)/(1 * 1000ULL) );
delay_1s = hrt_absolute_time();
}
delt_time = hrt_absolute_time();
return ret; return ret;
} }

2
src/modules/logger/logged_topics.cpp

@ -159,7 +159,7 @@ void LoggedTopics::add_default_topics()
// log all raw sensors at minimal rate (at least 1 Hz) // log all raw sensors at minimal rate (at least 1 Hz)
add_topic_multi("battery_status", 200, 2); add_topic_multi("battery_status", 200, 2);
add_topic_multi("differential_pressure", 1000, 2); add_topic_multi("differential_pressure", 1000, 2);
add_topic_multi("distance_sensor", 1000); add_topic_multi("distance_sensor", 100);
add_topic_multi("optical_flow", 1000, 1); add_topic_multi("optical_flow", 1000, 1);
add_topic_multi("sensor_accel", 1000, 4); add_topic_multi("sensor_accel", 1000, 4);
add_topic_multi("sensor_baro", 1000, 4); add_topic_multi("sensor_baro", 1000, 4);

3
src/modules/mavlink/mavlink_main.cpp

@ -1521,7 +1521,8 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("BATTERY_STATUS", 0.5f); configure_stream_local("BATTERY_STATUS", 0.5f);
configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate); configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate);
configure_stream_local("COLLISION", unlimited_rate); configure_stream_local("COLLISION", unlimited_rate);
configure_stream_local("DISTANCE_SENSOR", 0.5f); // configure_stream_local("DISTANCE_SENSOR", 0.5f);
configure_stream_local("DISTANCE_SENSOR", 10.0f);
configure_stream_local("ESC_INFO", 1.0f); configure_stream_local("ESC_INFO", 1.0f);
configure_stream_local("ESC_STATUS", 1.0f); configure_stream_local("ESC_STATUS", 1.0f);
configure_stream_local("ESTIMATOR_STATUS", 0.5f); configure_stream_local("ESTIMATOR_STATUS", 0.5f);

Loading…
Cancel
Save