AP_Proximity: remove unused get_horizontal_distance
This commit is contained in:
parent
52c21d6ea0
commit
80d8889d14
@ -347,24 +347,6 @@ void AP_Proximity::detect_instance(uint8_t instance)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// get distance in meters in a particular direction in degrees (0 is forward, clockwise)
|
|
||||||
// returns true on successful read and places distance in distance
|
|
||||||
bool AP_Proximity::get_horizontal_distance(uint8_t instance, float angle_deg, float &distance) const
|
|
||||||
{
|
|
||||||
if (!valid_instance(instance)) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
// get distance from backend
|
|
||||||
return drivers[instance]->get_horizontal_distance(angle_deg, distance);
|
|
||||||
}
|
|
||||||
|
|
||||||
// get distance in meters in a particular direction in degrees (0 is forward, clockwise)
|
|
||||||
// returns true on successful read and places distance in distance
|
|
||||||
bool AP_Proximity::get_horizontal_distance(float angle_deg, float &distance) const
|
|
||||||
{
|
|
||||||
return get_horizontal_distance(primary_instance, angle_deg, distance);
|
|
||||||
}
|
|
||||||
|
|
||||||
// get distances in 8 directions. used for sending distances to ground station
|
// get distances in 8 directions. used for sending distances to ground station
|
||||||
bool AP_Proximity::get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const
|
bool AP_Proximity::get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const
|
||||||
{
|
{
|
||||||
|
@ -85,11 +85,6 @@ public:
|
|||||||
return num_instances;
|
return num_instances;
|
||||||
}
|
}
|
||||||
|
|
||||||
// get distance in meters in a particular direction in degrees (0 is forward, clockwise)
|
|
||||||
// returns true on successful read and places distance in distance
|
|
||||||
bool get_horizontal_distance(uint8_t instance, float angle_deg, float &distance) const;
|
|
||||||
bool get_horizontal_distance(float angle_deg, float &distance) const;
|
|
||||||
|
|
||||||
// get distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station
|
// get distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station
|
||||||
bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const;
|
bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const;
|
||||||
|
|
||||||
|
@ -33,17 +33,6 @@ AP_Proximity_Backend::AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity
|
|||||||
init_boundary();
|
init_boundary();
|
||||||
}
|
}
|
||||||
|
|
||||||
// get distance in meters in a particular direction in degrees (0 is forward, angles increase in the clockwise direction)
|
|
||||||
bool AP_Proximity_Backend::get_horizontal_distance(float angle_deg, float &distance) const
|
|
||||||
{
|
|
||||||
const uint8_t sector = convert_angle_to_sector(angle_deg);
|
|
||||||
if (_distance_valid[sector]) {
|
|
||||||
distance = _distance[sector];
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// get distance and angle to closest object (used for pre-arm check)
|
// get distance and angle to closest object (used for pre-arm check)
|
||||||
// returns true on success, false if no valid readings
|
// returns true on success, false if no valid readings
|
||||||
bool AP_Proximity_Backend::get_closest_object(float& angle_deg, float &distance) const
|
bool AP_Proximity_Backend::get_closest_object(float& angle_deg, float &distance) const
|
||||||
|
@ -47,10 +47,6 @@ public:
|
|||||||
// handle mavlink DISTANCE_SENSOR messages
|
// handle mavlink DISTANCE_SENSOR messages
|
||||||
virtual void handle_msg(const mavlink_message_t &msg) {}
|
virtual void handle_msg(const mavlink_message_t &msg) {}
|
||||||
|
|
||||||
// get distance in meters in a particular direction in degrees (0 is forward, clockwise)
|
|
||||||
// returns true on successful read and places distance in distance
|
|
||||||
bool get_horizontal_distance(float angle_deg, float &distance) const;
|
|
||||||
|
|
||||||
// get boundary points around vehicle for use by avoidance
|
// get boundary points around vehicle for use by avoidance
|
||||||
// returns nullptr and sets num_points to zero if no boundary can be returned
|
// returns nullptr and sets num_points to zero if no boundary can be returned
|
||||||
const Vector2f* get_boundary_points(uint16_t& num_points) const;
|
const Vector2f* get_boundary_points(uint16_t& num_points) const;
|
||||||
|
Loading…
Reference in New Issue
Block a user