mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 09:28:58 +00:00
Refactored Mavlink stream configuration (#5015)
Streams ordered same way in all modes.
This commit is contained in:
@@ -1851,76 +1851,76 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
switch (_mode) {
|
||||
case MAVLINK_MODE_NORMAL:
|
||||
configure_stream("SYS_STATUS", 1.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("EXTENDED_SYS_STATE", 1.0f);
|
||||
configure_stream("HIGHRES_IMU", 2.0f);
|
||||
configure_stream("ATTITUDE", 20.0f);
|
||||
configure_stream("VFR_HUD", 8.0f);
|
||||
configure_stream("GPS_RAW_INT", 1.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 3.0f);
|
||||
configure_stream("LOCAL_POSITION_NED", 3.0f);
|
||||
configure_stream("RC_CHANNELS", 1.0f);
|
||||
configure_stream("SERVO_OUTPUT_RAW_0", 1.0f);
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 8.0f);
|
||||
configure_stream("ALTITUDE", 1.0f);
|
||||
configure_stream("GPS_RAW_INT", 1.0f);
|
||||
configure_stream("ADSB_VEHICLE", 2.0f);
|
||||
configure_stream("DISTANCE_SENSOR", 0.5f);
|
||||
configure_stream("OPTICAL_FLOW_RAD", 5.0f);
|
||||
configure_stream("EXTENDED_SYS_STATE", 1.0f);
|
||||
configure_stream("ALTITUDE", 1.0f);
|
||||
configure_stream("VISION_POSITION_NED", 10.0f);
|
||||
configure_stream("NAMED_VALUE_FLOAT", 1.0f);
|
||||
configure_stream("ESTIMATOR_STATUS", 0.5f);
|
||||
configure_stream("ADSB_VEHICLE", 2.0f);
|
||||
configure_stream("NAV_CONTROLLER_OUTPUT", 2.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 3.0f);
|
||||
configure_stream("LOCAL_POSITION_NED", 3.0f);
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 8.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("NAMED_VALUE_FLOAT", 1.0f);
|
||||
configure_stream("VFR_HUD", 8.0f);
|
||||
configure_stream("WIND", 2.0f);
|
||||
break;
|
||||
|
||||
case MAVLINK_MODE_ONBOARD:
|
||||
configure_stream("SYS_STATUS", 1.0f);
|
||||
configure_stream("ATTITUDE", 250.0f);
|
||||
configure_stream("EXTENDED_SYS_STATE", 2.0f);
|
||||
configure_stream("HIGHRES_IMU", 50.0f);
|
||||
configure_stream("GPS_RAW_INT", 5.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 50.0f);
|
||||
configure_stream("LOCAL_POSITION_NED", 30.0f);
|
||||
configure_stream("NAMED_VALUE_FLOAT", 10.0f);
|
||||
configure_stream("CAMERA_CAPTURE", 2.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("ATTITUDE_TARGET", 10.0f);
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
|
||||
configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f);
|
||||
configure_stream("DISTANCE_SENSOR", 10.0f);
|
||||
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
|
||||
configure_stream("ATTITUDE", 250.0f);
|
||||
configure_stream("RC_CHANNELS", 20.0f);
|
||||
configure_stream("SERVO_OUTPUT_RAW_0", 10.0f);
|
||||
configure_stream("VFR_HUD", 10.0f);
|
||||
configure_stream("SYSTEM_TIME", 1.0f);
|
||||
configure_stream("TIMESYNC", 10.0f);
|
||||
configure_stream("ACTUATOR_CONTROL_TARGET0", 10.0f);
|
||||
//camera trigger is rate limited at the source, do not limit here
|
||||
configure_stream("CAMERA_TRIGGER", 500.0f);
|
||||
configure_stream("EXTENDED_SYS_STATE", 2.0f);
|
||||
configure_stream("ALTITUDE", 10.0f);
|
||||
configure_stream("GPS_RAW_INT", 5.0f);
|
||||
configure_stream("ADSB_VEHICLE", 10.0f);
|
||||
configure_stream("DISTANCE_SENSOR", 10.0f);
|
||||
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
|
||||
configure_stream("VISION_POSITION_NED", 10.0f);
|
||||
configure_stream("ESTIMATOR_STATUS", 1.0f);
|
||||
configure_stream("ADSB_VEHICLE", 10.0f);
|
||||
configure_stream("NAV_CONTROLLER_OUTPUT", 10.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 50.0f);
|
||||
configure_stream("LOCAL_POSITION_NED", 30.0f);
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 10.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("NAMED_VALUE_FLOAT", 10.0f);
|
||||
configure_stream("VFR_HUD", 10.0f);
|
||||
configure_stream("WIND", 10.0f);
|
||||
configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f);
|
||||
configure_stream("SYSTEM_TIME", 1.0f);
|
||||
configure_stream("TIMESYNC", 10.0f);
|
||||
configure_stream("CAMERA_CAPTURE", 2.0f);
|
||||
//camera trigger is rate limited at the source, do not limit here
|
||||
configure_stream("CAMERA_TRIGGER", 500.0f);
|
||||
configure_stream("ACTUATOR_CONTROL_TARGET0", 10.0f);
|
||||
break;
|
||||
|
||||
case MAVLINK_MODE_OSD:
|
||||
configure_stream("SYS_STATUS", 5.0f);
|
||||
configure_stream("EXTENDED_SYS_STATE", 1.0f);
|
||||
configure_stream("ATTITUDE", 25.0f);
|
||||
configure_stream("VFR_HUD", 25.0f);
|
||||
configure_stream("GPS_RAW_INT", 1.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 10.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("ATTITUDE_TARGET", 10.0f);
|
||||
configure_stream("SYSTEM_TIME", 1.0f);
|
||||
configure_stream("RC_CHANNELS", 5.0f);
|
||||
configure_stream("SERVO_OUTPUT_RAW_0", 1.0f);
|
||||
configure_stream("EXTENDED_SYS_STATE", 1.0f);
|
||||
configure_stream("ALTITUDE", 1.0f);
|
||||
configure_stream("GPS_RAW_INT", 1.0f);
|
||||
configure_stream("ESTIMATOR_STATUS", 1.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 10.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 10.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("VFR_HUD", 25.0f);
|
||||
configure_stream("WIND", 2.0f);
|
||||
configure_stream("SYSTEM_TIME", 1.0f);
|
||||
break;
|
||||
|
||||
case MAVLINK_MODE_MAGIC:
|
||||
@@ -1930,32 +1930,32 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
case MAVLINK_MODE_CONFIG:
|
||||
// Enable a number of interesting streams we want via USB
|
||||
configure_stream("SYS_STATUS", 1.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 10.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 8.0f);
|
||||
configure_stream("MISSION_ITEM", 50.0f);
|
||||
configure_stream("NAMED_VALUE_FLOAT", 50.0f);
|
||||
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
|
||||
configure_stream("DISTANCE_SENSOR", 10.0f);
|
||||
configure_stream("VFR_HUD", 20.0f);
|
||||
configure_stream("EXTENDED_SYS_STATE", 2.0f);
|
||||
configure_stream("HIGHRES_IMU", 50.0f);
|
||||
configure_stream("ATTITUDE", 100.0f);
|
||||
configure_stream("ACTUATOR_CONTROL_TARGET0", 30.0f);
|
||||
configure_stream("RC_CHANNELS", 10.0f);
|
||||
configure_stream("SERVO_OUTPUT_RAW_0", 20.0f);
|
||||
configure_stream("SERVO_OUTPUT_RAW_1", 20.0f);
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
|
||||
configure_stream("LOCAL_POSITION_NED", 30.0f);
|
||||
configure_stream("MANUAL_CONTROL", 5.0f);
|
||||
configure_stream("HIGHRES_IMU", 50.0f);
|
||||
configure_stream("GPS_RAW_INT", 10.0f);
|
||||
configure_stream("CAMERA_TRIGGER", 500.0f);
|
||||
configure_stream("EXTENDED_SYS_STATE", 2.0f);
|
||||
configure_stream("ALTITUDE", 10.0f);
|
||||
configure_stream("GPS_RAW_INT", 10.0f);
|
||||
configure_stream("ADSB_VEHICLE", 20.0f);
|
||||
configure_stream("DISTANCE_SENSOR", 10.0f);
|
||||
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
|
||||
configure_stream("VISION_POSITION_NED", 10.0f);
|
||||
configure_stream("ESTIMATOR_STATUS", 5.0f);
|
||||
configure_stream("ADSB_VEHICLE", 20.0f);
|
||||
configure_stream("NAV_CONTROLLER_OUTPUT", 10.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 10.0f);
|
||||
configure_stream("LOCAL_POSITION_NED", 30.0f);
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 8.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("NAMED_VALUE_FLOAT", 50.0f);
|
||||
configure_stream("VFR_HUD", 20.0f);
|
||||
configure_stream("WIND", 10.0f);
|
||||
configure_stream("CAMERA_TRIGGER", 500.0f);
|
||||
configure_stream("MISSION_ITEM", 50.0f);
|
||||
configure_stream("ACTUATOR_CONTROL_TARGET0", 30.0f);
|
||||
configure_stream("MANUAL_CONTROL", 5.0f);
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user