forked from Archive/PX4-Autopilot
mavlink_main: add ESC_INFO & ESC_STATUS to onboard_lowbandwith configuration
Signed-off-by: Claudio Micheli <claudio@auterion.com>
This commit is contained in:
parent
a93f8dade4
commit
a6d88cad18
|
@ -1819,6 +1819,8 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
|||
configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f);
|
||||
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f);
|
||||
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f);
|
||||
configure_stream_local("ESC_INFO", 1.0f);
|
||||
configure_stream_local("ESC_STATUS", 5.0f);
|
||||
|
||||
configure_stream_local("ADSB_VEHICLE", unlimited_rate);
|
||||
configure_stream_local("ATTITUDE_TARGET", 2.0f);
|
||||
|
|
Loading…
Reference in New Issue