AC_WPNav: use singleton for getting AC_Avoid instance
This commit is contained in:
parent
6047ef105e
commit
f2163fbc24
@ -305,6 +305,7 @@ void AC_Loiter::calc_desired_velocity(float nav_dt)
|
||||
|
||||
// Limit the velocity to prevent fence violations
|
||||
// TODO: We need to also limit the _desired_accel
|
||||
AC_Avoid *_avoid = AP::ac_avoid();
|
||||
if (_avoid != nullptr) {
|
||||
_avoid->adjust_velocity(_pos_control.get_pos_xy_p().kP(), _accel_cmss, desired_vel, nav_dt);
|
||||
}
|
||||
|
@ -16,9 +16,6 @@ public:
|
||||
/// Constructor
|
||||
AC_Loiter(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);
|
||||
|
||||
/// provide pointer to avoidance library
|
||||
void set_avoidance(AC_Avoid* avoid_ptr) { _avoid = avoid_ptr; }
|
||||
|
||||
/// init_target to a position in cm from ekf origin
|
||||
void init_target(const Vector3f& position);
|
||||
|
||||
@ -73,7 +70,6 @@ protected:
|
||||
const AP_AHRS_View& _ahrs;
|
||||
AC_PosControl& _pos_control;
|
||||
const AC_AttitudeControl& _attitude_control;
|
||||
AC_Avoid *_avoid = nullptr;
|
||||
|
||||
// parameters
|
||||
AP_Float _angle_max; // maximum pilot commanded angle in degrees. Set to zero for 2/3 Angle Max
|
||||
|
@ -51,9 +51,6 @@ public:
|
||||
/// provide pointer to terrain database
|
||||
void set_terrain(AP_Terrain* terrain_ptr) { _terrain = terrain_ptr; }
|
||||
|
||||
/// provide pointer to avoidance library
|
||||
void set_avoidance(AC_Avoid* avoid_ptr) { _avoid = avoid_ptr; }
|
||||
|
||||
/// provide rangefinder altitude
|
||||
void set_rangefinder_alt(bool use, bool healthy, float alt_cm) { _rangefinder_available = use; _rangefinder_healthy = healthy; _rangefinder_alt_cm = alt_cm; }
|
||||
|
||||
@ -285,7 +282,6 @@ protected:
|
||||
AC_PosControl& _pos_control;
|
||||
const AC_AttitudeControl& _attitude_control;
|
||||
AP_Terrain *_terrain;
|
||||
AC_Avoid *_avoid;
|
||||
|
||||
// parameters
|
||||
AP_Float _wp_speed_cms; // default maximum horizontal speed in cm/s during missions
|
||||
|
Loading…
Reference in New Issue
Block a user