Skip to content

Commit

Permalink
Copter: reload takeoff cmd on arm when using AllowTakeOffWithoutRaisi…
Browse files Browse the repository at this point in the history
…ngThrottle

USING AUTO_OPTIONS 135 we set auto mode and arm from it if we got a takeoff cmd as first nav cmd.
Doing this, the takeoff cmd is loaded when we enter the auto mode and set the target alt relatively to origin https://github.com/ArduPilot/ardupilot/blob/master/ArduCopter/mode_auto.cpp#L343
This is never called again. So when we reset the home from the first arming, we don't update the target alt relativly to origin. This leads to a wrong takeoff alt settle due to the alt drift on ground.
  • Loading branch information
khancyr committed Mar 22, 2024
1 parent e7bf9d2 commit 7d63a74
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -992,7 +992,10 @@ void ModeAuto::takeoff_run()
// if the user doesn't want to raise the throttle we can set it automatically
// note that this can defeat the disarm check on takeoff
if ((copter.g2.auto_options & (int32_t)Options::AllowTakeOffWithoutRaisingThrottle) != 0) {
copter.set_auto_armed(true);
if (motors->armed() && copter.ap.auto_armed == false) {
copter.mode_auto.mission.restart_current_nav_cmd(); // reload the takeoff command after arming home update
copter.set_auto_armed(true);
}
}
auto_takeoff.run();
}
Expand Down

0 comments on commit 7d63a74

Please sign in to comment.