MAVLink: Send vibration status message

This commit is contained in:
Lorenz Meier
2016-02-25 15:57:53 +01:00
parent 29d417beb7
commit a516450868
2 changed files with 68 additions and 0 deletions

View File

@@ -1770,6 +1770,7 @@ Mavlink::task_main(int argc, char *argv[])
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);
break;
case MAVLINK_MODE_ONBOARD:
@@ -1799,6 +1800,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("ALTITUDE", 10.0f);
configure_stream("VISION_POSITION_NED", 10.0f);
configure_stream("NAMED_VALUE_FLOAT", 10.0f);
configure_stream("ESTIMATOR_STATUS", 1.0f);
break;
case MAVLINK_MODE_OSD:
@@ -1814,6 +1816,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream("EXTENDED_SYS_STATE", 1.0f);
configure_stream("ALTITUDE", 1.0f);
configure_stream("ESTIMATOR_STATUS", 1.0f);
break;
case MAVLINK_MODE_MAGIC:
@@ -1847,6 +1850,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("ALTITUDE", 10.0f);
configure_stream("VISION_POSITION_NED", 10.0f);
configure_stream("NAMED_VALUE_FLOAT", 50.0f);
configure_stream("ESTIMATOR_STATUS", 5.0f);
default:
break;
}