mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Follow: fix initialisation of offsets
This commit is contained in:
parent
30f369c3b4
commit
242e0a7c0a
@ -329,11 +329,11 @@ bool AP_Follow::get_velocity_ned(Vector3f &vel_ned, float dt) const
|
||||
return true;
|
||||
}
|
||||
|
||||
// initialise offsets to provided distance vector (in meters in NED frame) if required
|
||||
// initialise offsets to provided distance vector to other vehicle (in meters in NED frame) if required
|
||||
void AP_Follow::init_offsets_if_required(const Vector3f &dist_vec_ned)
|
||||
{
|
||||
if (_offset.get().is_zero()) {
|
||||
_offset = dist_vec_ned;
|
||||
_offset = -dist_vec_ned;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -81,7 +81,7 @@ private:
|
||||
// get velocity estimate in m/s in NED frame using dt since last update
|
||||
bool get_velocity_ned(Vector3f &vel_ned, float dt) const;
|
||||
|
||||
// initialise offsets to provided distance vector (in meters in NED frame) if required
|
||||
// initialise offsets to provided distance vector to other vehicle (in meters in NED frame) if required
|
||||
void init_offsets_if_required(const Vector3f &dist_vec_ned);
|
||||
|
||||
// get offsets in meters in NED frame
|
||||
|
Loading…
Reference in New Issue
Block a user