mirror of https://github.com/ArduPilot/ardupilot
Sub: SET_POSITION_TARGET_LOCAL_NED above origin
This commit is contained in:
parent
0e18bd450d
commit
2836ec4ae0
|
@ -614,9 +614,6 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg)
|
|||
packet.coordinate_frame == MAV_FRAME_BODY_NED ||
|
||||
packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
|
||||
pos_vector += sub.inertial_nav.get_position_neu_cm();
|
||||
} else {
|
||||
// convert from alt-above-home to alt-above-ekf-origin
|
||||
pos_vector.z = sub.pv_alt_above_origin(pos_vector.z);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue