mirror of https://github.com/ArduPilot/ardupilot
AP_Common: Location: add set_alt_m
we have get_alt_m already, and there's a bunch of places that *100
This commit is contained in:
parent
c0ee3b2216
commit
0077066ffb
|
@ -35,6 +35,10 @@ public:
|
|||
|
||||
// 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:
|
||||
|
|
|
@ -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));
|
||||
|
|
Loading…
Reference in New Issue