AP_Location: use enum class for AltFrame enumeration

This commit is contained in:
Peter Barker 2019-03-15 12:43:43 +11:00 committed by Andrew Tridgell
parent 61a04bd898
commit 22c0175d7f
2 changed files with 35 additions and 35 deletions

View File

@ -28,7 +28,7 @@ void Location::zero(void)
memset(this, 0, sizeof(*this)); memset(this, 0, sizeof(*this));
} }
Location::Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, ALT_FRAME frame) Location::Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFrame frame)
{ {
zero(); zero();
lat = latitude; lat = latitude;
@ -39,7 +39,7 @@ Location::Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, ALT_F
Location::Location(const Vector3f &ekf_offset_neu) Location::Location(const Vector3f &ekf_offset_neu)
{ {
// store alt and alt frame // store alt and alt frame
set_alt_cm(ekf_offset_neu.z, ALT_FRAME_ABOVE_ORIGIN); set_alt_cm(ekf_offset_neu.z, AltFrame::ABOVE_ORIGIN);
// calculate lat, lon // calculate lat, lon
Location ekf_origin; Location ekf_origin;
@ -50,23 +50,23 @@ Location::Location(const Vector3f &ekf_offset_neu)
} }
} }
void Location::set_alt_cm(int32_t alt_cm, ALT_FRAME frame) void Location::set_alt_cm(int32_t alt_cm, AltFrame frame)
{ {
alt = alt_cm; alt = alt_cm;
relative_alt = false; relative_alt = false;
terrain_alt = false; terrain_alt = false;
origin_alt = false; origin_alt = false;
switch (frame) { switch (frame) {
case ALT_FRAME_ABSOLUTE: case AltFrame::ABSOLUTE:
// do nothing // do nothing
break; break;
case ALT_FRAME_ABOVE_HOME: case AltFrame::ABOVE_HOME:
relative_alt = true; relative_alt = true;
break; break;
case ALT_FRAME_ABOVE_ORIGIN: case AltFrame::ABOVE_ORIGIN:
origin_alt = true; origin_alt = true;
break; break;
case ALT_FRAME_ABOVE_TERRAIN: case AltFrame::ABOVE_TERRAIN:
// we mark it as a relative altitude, as it doesn't have // we mark it as a relative altitude, as it doesn't have
// home alt added // home alt added
relative_alt = true; relative_alt = true;
@ -76,7 +76,7 @@ void Location::set_alt_cm(int32_t alt_cm, ALT_FRAME frame)
} }
// converts altitude to new frame // converts altitude to new frame
bool Location::change_alt_frame(ALT_FRAME desired_frame) bool Location::change_alt_frame(AltFrame desired_frame)
{ {
int32_t new_alt_cm; int32_t new_alt_cm;
if (!get_alt_cm(desired_frame, new_alt_cm)) { if (!get_alt_cm(desired_frame, new_alt_cm)) {
@ -87,24 +87,24 @@ bool Location::change_alt_frame(ALT_FRAME desired_frame)
} }
// get altitude frame // get altitude frame
Location::ALT_FRAME Location::get_alt_frame() const Location::AltFrame Location::get_alt_frame() const
{ {
if (terrain_alt) { if (terrain_alt) {
return ALT_FRAME_ABOVE_TERRAIN; return AltFrame::ABOVE_TERRAIN;
} }
if (origin_alt) { if (origin_alt) {
return ALT_FRAME_ABOVE_ORIGIN; return AltFrame::ABOVE_ORIGIN;
} }
if (relative_alt) { if (relative_alt) {
return ALT_FRAME_ABOVE_HOME; return AltFrame::ABOVE_HOME;
} }
return ALT_FRAME_ABSOLUTE; return AltFrame::ABSOLUTE;
} }
/// get altitude in desired frame /// get altitude in desired frame
bool Location::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
{ {
Location::ALT_FRAME frame = get_alt_frame(); Location::AltFrame frame = get_alt_frame();
// shortcut if desired and underlying frame are the same // shortcut if desired and underlying frame are the same
if (desired_frame == frame) { if (desired_frame == frame) {
@ -114,7 +114,7 @@ bool Location::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
// check for terrain altitude // check for terrain altitude
float alt_terr_cm = 0; float alt_terr_cm = 0;
if (frame == ALT_FRAME_ABOVE_TERRAIN || desired_frame == ALT_FRAME_ABOVE_TERRAIN) { if (frame == AltFrame::ABOVE_TERRAIN || desired_frame == AltFrame::ABOVE_TERRAIN) {
#if AP_TERRAIN_AVAILABLE #if AP_TERRAIN_AVAILABLE
if (_terrain == nullptr || !_terrain->height_amsl(*(Location *)this, alt_terr_cm, true)) { if (_terrain == nullptr || !_terrain->height_amsl(*(Location *)this, alt_terr_cm, true)) {
return false; return false;
@ -129,16 +129,16 @@ bool Location::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
// convert alt to absolute // convert alt to absolute
int32_t alt_abs = 0; int32_t alt_abs = 0;
switch (frame) { switch (frame) {
case ALT_FRAME_ABSOLUTE: case AltFrame::ABSOLUTE:
alt_abs = alt; alt_abs = alt;
break; break;
case ALT_FRAME_ABOVE_HOME: case AltFrame::ABOVE_HOME:
if (!AP::ahrs().home_is_set()) { if (!AP::ahrs().home_is_set()) {
return false; return false;
} }
alt_abs = alt + AP::ahrs().get_home().alt; alt_abs = alt + AP::ahrs().get_home().alt;
break; break;
case ALT_FRAME_ABOVE_ORIGIN: case AltFrame::ABOVE_ORIGIN:
{ {
// fail if we cannot get ekf origin // fail if we cannot get ekf origin
Location ekf_origin; Location ekf_origin;
@ -148,23 +148,23 @@ bool Location::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
alt_abs = alt + ekf_origin.alt; alt_abs = alt + ekf_origin.alt;
} }
break; break;
case ALT_FRAME_ABOVE_TERRAIN: case AltFrame::ABOVE_TERRAIN:
alt_abs = alt + alt_terr_cm; alt_abs = alt + alt_terr_cm;
break; break;
} }
// convert absolute to desired frame // convert absolute to desired frame
switch (desired_frame) { switch (desired_frame) {
case ALT_FRAME_ABSOLUTE: case AltFrame::ABSOLUTE:
ret_alt_cm = alt_abs; ret_alt_cm = alt_abs;
return true; return true;
case ALT_FRAME_ABOVE_HOME: case AltFrame::ABOVE_HOME:
if (!AP::ahrs().home_is_set()) { if (!AP::ahrs().home_is_set()) {
return false; return false;
} }
ret_alt_cm = alt_abs - AP::ahrs().get_home().alt; ret_alt_cm = alt_abs - AP::ahrs().get_home().alt;
return true; return true;
case ALT_FRAME_ABOVE_ORIGIN: case AltFrame::ABOVE_ORIGIN:
{ {
// fail if we cannot get ekf origin // fail if we cannot get ekf origin
Location ekf_origin; Location ekf_origin;
@ -174,7 +174,7 @@ bool Location::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
ret_alt_cm = alt_abs - ekf_origin.alt; ret_alt_cm = alt_abs - ekf_origin.alt;
return true; return true;
} }
case ALT_FRAME_ABOVE_TERRAIN: case AltFrame::ABOVE_TERRAIN:
ret_alt_cm = alt_abs - alt_terr_cm; ret_alt_cm = alt_abs - alt_terr_cm;
return true; return true;
} }
@ -204,7 +204,7 @@ bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const
// convert altitude // convert altitude
int32_t alt_above_origin_cm = 0; int32_t alt_above_origin_cm = 0;
if (!get_alt_cm(ALT_FRAME_ABOVE_ORIGIN, alt_above_origin_cm)) { if (!get_alt_cm(AltFrame::ABOVE_ORIGIN, alt_above_origin_cm)) {
return false; return false;
} }
vec_neu.z = alt_above_origin_cm; vec_neu.z = alt_above_origin_cm;

View File

@ -32,35 +32,35 @@ public:
int32_t lng; int32_t lng;
/// enumeration of possible altitude types /// enumeration of possible altitude types
enum ALT_FRAME { enum class AltFrame {
ALT_FRAME_ABSOLUTE = 0, ABSOLUTE = 0,
ALT_FRAME_ABOVE_HOME = 1, ABOVE_HOME = 1,
ALT_FRAME_ABOVE_ORIGIN = 2, ABOVE_ORIGIN = 2,
ALT_FRAME_ABOVE_TERRAIN = 3 ABOVE_TERRAIN = 3
}; };
/// constructors /// constructors
Location(); Location();
Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, ALT_FRAME frame); Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFrame frame);
Location(const Vector3f &ekf_offset_neu); Location(const Vector3f &ekf_offset_neu);
static void set_terrain(AP_Terrain* terrain) { _terrain = terrain; } static void set_terrain(AP_Terrain* terrain) { _terrain = terrain; }
// set altitude // set altitude
void set_alt_cm(int32_t alt_cm, ALT_FRAME frame); void set_alt_cm(int32_t alt_cm, AltFrame frame);
// get altitude (in cm) in the desired frame // get altitude (in cm) in the desired frame
// returns false on failure to get altitude in the desired frame which // returns false on failure to get altitude in the desired frame which
// can only happen if the original frame or desired frame is above-terrain // can only happen if the original frame or desired frame is above-terrain
bool get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const; bool get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const;
// get altitude frame // get altitude frame
ALT_FRAME get_alt_frame() const; AltFrame get_alt_frame() const;
// converts altitude to new frame // converts altitude to new frame
// returns false on failure to convert which can only happen if // returns false on failure to convert which can only happen if
// the original frame or desired frame is above-terrain // the original frame or desired frame is above-terrain
bool change_alt_frame(ALT_FRAME desired_frame); bool change_alt_frame(AltFrame desired_frame);
// get position as a vector from origin (x,y only or x,y,z) // get position as a vector from origin (x,y only or x,y,z)
// return false on failure to get the vector which can only // return false on failure to get the vector which can only