Browse Source

Alphabetize the mavlink stream lists in mavlink_main.cpp.

sbg
mcsauder 7 years ago committed by Daniel Agar
parent
commit
9122725052
  1. 153
      src/modules/mavlink/mavlink_main.cpp

153
src/modules/mavlink/mavlink_main.cpp

@ -2001,88 +2001,91 @@ Mavlink::task_main(int argc, char *argv[]) @@ -2001,88 +2001,91 @@ Mavlink::task_main(int argc, char *argv[])
switch (_mode) {
case MAVLINK_MODE_NORMAL:
configure_stream("SYS_STATUS", 1.0f);
configure_stream("EXTENDED_SYS_STATE", 1.0f);
configure_stream("HIGHRES_IMU", 1.5f);
configure_stream("ATTITUDE", 20.0f);
configure_stream("RC_CHANNELS", 5.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream("ALTITUDE", 1.0f);
configure_stream("GPS_RAW_INT", 1.0f);
configure_stream("ADSB_VEHICLE");
configure_stream("ALTITUDE", 1.0f);
configure_stream("ATTITUDE", 20.0f);
configure_stream("ATTITUDE_TARGET", 2.0f);
configure_stream("CAMERA_IMAGE_CAPTURED");
configure_stream("COLLISION");
configure_stream("DEBUG", 1.0f);
configure_stream("DEBUG_VECT", 1.0f);
configure_stream("DISTANCE_SENSOR", 0.5f);
configure_stream("OPTICAL_FLOW_RAD", 1.0f);
configure_stream("VISION_POSITION_ESTIMATE", 1.0f);
configure_stream("ESTIMATOR_STATUS", 0.5f);
configure_stream("NAV_CONTROLLER_OUTPUT", 1.5f);
configure_stream("EXTENDED_SYS_STATE", 1.0f);
configure_stream("GLOBAL_POSITION_INT", 5.0f);
configure_stream("GPS_RAW_INT", 1.0f);
configure_stream("HIGHRES_IMU", 1.5f);
configure_stream("HOME_POSITION", 0.5f);
configure_stream("LOCAL_POSITION_NED", 1.0f);
configure_stream("NAMED_VALUE_FLOAT", 1.0f);
configure_stream("NAV_CONTROLLER_OUTPUT", 1.5f);
configure_stream("OPTICAL_FLOW_RAD", 1.0f);
configure_stream("PING", 0.1f);
configure_stream("POSITION_TARGET_LOCAL_NED", 1.5f);
configure_stream("POSITION_TARGET_GLOBAL_INT", 1.5f);
configure_stream("ATTITUDE_TARGET", 2.0f);
configure_stream("HOME_POSITION", 0.5f);
configure_stream("NAMED_VALUE_FLOAT", 1.0f);
configure_stream("DEBUG", 1.0f);
configure_stream("DEBUG_VECT", 1.0f);
configure_stream("RC_CHANNELS", 5.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream("SYS_STATUS", 1.0f);
configure_stream("VFR_HUD", 4.0f);
configure_stream("VISION_POSITION_ESTIMATE", 1.0f);
configure_stream("WIND_COV", 1.0f);
configure_stream("CAMERA_IMAGE_CAPTURED");
configure_stream("PING", 0.1f);
break;
case MAVLINK_MODE_ONBOARD:
configure_stream("SYS_STATUS", 5.0f);
configure_stream("EXTENDED_SYS_STATE", 5.0f);
configure_stream("HIGHRES_IMU", 50.0f);
configure_stream("ACTUATOR_CONTROL_TARGET0", 10.0f);
configure_stream("ADSB_VEHICLE");
configure_stream("ALTITUDE", 10.0f);
configure_stream("ATTITUDE", 100.0f);
configure_stream("ATTITUDE_QUATERNION", 50.0f);
configure_stream("RC_CHANNELS", 20.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 10.0f);
configure_stream("ALTITUDE", 10.0f);
configure_stream("GPS_RAW_INT");
configure_stream("ADSB_VEHICLE");
configure_stream("ATTITUDE_TARGET", 10.0f);
configure_stream("CAMERA_CAPTURE", 2.0f);
configure_stream("CAMERA_IMAGE_CAPTURED");
configure_stream("CAMERA_TRIGGER");
configure_stream("COLLISION");
configure_stream("DEBUG", 10.0f);
configure_stream("DEBUG_VECT", 10.0f);
configure_stream("DISTANCE_SENSOR", 10.0f);
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
configure_stream("VISION_POSITION_ESTIMATE", 10.0f);
configure_stream("ESTIMATOR_STATUS", 1.0f);
configure_stream("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream("EXTENDED_SYS_STATE", 5.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("GPS_RAW_INT");
configure_stream("HIGHRES_IMU", 50.0f);
configure_stream("HOME_POSITION", 0.5f);
configure_stream("LOCAL_POSITION_NED", 30.0f);
configure_stream("NAMED_VALUE_FLOAT", 10.0f);
configure_stream("DEBUG", 10.0f);
configure_stream("DEBUG_VECT", 10.0f);
configure_stream("VFR_HUD", 10.0f);
configure_stream("WIND_COV", 10.0f);
configure_stream("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
configure_stream("PING", 1.0f);
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f);
configure_stream("RC_CHANNELS", 20.0f);
configure_stream("SCALED_IMU", 50.0f);
configure_stream("SCALED_IMU2", 50.0f);
configure_stream("SCALED_IMU3", 50.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 10.0f);
configure_stream("SYS_STATUS", 5.0f);
configure_stream("SYSTEM_TIME", 1.0f);
configure_stream("TIMESYNC", 10.0f);
configure_stream("CAMERA_CAPTURE", 2.0f);
configure_stream("CAMERA_TRIGGER");
configure_stream("CAMERA_IMAGE_CAPTURED");
configure_stream("ACTUATOR_CONTROL_TARGET0", 10.0f);
configure_stream("PING", 1.0f);
configure_stream("VFR_HUD", 10.0f);
configure_stream("VISION_POSITION_ESTIMATE", 10.0f);
configure_stream("WIND_COV", 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("RC_CHANNELS", 5.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream("ALTITUDE", 1.0f);
configure_stream("GPS_RAW_INT", 1.0f);
configure_stream("ATTITUDE", 25.0f);
configure_stream("ATTITUDE_TARGET", 10.0f);
configure_stream("ESTIMATOR_STATUS", 1.0f);
configure_stream("EXTENDED_SYS_STATE", 1.0f);
configure_stream("GLOBAL_POSITION_INT", 10.0f);
configure_stream("ATTITUDE_TARGET", 10.0f);
configure_stream("GPS_RAW_INT", 1.0f);
configure_stream("HOME_POSITION", 0.5f);
configure_stream("RC_CHANNELS", 5.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream("SYS_STATUS", 5.0f);
configure_stream("SYSTEM_TIME", 1.0f);
configure_stream("VFR_HUD", 25.0f);
configure_stream("WIND_COV", 2.0f);
configure_stream("SYSTEM_TIME", 1.0f);
break;
case MAVLINK_MODE_MAGIC:
@ -2091,40 +2094,40 @@ Mavlink::task_main(int argc, char *argv[]) @@ -2091,40 +2094,40 @@ 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("EXTENDED_SYS_STATE", 2.0f);
configure_stream("HIGHRES_IMU", 50.0f);
configure_stream("ACTUATOR_CONTROL_TARGET0", 30.0f);
configure_stream("ADSB_VEHICLE");
configure_stream("ALTITUDE", 10.0f);
configure_stream("ATTITUDE", 50.0f);
configure_stream("ATTITUDE_TARGET", 8.0f);
configure_stream("ATTITUDE_QUATERNION", 50.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("ALTITUDE", 10.0f);
configure_stream("GPS_RAW_INT");
configure_stream("ADSB_VEHICLE");
configure_stream("CAMERA_TRIGGER");
configure_stream("CAMERA_IMAGE_CAPTURED");
configure_stream("COLLISION");
configure_stream("DEBUG", 50.0f);
configure_stream("DEBUG_VECT", 50.0f);
configure_stream("DISTANCE_SENSOR", 10.0f);
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
configure_stream("VISION_POSITION_ESTIMATE", 10.0f);
configure_stream("GPS_RAW_INT");
configure_stream("ESTIMATOR_STATUS", 5.0f);
configure_stream("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream("EXTENDED_SYS_STATE", 2.0f);
configure_stream("GLOBAL_POSITION_INT", 10.0f);
configure_stream("HIGHRES_IMU", 50.0f);
configure_stream("HOME_POSITION", 0.5f);
configure_stream("LOCAL_POSITION_NED", 30.0f);
configure_stream("MANUAL_CONTROL", 5.0f);
configure_stream("NAMED_VALUE_FLOAT", 50.0f);
configure_stream("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
configure_stream("PING", 1.0f);
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.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("SYS_STATUS", 1.0f);
configure_stream("SYSTEM_TIME", 1.0f);
configure_stream("TIMESYNC", 10.0f);
configure_stream("ATTITUDE_TARGET", 8.0f);
configure_stream("HOME_POSITION", 0.5f);
configure_stream("NAMED_VALUE_FLOAT", 50.0f);
configure_stream("DEBUG", 50.0f);
configure_stream("DEBUG_VECT", 50.0f);
configure_stream("VFR_HUD", 20.0f);
configure_stream("VISION_POSITION_ESTIMATE", 10.0f);
configure_stream("WIND_COV", 10.0f);
configure_stream("CAMERA_TRIGGER");
configure_stream("CAMERA_IMAGE_CAPTURED");
configure_stream("ACTUATOR_CONTROL_TARGET0", 30.0f);
configure_stream("MANUAL_CONTROL", 5.0f);
configure_stream("PING", 1.0f);
break;
case MAVLINK_MODE_IRIDIUM:
@ -2132,15 +2135,15 @@ Mavlink::task_main(int argc, char *argv[]) @@ -2132,15 +2135,15 @@ Mavlink::task_main(int argc, char *argv[])
break;
case MAVLINK_MODE_MINIMAL:
configure_stream("SYS_STATUS", 0.1f);
configure_stream("EXTENDED_SYS_STATE", 0.1f);
configure_stream("ATTITUDE", 10.0f);
configure_stream("RC_CHANNELS", 0.5f);
configure_stream("ALTITUDE", 0.5f);
configure_stream("ATTITUDE", 10.0f);
configure_stream("EXTENDED_SYS_STATE", 0.1f);
configure_stream("GPS_RAW_INT", 0.5f);
configure_stream("GLOBAL_POSITION_INT", 5.0f);
configure_stream("HOME_POSITION", 0.1f);
configure_stream("NAMED_VALUE_FLOAT", 1.0f);
configure_stream("RC_CHANNELS", 0.5f);
configure_stream("SYS_STATUS", 0.1f);
configure_stream("VFR_HUD", 1.0f);
break;

Loading…
Cancel
Save