|
|
|
@ -1644,6 +1644,7 @@ Mavlink::task_main(int argc, char *argv[])
@@ -1644,6 +1644,7 @@ Mavlink::task_main(int argc, char *argv[])
|
|
|
|
|
configure_stream("GPS_RAW_INT", 1.0f); |
|
|
|
|
configure_stream("GLOBAL_POSITION_INT", 3.0f); |
|
|
|
|
configure_stream("LOCAL_POSITION_NED", 3.0f); |
|
|
|
|
configure_stream("NAMED_VALUE_FLOAT", 2.0f); |
|
|
|
|
configure_stream("RC_CHANNELS", 1.0f); |
|
|
|
|
configure_stream("SERVO_OUTPUT_RAW_0", 1.0f); |
|
|
|
|
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f); |
|
|
|
@ -1660,6 +1661,7 @@ Mavlink::task_main(int argc, char *argv[])
@@ -1660,6 +1661,7 @@ Mavlink::task_main(int argc, char *argv[])
|
|
|
|
|
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); |
|
|
|
@ -1701,7 +1703,7 @@ Mavlink::task_main(int argc, char *argv[])
@@ -1701,7 +1703,7 @@ Mavlink::task_main(int argc, char *argv[])
|
|
|
|
|
configure_stream("ATTITUDE_TARGET", 8.0f); |
|
|
|
|
configure_stream("PARAM_VALUE", 300.0f); |
|
|
|
|
configure_stream("MISSION_ITEM", 50.0f); |
|
|
|
|
configure_stream("NAMED_VALUE_FLOAT", 10.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); |
|
|
|
|