mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: resolve compiler warning and format fix
This commit is contained in:
parent
2d4d99e836
commit
436f514142
|
@ -24,8 +24,8 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
AP_Proximity_RangeFinder::AP_Proximity_RangeFinder(AP_Proximity &_frontend,
|
||||
AP_Proximity::Proximity_State &_state) :
|
||||
_distance_upward(-1),
|
||||
AP_Proximity_Backend(_frontend, _state)
|
||||
AP_Proximity_Backend(_frontend, _state),
|
||||
_distance_upward(-1)
|
||||
{
|
||||
}
|
||||
|
||||
|
|
|
@ -17,7 +17,7 @@ public:
|
|||
|
||||
// get maximum and minimum distances (in meters) of sensor
|
||||
float distance_max() const { return _distance_max; }
|
||||
float distance_min() const { return _distance_min; };
|
||||
float distance_min() const { return _distance_min; }
|
||||
|
||||
// get distance upwards in meters. returns true on success
|
||||
bool get_upward_distance(float &distance) const;
|
||||
|
|
Loading…
Reference in New Issue