mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-29 02:14:08 +08:00
mavlink: RC_CHANNELS_RAW added to default streams set
This commit is contained in:
parent
8425b9bef2
commit
39b1f7244c
@ -1731,6 +1731,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
configure_stream("GPS_RAW_INT", 1.0f * rate_mult);
|
||||
configure_stream("GLOBAL_POSITION_INT", 3.0f * rate_mult);
|
||||
configure_stream("LOCAL_POSITION_NED", 3.0f * rate_mult);
|
||||
configure_stream("RC_CHANNELS_RAW", 1.0f * rate_mult);
|
||||
break;
|
||||
|
||||
case MODE_HIL:
|
||||
@ -1743,6 +1744,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
configure_stream("GPS_RAW_INT", 1.0f * rate_mult);
|
||||
configure_stream("GLOBAL_POSITION_INT", 1.0f * rate_mult);
|
||||
configure_stream("LOCAL_POSITION_NED", 1.0f * rate_mult);
|
||||
configure_stream("RC_CHANNELS_RAW", 1.0f * rate_mult);
|
||||
configure_stream("HIL_CONTROLS", 15.0f * rate_mult);
|
||||
break;
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user