|
|
|
@ -1597,7 +1597,7 @@ Mavlink::task_main(int argc, char *argv[])
@@ -1597,7 +1597,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("RC_CHANNELS_RAW", 1.0f); |
|
|
|
|
configure_stream("RC_CHANNELS", 1.0f); |
|
|
|
|
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f); |
|
|
|
|
configure_stream("ATTITUDE_TARGET", 3.0f); |
|
|
|
|
configure_stream("DISTANCE_SENSOR", 0.5f); |
|
|
|
@ -1617,7 +1617,7 @@ Mavlink::task_main(int argc, char *argv[])
@@ -1617,7 +1617,7 @@ Mavlink::task_main(int argc, char *argv[])
|
|
|
|
|
configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f); |
|
|
|
|
configure_stream("DISTANCE_SENSOR", 10.0f); |
|
|
|
|
configure_stream("OPTICAL_FLOW_RAD", 10.0f); |
|
|
|
|
configure_stream("RC_CHANNELS_RAW", 20.0f); |
|
|
|
|
configure_stream("RC_CHANNELS", 20.0f); |
|
|
|
|
configure_stream("VFR_HUD", 10.0f); |
|
|
|
|
configure_stream("SYSTEM_TIME", 1.0f); |
|
|
|
|
configure_stream("TIMESYNC", 10.0f); |
|
|
|
@ -1634,7 +1634,7 @@ Mavlink::task_main(int argc, char *argv[])
@@ -1634,7 +1634,7 @@ Mavlink::task_main(int argc, char *argv[])
|
|
|
|
|
configure_stream("ATTITUDE_TARGET", 10.0f); |
|
|
|
|
configure_stream("BATTERY_STATUS", 1.0f); |
|
|
|
|
configure_stream("SYSTEM_TIME", 1.0f); |
|
|
|
|
configure_stream("RC_CHANNELS_RAW", 5.0f); |
|
|
|
|
configure_stream("RC_CHANNELS", 5.0f); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|