Browse Source

AP_Avoidance: Add missing const in member functions

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
c415-sdk
Patrick José Pereira 4 years ago committed by Andrew Tridgell
parent
commit
f6937babfa
  1. 2
      libraries/AP_Avoidance/AP_Avoidance.cpp
  2. 2
      libraries/AP_Avoidance/AP_Avoidance.h

2
libraries/AP_Avoidance/AP_Avoidance.cpp

@ -609,7 +609,7 @@ void AP_Avoidance::handle_msg(const mavlink_message_t &msg) @@ -609,7 +609,7 @@ void AP_Avoidance::handle_msg(const mavlink_message_t &msg)
}
// get unit vector away from the nearest obstacle
bool AP_Avoidance::get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu)
bool AP_Avoidance::get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu) const
{
if (obstacle == nullptr) {
// why where we called?!

2
libraries/AP_Avoidance/AP_Avoidance.h

@ -140,7 +140,7 @@ protected: @@ -140,7 +140,7 @@ protected:
bool get_destination_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &newdest_neu, const float wp_speed_xy, const float wp_speed_z, const uint8_t _minimum_avoid_height);
// get unit vector away from the nearest obstacle
bool get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu);
bool get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu) const;
// helper functions to calculate destination to get us away from obstacle
// Note: v1 is NED

Loading…
Cancel
Save