Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GCS_Common: LOCAL_POSITION_NED sent using offset from origin (instead of offset from home) #15169

Merged
merged 3 commits into from
Sep 1, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 0 additions & 10 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1101,16 +1101,6 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
packet.coordinate_frame == MAV_FRAME_BODY_NED ||
packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
pos_vector += copter.inertial_nav.get_position();
} else {
// convert from alt-above-home to alt-above-ekf-origin
if (!AP::ahrs().home_is_set()) {
break;
}
Location origin;
pos_vector.z += AP::ahrs().get_home().alt;
if (copter.ahrs.get_origin(origin)) {
pos_vector.z -= origin.alt;
}
}
}

Expand Down
11 changes: 9 additions & 2 deletions Rover/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -766,6 +766,12 @@ void GCS_MAVLINK_Rover::handleMessage(const mavlink_message_t &msg)
break;
}

// need ekf origin
Location ekf_origin;
if (!rover.ahrs.get_origin(ekf_origin)) {
break;
}

// check for supported coordinate frames
if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&
packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&
Expand Down Expand Up @@ -799,9 +805,10 @@ void GCS_MAVLINK_Rover::handleMessage(const mavlink_message_t &msg)
target_loc.offset(packet.x, packet.y);
break;

case MAV_FRAME_LOCAL_NED:
default:
// MAV_FRAME_LOCAL_NED interpret as an offset from home
target_loc = rover.ahrs.get_home();
// MAV_FRAME_LOCAL_NED is interpreted as an offset from EKF origin
target_loc = ekf_origin;
target_loc.offset(packet.x, packet.y);
break;
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2271,7 +2271,7 @@ void GCS_MAVLINK::send_local_position() const
const AP_AHRS &ahrs = AP::ahrs();

Vector3f local_position, velocity;
if (!ahrs.get_relative_position_NED_home(local_position) ||
if (!ahrs.get_relative_position_NED_origin(local_position) ||
!ahrs.get_velocity_NED(velocity)) {
// we don't know the position and velocity
return;
Expand Down