Skip to content

Commit

Permalink
Copter: RTL: ensure rally point is in absolute alt frame as RTL_ALT_T…
Browse files Browse the repository at this point in the history
…YPE takes precedence
  • Loading branch information
IamPete1 committed Oct 31, 2023
1 parent 75e8110 commit 7a84598
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion ArduCopter/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -408,9 +408,10 @@ void ModeRTL::build_path()
// return target's altitude is updated to a higher altitude that the vehicle can safely return at (frame may also be set)
void ModeRTL::compute_return_target()
{
// set return target to nearest rally point or home position (Note: alt is absolute)
// set return target to nearest rally point or home position
#if HAL_RALLY_ENABLED
rtl_path.return_target = copter.rally.calc_best_rally_or_home_location(copter.current_loc, ahrs.get_home().alt);
rtl_path.return_target.change_alt_frame(Location::AltFrame::ABSOLUTE);
#else
rtl_path.return_target = ahrs.get_home();
#endif
Expand Down

0 comments on commit 7a84598

Please sign in to comment.