Skip to content

Commit

Permalink
refactor: use enum instead of multiple flags for activation
Browse files Browse the repository at this point in the history
  • Loading branch information
damien-robotsix committed Jul 12, 2024
1 parent debe3da commit 04e778c
Show file tree
Hide file tree
Showing 4 changed files with 17 additions and 7 deletions.
9 changes: 7 additions & 2 deletions px4_ros2_cpp/include/px4_ros2/components/mode_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,13 @@ class ModeExecutorBase

struct Settings
{
bool activate_immediately{false}; ///< If set activate the mode (and executor) immediately. Only use this for fully autonomous executors that also arm the vehicle
bool is_allowed_to_arm{false}; ///< If set, the executor is allowed to arm the vehicle
enum class Activation
{
ActivateOnlyWhenArmed, ///< Only activate the executor when armed (and selected)
ActivateAlways, ///< Allow the executor to always be activated (so it can arm the vehicle)
ActivateImmediately, ///< Activate the mode and executor immediately after registration. Only use this for fully autonomous executors that also arm the vehicle
};
Activation activation{Activation::ActivateOnlyWhenArmed};
};

enum class DeactivateReason
Expand Down
9 changes: 6 additions & 3 deletions px4_ros2_cpp/src/components/mode_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,8 @@ bool ModeExecutorBase::doRegister()
_owned_mode.unsubscribeVehicleStatus();
RegistrationSettings settings = _owned_mode.getRegistrationSettings();
settings.register_mode_executor = true;
settings.activate_mode_immediately = _settings.activate_immediately;
settings.activate_mode_immediately =
(_settings.activation == Settings::Activation::ActivateImmediately);
bool ret = _registration->doRegister(settings);

if (ret) {
Expand Down Expand Up @@ -289,9 +290,11 @@ void ModeExecutorBase::vehicleStatusUpdated(const px4_msgs::msg::VehicleStatus::
const bool was_armed = _is_armed;
const ModeBase::ModeID current_mode = static_cast<ModeBase::ModeID>(msg->nav_state);
_is_armed = msg->arming_state == px4_msgs::msg::VehicleStatus::ARMING_STATE_ARMED;
const bool wants_to_activate_immediately = _settings.activate_immediately && _was_never_activated;
const bool wants_to_activate_immediately =
(_settings.activation == Settings::Activation::ActivateImmediately) && _was_never_activated;
const bool is_in_charge = id() == msg->executor_in_charge &&
(_is_armed || wants_to_activate_immediately || _settings.is_allowed_to_arm);
(_is_armed || wants_to_activate_immediately ||
_settings.activation == Settings::Activation::ActivateAlways);
const bool changed_to_armed = !was_armed && _is_armed;

bool got_activated = false;
Expand Down
3 changes: 2 additions & 1 deletion px4_ros2_cpp/test/integration/mode_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,8 @@ class ModeExecutorTest : public px4_ros2::ModeExecutorBase
{
public:
ModeExecutorTest(rclcpp::Node & node, FlightModeTest & owned_mode, bool activate_immediately)
: ModeExecutorBase(node, ModeExecutorBase::Settings{activate_immediately}, owned_mode),
: ModeExecutorBase(node, ModeExecutorBase::Settings{Settings::Activation::ActivateImmediately},
owned_mode),
_node(node)
{}

Expand Down
3 changes: 2 additions & 1 deletion px4_ros2_cpp/test/integration/overrides.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,8 @@ class ModeExecutorTest : public px4_ros2::ModeExecutorBase
{
public:
ModeExecutorTest(rclcpp::Node & node, FlightModeTest & owned_mode, bool activate_immediately)
: ModeExecutorBase(node, ModeExecutorBase::Settings{activate_immediately}, owned_mode),
: ModeExecutorBase(node, ModeExecutorBase::Settings{Settings::Activation::ActivateImmediately},
owned_mode),
_node(node)
{}

Expand Down

0 comments on commit 04e778c

Please sign in to comment.