mirror of https://github.com/ArduPilot/ardupilot
Rover: only send airspeed when enabled
Avoids debug message spam about sending an unknown message.
This commit is contained in:
parent
b9dcd5949d
commit
95fb9bd533
|
@ -529,7 +529,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
|
|||
MSG_SCALED_PRESSURE,
|
||||
MSG_SCALED_PRESSURE2,
|
||||
MSG_SCALED_PRESSURE3,
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
MSG_AIRSPEED,
|
||||
#endif
|
||||
};
|
||||
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
MSG_SYS_STATUS,
|
||||
|
|
Loading…
Reference in New Issue