mirror of https://github.com/ArduPilot/ardupilot
AP_Rally: clarify that rtl altitude is in cm amsl
This commit is contained in:
parent
a2a63e14b1
commit
d1f4e95b26
|
@ -167,11 +167,11 @@ bool AP_Rally::find_nearest_rally_point(const Location ¤t_loc, RallyLocati
|
|||
}
|
||||
|
||||
// return best RTL location from current position
|
||||
Location AP_Rally::calc_best_rally_or_home_location(const Location ¤t_loc, float rtl_home_alt) const
|
||||
Location AP_Rally::calc_best_rally_or_home_location(const Location ¤t_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)) {
|
||||
|
|
|
@ -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 ¤t_loc, float rtl_home_alt) const;
|
||||
Location calc_best_rally_or_home_location(const Location ¤t_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…
Reference in New Issue