Skip to content

Commit 645defa

Browse files
committed
Rover: allow sending of rangefinder mavlink message to be compiled out
1 parent b4e657e commit 645defa

File tree

2 files changed

+6
-2
lines changed

2 files changed

+6
-2
lines changed

Rover/GCS_MAVLink_Rover.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -155,7 +155,7 @@ int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const
155155
return rover.g2.motors.get_throttle();
156156
}
157157

158-
#if AP_RANGEFINDER_ENABLED
158+
#if AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED
159159
void GCS_MAVLINK_Rover::send_rangefinder() const
160160
{
161161
float distance = 0;
@@ -185,7 +185,9 @@ void GCS_MAVLINK_Rover::send_rangefinder() const
185185
distance,
186186
voltage);
187187
}
188+
#endif // AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED
188189

190+
#if AP_RANGEFINDER_ENABLED
189191
void GCS_MAVLINK_Rover::send_water_depth()
190192
{
191193
if (!HAVE_PAYLOAD_SPACE(chan, WATER_DEPTH)) {

Rover/GCS_MAVLink_Rover.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,9 +57,11 @@ class GCS_MAVLINK_Rover : public GCS_MAVLINK
5757

5858
int16_t vfr_hud_throttle() const override;
5959

60-
#if AP_RANGEFINDER_ENABLED
60+
#if AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED
6161
void send_rangefinder() const override;
62+
#endif // AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED
6263

64+
#if AP_RANGEFINDER_ENABLED
6365
// send WATER_DEPTH - metres and temperature
6466
void send_water_depth();
6567
// state variable for the last rangefinder we sent a WATER_DEPTH

0 commit comments

Comments
 (0)