Skip to content

Commit

Permalink
parameterized condition to allow external mode registrations while ar…
Browse files Browse the repository at this point in the history
…med with COM_MODE_ARM_CHK
  • Loading branch information
bdilman committed Jan 23, 2025
1 parent 07e7c64 commit c199994
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include <uORB/topics/arming_check_reply.h>
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <px4_platform_common/module_params.h>

static_assert((1ull << arming_check_reply_s::HEALTH_COMPONENT_INDEX_AVOIDANCE) == (uint64_t)
health_component_t::avoidance, "enum definition missmatch");
Expand Down Expand Up @@ -66,7 +67,7 @@ class ExternalChecks : public HealthAndArmingCheckBase
void update();

bool isUnresponsive(int registration_id);

bool allowUpdateWhileArmed() const { return _param_com_mode_arm_chk.get(); }
private:
static constexpr hrt_abstime REQUEST_TIMEOUT = 50_ms;
static constexpr hrt_abstime UPDATE_INTERVAL = 300_ms;
Expand Down Expand Up @@ -109,4 +110,7 @@ class ExternalChecks : public HealthAndArmingCheckBase
uORB::Subscription _arming_check_reply_sub{ORB_ID(arming_check_reply)};

uORB::Publication<arming_check_request_s> _arming_check_request_pub{ORB_ID(arming_check_request)};
DEFINE_PARAMETERS(
(ParamInt<px4::params::COM_MODE_ARM_CHK>) _param_com_mode_arm_chk
);
};
2 changes: 1 addition & 1 deletion src/modules/commander/ModeManagement.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -370,7 +370,7 @@ void ModeManagement::update(bool armed, uint8_t user_intended_nav_state, bool fa
_failsafe_action_active = failsafe_action_active;
_external_checks.update();

bool allow_update_while_armed = false;
bool allow_update_while_armed = _external_checks.allowUpdateWhileArmed();
#if defined(CONFIG_ARCH_BOARD_PX4_SITL)
// For simulation, allow registering modes while armed for developer convenience
allow_update_while_armed = true;
Expand Down
12 changes: 12 additions & 0 deletions src/modules/commander/commander_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -1018,3 +1018,15 @@ PARAM_DEFINE_FLOAT(COM_THROW_SPEED, 5);
* @increment 1
*/
PARAM_DEFINE_INT32(COM_FLTT_LOW_ACT, 3);

/**
* Condition to enable external mode registration while armed
*
* By default, mode registration is disabled while armed.
*
* @value 0 Disabled
* @value 1 Enabled
*
* @group Commander
*/
PARAM_DEFINE_INT32(COM_MODE_ARM_CHK, 0);

0 comments on commit c199994

Please sign in to comment.