mirror of https://github.com/ArduPilot/ardupilot
Rover: correct compilation if rangefinder disabled
This commit is contained in:
parent
2ac9cc94c6
commit
988d917384
|
@ -149,6 +149,7 @@ int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const
|
|||
return rover.g2.motors.get_throttle();
|
||||
}
|
||||
|
||||
#if AP_RANGEFINDER_ENABLED
|
||||
void GCS_MAVLINK_Rover::send_rangefinder() const
|
||||
{
|
||||
float distance = 0;
|
||||
|
@ -178,6 +179,7 @@ void GCS_MAVLINK_Rover::send_rangefinder() const
|
|||
distance,
|
||||
voltage);
|
||||
}
|
||||
#endif // AP_RANGEFINDER_ENABLED
|
||||
|
||||
/*
|
||||
send PID tuning message
|
||||
|
|
|
@ -58,7 +58,9 @@ private:
|
|||
|
||||
int16_t vfr_hud_throttle() const override;
|
||||
|
||||
#if AP_RANGEFINDER_ENABLED
|
||||
void send_rangefinder() const override;
|
||||
#endif
|
||||
|
||||
#if HAL_HIGH_LATENCY2_ENABLED
|
||||
uint8_t high_latency_tgt_heading() const override;
|
||||
|
|
Loading…
Reference in New Issue