mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: stop streaming trying SIM_STATE messages outside sim
This commit is contained in:
parent
261bc4f884
commit
c531d81cb3
|
@ -531,7 +531,9 @@ static const ap_message STREAM_RC_CHANNELS_msgs[] = {
|
||||||
};
|
};
|
||||||
static const ap_message STREAM_EXTRA1_msgs[] = {
|
static const ap_message STREAM_EXTRA1_msgs[] = {
|
||||||
MSG_ATTITUDE,
|
MSG_ATTITUDE,
|
||||||
|
#if AP_SIM_ENABLED
|
||||||
MSG_SIMSTATE,
|
MSG_SIMSTATE,
|
||||||
|
#endif
|
||||||
MSG_AHRS2,
|
MSG_AHRS2,
|
||||||
MSG_PID_TUNING // Up to four PID_TUNING messages are sent, depending on GCS_PID_MASK parameter
|
MSG_PID_TUNING // Up to four PID_TUNING messages are sent, depending on GCS_PID_MASK parameter
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue