mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2025-12-10 00:28:42 -06:00
Rover: allow sending of rangefinder mavlink message to be compiled out
This commit is contained in:
parent
572f419d8e
commit
bddeac0de6
@ -155,7 +155,7 @@ int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const
|
||||
return rover.g2.motors.get_throttle();
|
||||
}
|
||||
|
||||
#if AP_RANGEFINDER_ENABLED
|
||||
#if AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED
|
||||
void GCS_MAVLINK_Rover::send_rangefinder() const
|
||||
{
|
||||
float distance = 0;
|
||||
@ -185,7 +185,9 @@ void GCS_MAVLINK_Rover::send_rangefinder() const
|
||||
distance,
|
||||
voltage);
|
||||
}
|
||||
#endif // AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED
|
||||
|
||||
#if AP_RANGEFINDER_ENABLED
|
||||
void GCS_MAVLINK_Rover::send_water_depth()
|
||||
{
|
||||
if (!HAVE_PAYLOAD_SPACE(chan, WATER_DEPTH)) {
|
||||
|
||||
@ -61,9 +61,11 @@ private:
|
||||
|
||||
int16_t vfr_hud_throttle() const override;
|
||||
|
||||
#if AP_RANGEFINDER_ENABLED
|
||||
#if AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED
|
||||
void send_rangefinder() const override;
|
||||
#endif // AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED
|
||||
|
||||
#if AP_RANGEFINDER_ENABLED
|
||||
// send WATER_DEPTH - metres and temperature
|
||||
void send_water_depth();
|
||||
// state variable for the last rangefinder we sent a WATER_DEPTH
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user