mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Commander: don't reset Home position if landed during a (uncompleted) mission. (#24902)
This commit is contained in:
parent
8d3c94c947
commit
2110da73ad
@ -613,7 +613,7 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_
|
||||
events::send<events::px4::enums::arm_disarm_reason_t>(events::ID("commander_armed_by"), events::Log::Info,
|
||||
"Armed by {1}", calling_reason);
|
||||
|
||||
if (_param_com_home_en.get()) {
|
||||
if (_param_com_home_en.get() && !_mission_in_progress) {
|
||||
_home_position.setHomePosition();
|
||||
}
|
||||
|
||||
@ -1809,7 +1809,10 @@ void Commander::run()
|
||||
|
||||
vtolStatusUpdate();
|
||||
|
||||
_home_position.update(_param_com_home_en.get(), !isArmed() && _vehicle_land_detected.landed);
|
||||
_mission_in_progress = (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION)
|
||||
&& !_mission_result_sub.get().finished;
|
||||
|
||||
_home_position.update(_param_com_home_en.get(), !isArmed() && _vehicle_land_detected.landed && !_mission_in_progress);
|
||||
|
||||
handleAutoDisarm();
|
||||
|
||||
@ -2110,7 +2113,7 @@ void Commander::landDetectorUpdate()
|
||||
}
|
||||
|
||||
// automatically set or update home position
|
||||
if (_param_com_home_en.get()) {
|
||||
if (_param_com_home_en.get() && !_mission_in_progress) {
|
||||
// set the home position when taking off
|
||||
if (!_vehicle_land_detected.landed) {
|
||||
if (was_landed) {
|
||||
|
||||
@ -279,6 +279,7 @@ private:
|
||||
bool _arm_tune_played{false};
|
||||
bool _have_taken_off_since_arming{false};
|
||||
bool _status_changed{true};
|
||||
bool _mission_in_progress{false};
|
||||
|
||||
vehicle_land_detected_s _vehicle_land_detected{};
|
||||
|
||||
|
||||
@ -142,6 +142,9 @@ PARAM_DEFINE_FLOAT(COM_RC_LOSS_T, 0.5f);
|
||||
*
|
||||
* Set home position automatically if possible.
|
||||
*
|
||||
* During missions, the home position is locked and will not reset during intermediate landings.
|
||||
* It will only update once the mission is complete or landed outside of a mission.
|
||||
*
|
||||
* @group Commander
|
||||
* @reboot_required true
|
||||
* @boolean
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user