MAVLink app: Fix VTOL reporting and prevent mission reached spam

The VTOL status reporting and the mission status reporting were both suboptimal. VTOL was too slow, mission reporting too fast
This commit is contained in:
Lorenz Meier
2016-12-25 17:07:34 +01:00
parent 171ccd1203
commit 737e18dccb
3 changed files with 8 additions and 3 deletions

View File

@@ -2011,8 +2011,8 @@ Mavlink::task_main(int argc, char *argv[])
break;
case MAVLINK_MODE_ONBOARD:
configure_stream("SYS_STATUS", 1.0f);
configure_stream("EXTENDED_SYS_STATE", 2.0f);
configure_stream("SYS_STATUS", 5.0f);
configure_stream("EXTENDED_SYS_STATE", 5.0f);
configure_stream("HIGHRES_IMU", 50.0f);
configure_stream("ATTITUDE", 250.0f);
configure_stream("RC_CHANNELS", 20.0f);