diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 34f69e97a7a7a9..22b8697bfd86ec 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -1190,6 +1190,7 @@ void AC_PosControl::init_offsets_z() bool AC_PosControl::set_posvelaccel_offset(const Vector3f &pos_offset_NED, const Vector3f &vel_offset_NED, const Vector3f &accel_offset_NED) { set_posvelaccel_offset_target_xy_cm(pos_offset_NED.topostype().xy() * 100.0, vel_offset_NED.xy() * 100.0, accel_offset_NED.xy() * 100.0); + set_posvelaccel_offset_target_z_cm(-pos_offset_NED.topostype().z * 100.0, -vel_offset_NED.z * 100, -accel_offset_NED.z * 100.0); return true; } @@ -1197,9 +1198,12 @@ bool AC_PosControl::set_posvelaccel_offset(const Vector3f &pos_offset_NED, const // units are m and m/s in NED frame bool AC_PosControl::get_posvelaccel_offset(Vector3f &pos_offset_NED, Vector3f &vel_offset_NED, Vector3f &accel_offset_NED) { - pos_offset_NED = _pos_offset_target.tofloat() * 0.01; - vel_offset_NED = _vel_offset_target * 0.01; - accel_offset_NED = _accel_offset_target * 0.01; + pos_offset_NED.xy() = _pos_offset_target.xy().tofloat() * 0.01; + pos_offset_NED.z = -_pos_offset_target.z * 0.01; + vel_offset_NED.xy() = _vel_offset_target.xy() * 0.01; + vel_offset_NED.z = -_vel_offset_target.z * 0.01; + accel_offset_NED.xy() = _accel_offset_target.xy() * 0.01; + accel_offset_NED.z = -_accel_offset_target.z * 0.01; return true; } #endif