mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-08 18:52:46 +08:00
mavlink_main: raise rates of onboard mode
This commit is contained in:
@@ -1401,9 +1401,9 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
|
||||
case MAVLINK_MODE_ONBOARD:
|
||||
configure_stream("SYS_STATUS", 1.0f);
|
||||
configure_stream("ATTITUDE", 15.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 15.0f);
|
||||
configure_stream("CAMERA_CAPTURE", 1.0f);
|
||||
configure_stream("ATTITUDE", 50.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 50.0f);
|
||||
configure_stream("CAMERA_CAPTURE", 2.0f);
|
||||
break;
|
||||
|
||||
default:
|
||||
|
||||
Reference in New Issue
Block a user