Browse Source

调整Mavlink和日志频率

my1.12-iic
那个Zeng 3 years ago
parent
commit
a740a1b091
  1. 3
      src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp
  2. 2
      src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.h
  3. 3
      src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c_main.cpp
  4. 2
      src/modules/commander/state_machine_helper.cpp
  5. 2
      src/modules/logger/logged_topics.cpp
  6. 3
      src/modules/mavlink/mavlink_main.cpp

3
src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp

@ -54,7 +54,8 @@ TFmini_i2c::TFmini_i2c(I2CSPIBusOption bus_option, const int bus, const uint8_t
{ {
_px4_rangefinder.set_min_distance(TFMINI_MIN_DISTANCE); _px4_rangefinder.set_min_distance(TFMINI_MIN_DISTANCE);
_px4_rangefinder.set_max_distance(TFMINI_MAX_DISTANCE); _px4_rangefinder.set_max_distance(TFMINI_MAX_DISTANCE);
_px4_rangefinder.set_fov(0.008); // Divergence 8 mRadian _px4_rangefinder.set_fov(math::radians(1.15f));
// up the retries since the device misses the first measure attempts // up the retries since the device misses the first measure attempts
_retries = 3; _retries = 3;

2
src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.h

@ -86,7 +86,7 @@ static constexpr int TFMINI_PEAK_STRENGTH_LOW = 135; /* Minimum peak str
static constexpr int TFMINI_PEAK_STRENGTH_HIGH = 234; /* Max peak strength raw value */ static constexpr int TFMINI_PEAK_STRENGTH_HIGH = 234; /* Max peak strength raw value */
static constexpr float TFMINI_MIN_DISTANCE{0.05f}; static constexpr float TFMINI_MIN_DISTANCE{0.2f};
static constexpr float TFMINI_MAX_DISTANCE{12.00f}; static constexpr float TFMINI_MAX_DISTANCE{12.00f};
static constexpr float TFMINI_MAX_DISTANCE_V2{35.00f}; static constexpr float TFMINI_MAX_DISTANCE_V2{35.00f};

3
src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c_main.cpp

@ -138,8 +138,7 @@ extern "C" __EXPORT int tfmini_i2c_main(int argc, char *argv[])
} }
if (!strcmp(verb, "test")) { if (!strcmp(verb, "test")) {
static float dist; double dist= 1.1;
dist += 1.1;
printf("test dist:%.2f\n",dist); printf("test dist:%.2f\n",dist);
return 0; return 0;
} }

2
src/modules/commander/state_machine_helper.cpp

@ -280,7 +280,7 @@ transition_result_t arming_state_transition(vehicle_status_s &status, const safe
return ret; return ret;
} }
// 判断遥控器是否切换成功
transition_result_t transition_result_t
main_state_transition(const vehicle_status_s &status, const main_state_t new_main_state, main_state_transition(const vehicle_status_s &status, const main_state_t new_main_state,
const vehicle_status_flags_s &status_flags, commander_state_s &internal_state) const vehicle_status_flags_s &status_flags, commander_state_s &internal_state)

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