Browse Source

AP_Follow: use ahrs singleton

master
Peter Barker 7 years ago committed by Francisco Ferreira
parent
commit
e33ce5eb48
  1. 5
      libraries/AP_Follow/AP_Follow.cpp
  2. 5
      libraries/AP_Follow/AP_Follow.h

5
libraries/AP_Follow/AP_Follow.cpp

@ -114,8 +114,7 @@ const AP_Param::GroupInfo AP_Follow::var_info[] = { @@ -114,8 +114,7 @@ const AP_Param::GroupInfo AP_Follow::var_info[] = {
constructor is not called until detect() returns true, so we
already know that we should setup the proximity sensor
*/
AP_Follow::AP_Follow(const AP_AHRS &ahrs) :
_ahrs(ahrs),
AP_Follow::AP_Follow() :
_p_pos(AP_FOLLOW_POS_P_DEFAULT)
{
AP_Param::setup_object_defaults(this, var_info);
@ -158,7 +157,7 @@ bool AP_Follow::get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_w @@ -158,7 +157,7 @@ bool AP_Follow::get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_w
{
// get our location
Location current_loc;
if (!_ahrs.get_position(current_loc)) {
if (!AP::ahrs().get_position(current_loc)) {
return false;
}

5
libraries/AP_Follow/AP_Follow.h

@ -36,7 +36,7 @@ public: @@ -36,7 +36,7 @@ public:
};
// constructor
AP_Follow(const AP_AHRS &ahrs);
AP_Follow();
// set which target to follow
void set_target_sysid(uint8_t sysid) { _sysid = sysid; }
@ -87,9 +87,6 @@ private: @@ -87,9 +87,6 @@ private:
// get offsets in meters in NED frame
bool get_offsets_ned(Vector3f &offsets) const;
// references
const AP_AHRS &_ahrs;
// parameters
AP_Int8 _enabled; // 1 if this subsystem is enabled
AP_Int16 _sysid; // target's mavlink system id (0 to use first sysid seen)

Loading…
Cancel
Save