Browse Source

AP_Proximity_Boundary_3D:correction of miswriting

apm_2208
xianglunkai 3 years ago committed by Randy Mackay
parent
commit
c853694f7a
  1. 2
      libraries/AP_Proximity/AP_Proximity_Boundary_3D.h

2
libraries/AP_Proximity/AP_Proximity_Boundary_3D.h

@ -178,7 +178,7 @@ public: @@ -178,7 +178,7 @@ public:
// add a distance to the temp boundary if it is shorter than any other provided distance since the last time the boundary was reset
// pitch and yaw are in degrees, distance is in meters
void add_distance(const AP_Proximity_Boundary_3D::Face &face, float pitch, float yaw, float distance);
void add_distance(const AP_Proximity_Boundary_3D::Face &face, float yaw, float distance) { add_distance(face, 0.0f, PID_TUNING_YAW, distance); }
void add_distance(const AP_Proximity_Boundary_3D::Face &face, float yaw, float distance) { add_distance(face, 0.0f, yaw, distance); }
// fill the original 3D boundary with the contents of this temporary boundary
void update_3D_boundary(AP_Proximity_Boundary_3D &boundary);

Loading…
Cancel
Save