Browse Source

AP_Follow: params always use set method

apm_2208
Iampete1 3 years ago committed by Peter Hall
parent
commit
0d32e6cbf3
  1. 2
      libraries/AP_Follow/AP_Follow.cpp
  2. 2
      libraries/AP_Follow/AP_Follow.h

2
libraries/AP_Follow/AP_Follow.cpp

@ -446,7 +446,7 @@ void AP_Follow::init_offsets_if_required(const Vector3f &dist_vec_ned) @@ -446,7 +446,7 @@ void AP_Follow::init_offsets_if_required(const Vector3f &dist_vec_ned)
// initialise offset in NED frame
_offset = -dist_vec_ned;
// ensure offset_type used matches frame of offsets saved
_offset_type = AP_FOLLOW_OFFSET_TYPE_NED;
_offset_type.set(AP_FOLLOW_OFFSET_TYPE_NED);
gcs().send_text(MAV_SEVERITY_INFO, "N-E-D follow offset loaded");
}
}

2
libraries/AP_Follow/AP_Follow.h

@ -48,7 +48,7 @@ public: @@ -48,7 +48,7 @@ public:
bool enabled() const { return _enabled; }
// set which target to follow
void set_target_sysid(uint8_t sysid) { _sysid = sysid; }
void set_target_sysid(uint8_t sysid) { _sysid.set(sysid); }
// restore offsets to zero if necessary, should be called when vehicle exits follow mode
void clear_offsets_if_required();

Loading…
Cancel
Save