mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: do not send MSG_RPM if RPM not enabled
This commit is contained in:
parent
5c75ad282f
commit
e2fd4fc782
@ -2,6 +2,7 @@
|
|||||||
|
|
||||||
#include "GCS_Mavlink.h"
|
#include "GCS_Mavlink.h"
|
||||||
|
|
||||||
|
#include <AP_RPM/AP_RPM_config.h>
|
||||||
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
|
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
|
||||||
|
|
||||||
MAV_TYPE GCS_Rover::frame_type() const
|
MAV_TYPE GCS_Rover::frame_type() const
|
||||||
@ -564,7 +565,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
|||||||
MSG_MAG_CAL_PROGRESS,
|
MSG_MAG_CAL_PROGRESS,
|
||||||
MSG_EKF_STATUS_REPORT,
|
MSG_EKF_STATUS_REPORT,
|
||||||
MSG_VIBRATION,
|
MSG_VIBRATION,
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
MSG_RPM,
|
MSG_RPM,
|
||||||
|
#endif
|
||||||
MSG_WHEEL_DISTANCE,
|
MSG_WHEEL_DISTANCE,
|
||||||
MSG_ESC_TELEMETRY,
|
MSG_ESC_TELEMETRY,
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user