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

AP_AHRS: clarify frame of get_location_from_origin_offset #27259

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
2 changes: 1 addition & 1 deletion ArduCopter/mode_circle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ bool ModeCircle::init(bool ignore_checks)
if (copter.circle_nav->roi_at_center()) {
const Vector3p &pos { copter.circle_nav->get_center() };
Location circle_center;
if (!AP::ahrs().get_location_from_origin_offset(circle_center, pos * 0.01)) {
if (!AP::ahrs().get_location_from_origin_offset_NED(circle_center, pos * 0.01)) {
return false;
}
// point at the ground:
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3536,7 +3536,7 @@ bool AP_AHRS::get_velocity_NED(Vector3f &vec) const

// return location corresponding to vector relative to the
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The existing comment seems wrong.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Or at least confusing.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggestions for less-confusing words welcome :-)

// vehicle's origin
bool AP_AHRS::get_location_from_origin_offset(Location &loc, const Vector3p &offset_ned) const
bool AP_AHRS::get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const
{
if (!get_origin(loc)) {
return false;
Expand All @@ -3548,7 +3548,7 @@ bool AP_AHRS::get_location_from_origin_offset(Location &loc, const Vector3p &off

// return location corresponding to vector relative to the
// vehicle's home location
bool AP_AHRS::get_location_from_home_offset(Location &loc, const Vector3p &offset_ned) const
bool AP_AHRS::get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const
{
if (!home_is_set()) {
return false;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_AHRS/AP_AHRS.h
Original file line number Diff line number Diff line change
Expand Up @@ -277,8 +277,8 @@ class AP_AHRS {

// return location corresponding to vector relative to the
// vehicle's origin
bool get_location_from_origin_offset(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED;
bool get_location_from_home_offset(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED;
bool get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED;
bool get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED;

// Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.
// This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for.
Expand Down
Loading