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_Common: Location: add set_alt_m #28480

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
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
4 changes: 4 additions & 0 deletions libraries/AP_Common/Location.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,10 @@ class Location

// set altitude
void set_alt_cm(int32_t alt_cm, AltFrame frame);
// set_alt_m - set altitude in metres
void set_alt_m(float alt_m, AltFrame frame) {
set_alt_cm(alt_m*100, frame);
}

// get altitude (in cm) in the desired frame
// returns false on failure to get altitude in the desired frame which can only happen if the original frame or desired frame is:
Expand Down
7 changes: 7 additions & 0 deletions libraries/AP_Common/tests/test_location.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -280,6 +280,13 @@ TEST(Location, Tests)
EXPECT_EQ(0, test_location4.loiter_xtrack);
EXPECT_TRUE(test_location4.initialised());

// test set_alt_m API:
Location loc = test_home;
loc.set_alt_m(1.71, Location::AltFrame::ABSOLUTE);
int32_t alt_in_cm_from_m;
EXPECT_TRUE(loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_in_cm_from_m));
EXPECT_EQ(171, alt_in_cm_from_m);

// can't create a Location using a vector here as there's no origin for the vector to be relative to:
// const Location test_location_empty{test_vect, Location::AltFrame::ABOVE_HOME};
// EXPECT_FALSE(test_location_empty.get_vector_from_origin_NEU(test_vec3));
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 @@ -5058,7 +5058,7 @@ bool GCS_MAVLINK::location_from_command_t(const mavlink_command_int_t &in, Locat
out.lat = in.x;
out.lng = in.y;

out.set_alt_cm(int32_t(in.z * 100), frame);
out.set_alt_m(in.z, frame);

return true;
}
Expand Down
Loading