mirror of https://github.com/ArduPilot/ardupilot
Rover: fix compiler warning, uninitialized variables in GCS msg
This commit is contained in:
parent
e6e45eda97
commit
2d09b3fcef
|
@ -149,8 +149,8 @@ int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const
|
||||||
|
|
||||||
void GCS_MAVLINK_Rover::send_rangefinder() const
|
void GCS_MAVLINK_Rover::send_rangefinder() const
|
||||||
{
|
{
|
||||||
float distance;
|
float distance = 0;
|
||||||
float voltage;
|
float voltage = 0;
|
||||||
bool got_one = false;
|
bool got_one = false;
|
||||||
|
|
||||||
// report smaller distance of all rangefinders
|
// report smaller distance of all rangefinders
|
||||||
|
|
Loading…
Reference in New Issue