Browse Source

AP_Rally: clarify that rtl altitude is in cm amsl

apm_2208
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
d1f4e95b26
  1. 4
      libraries/AP_Rally/AP_Rally.cpp
  2. 2
      libraries/AP_Rally/AP_Rally.h

4
libraries/AP_Rally/AP_Rally.cpp

@ -167,11 +167,11 @@ bool AP_Rally::find_nearest_rally_point(const Location &current_loc, RallyLocati @@ -167,11 +167,11 @@ bool AP_Rally::find_nearest_rally_point(const Location &current_loc, RallyLocati
}
// return best RTL location from current position
Location AP_Rally::calc_best_rally_or_home_location(const Location &current_loc, float rtl_home_alt) const
Location AP_Rally::calc_best_rally_or_home_location(const Location &current_loc, float rtl_home_alt_amsl_cm) const
{
// if no valid rally point, return home position:
Location return_loc { AP::ahrs().get_home() };
return_loc.set_alt_cm(rtl_home_alt, Location::AltFrame::ABSOLUTE);
return_loc.set_alt_cm(rtl_home_alt_amsl_cm, Location::AltFrame::ABSOLUTE);
RallyLocation ral_loc;
if (find_nearest_rally_point(current_loc, ral_loc)) {

2
libraries/AP_Rally/AP_Rally.h

@ -68,7 +68,7 @@ public: @@ -68,7 +68,7 @@ public:
Location rally_location_to_location(const RallyLocation &ret) const;
// logic handling
Location calc_best_rally_or_home_location(const Location &current_loc, float rtl_home_alt) const;
Location calc_best_rally_or_home_location(const Location &current_loc, float rtl_home_alt_amsl_cm) const;
bool find_nearest_rally_point(const Location &myloc, RallyLocation &ret) const;
// last time rally points changed

Loading…
Cancel
Save