Skip to content

Commit

Permalink
AP_Proximity: rename get_distances to get_horizontal_distances
Browse files Browse the repository at this point in the history
Also fix existing bug in return
  • Loading branch information
rmackay9 committed Apr 20, 2017
1 parent 09e3d6b commit 3ad5c37
Show file tree
Hide file tree
Showing 4 changed files with 21 additions and 21 deletions.
20 changes: 10 additions & 10 deletions libraries/AP_Proximity/AP_Proximity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -323,6 +323,16 @@ bool AP_Proximity::get_horizontal_distance(float angle_deg, float &distance) con
return get_horizontal_distance(primary_instance, angle_deg, distance);
}

// 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
{
if ((drivers[primary_instance] == nullptr) || (_type[primary_instance] == Proximity_Type_None)) {
return false;
}
// get distances from backend
return drivers[primary_instance]->get_horizontal_distances(prx_dist_array);
}

// get boundary points around vehicle for use by avoidance
// returns nullptr and sets num_points to zero if no boundary can be returned
const Vector2f* AP_Proximity::get_boundary_points(uint8_t instance, uint16_t& num_points) const
Expand Down Expand Up @@ -372,16 +382,6 @@ bool AP_Proximity::get_object_angle_and_distance(uint8_t object_number, float& a
return drivers[primary_instance]->get_object_angle_and_distance(object_number, angle_deg, distance);
}

// get distances in 8 directions. used for sending distances to ground station
bool AP_Proximity::get_distances(Proximity_Distance_Array &prx_dist_array) const
{
if ((drivers[primary_instance] == nullptr) || (_type[primary_instance] == Proximity_Type_None)) {
return 0.0f;
}
// get distances from backend
return drivers[primary_instance]->get_distances(prx_dist_array);
}

// get maximum and minimum distances (in meters) of primary sensor
float AP_Proximity::distance_max() const
{
Expand Down
18 changes: 9 additions & 9 deletions libraries/AP_Proximity/AP_Proximity.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,12 @@ class AP_Proximity
Proximity_Good
};

// structure holding distances in 8 directions. used for sending distances to ground station
struct Proximity_Distance_Array {
uint8_t orientation[8]; // orientation (i.e. rough direction) of the distance (see MAV_SENSOR_ORIENTATION)
float distance[8]; // distance in meters
};

// detect and initialise any available proximity sensors
void init(void);

Expand Down Expand Up @@ -78,6 +84,9 @@ class AP_Proximity
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 8 directions. used for sending distances to ground station
bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const;

// get boundary points around vehicle for use by avoidance
// returns nullptr and sets num_points to zero if no boundary can be returned
const Vector2f* get_boundary_points(uint8_t instance, uint16_t& num_points) const;
Expand All @@ -91,15 +100,6 @@ class AP_Proximity
uint8_t get_object_count() const;
bool get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const;

// structure holding distances in 8 directions
struct Proximity_Distance_Array {
uint8_t orientation[8]; // orientation (i.e. rough direction) of the distance (see MAV_SENSOR_ORIENTATION)
float distance[8]; // distance in meters
};

// get distances in 8 directions. used for sending distances to ground station
bool get_distances(Proximity_Distance_Array &prx_dist_array) const;

// get maximum and minimum distances (in meters) of primary sensor
float distance_max() const;
float distance_min() const;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Proximity/AP_Proximity_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ bool AP_Proximity_Backend::get_object_angle_and_distance(uint8_t object_number,
}

// get distances in 8 directions. used for sending distances to ground station
bool AP_Proximity_Backend::get_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const
bool AP_Proximity_Backend::get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const
{
// exit immediately if we have no good ranges
bool valid_distances = false;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Proximity/AP_Proximity_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class AP_Proximity_Backend
bool get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const;

// get distances in 8 directions. used for sending distances to ground station
bool get_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const;
bool get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const;

protected:

Expand Down

0 comments on commit 3ad5c37

Please sign in to comment.