SITL: allow disabling MAVLink simstate messages

This commit is contained in:
Iampete1 2024-04-02 03:13:32 +01:00 committed by Andrew Tridgell
parent 64b57de559
commit 30fdae880f
2 changed files with 15 additions and 0 deletions

View File

@ -1195,6 +1195,11 @@ const Location post_origin {
/* report SITL state via MAVLink SIMSTATE*/
void SIM::simstate_send(mavlink_channel_t chan) const
{
if (stop_MAVLink_sim_state) {
// Sim only MAVLink messages disabled to give more relaistic data rates
return;
}
float yaw;
// convert to same conventions as DCM
@ -1220,6 +1225,11 @@ void SIM::simstate_send(mavlink_channel_t chan) const
/* report SITL state via MAVLink SIM_STATE */
void SIM::sim_state_send(mavlink_channel_t chan) const
{
if (stop_MAVLink_sim_state) {
// Sim only MAVLink messages disabled to give more relaistic data rates
return;
}
// convert to same conventions as DCM
float yaw = state.yawDeg;
if (yaw > 180) {

View File

@ -543,6 +543,11 @@ public:
AP_Int16 osd_rows;
AP_Int16 osd_columns;
#endif
// Allow inhibiting of SITL only sim state messages over MAVLink
// This gives more realistic data rates for testing links
void set_stop_MAVLink_sim_state() { stop_MAVLink_sim_state = true; }
bool stop_MAVLink_sim_state;
};
} // namespace SITL