121 std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Feedback> feedback_ptr,
122 std::shared_ptr<Result> result_ptr)
override final;
125 bool isCurrentNavState(uint8_t nav_state);
126 virtual bool sendActivationCommand(
const VehicleCommandClient & client, std::shared_ptr<const Goal> goal_ptr);
127 virtual bool isCompleted(std::shared_ptr<const Goal> goal_ptr,
const px4_msgs::msg::VehicleStatus & vehicle_status);
128 virtual void setFeedback(std::shared_ptr<Feedback> feedback_ptr,
const px4_msgs::msg::VehicleStatus & vehicle_status);
130 uint8_t getModeID()
const;
133 const VehicleCommandClient vehicle_command_client_;
134 const uint8_t mode_id_;
135 bool deactivate_before_completion_;
136 rclcpp::Subscription<px4_msgs::msg::VehicleStatus>::SharedPtr vehicle_status_sub_ptr_;
137 rclcpp::Subscription<px4_msgs::msg::ModeCompleted>::SharedPtr mode_completed_sub_ptr_;
138 px4_msgs::msg::VehicleStatus::SharedPtr last_vehicle_status_ptr_;
139 bool mode_completed_{
false};
140 bool deactivation_command_sent_{
false};
141 State state_{State::REQUEST_ACTIVATION};
142 rclcpp::Time activation_command_sent_time_;
143 rclcpp::Duration activation_timeout_{0, 0};
153template <
class ActionT,
class ModeT>
154class ModeExecutorFactory
158 const std::string & action_name,
const rclcpp::NodeOptions & options,
159 const std::string & topic_namespace_prefix =
"",
bool deactivate_before_completion =
true);
161 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface();
164 rclcpp::Node::SharedPtr node_ptr_;
165 std::unique_ptr<ModeBase<ActionT>> mode_ptr_;
166 std::shared_ptr<ModeExecutor<ActionT>> mode_executor_ptr_;
173template <
class ActionT>
174ModeExecutor<ActionT>::ModeExecutor(
175 const std::string & action_name, rclcpp::Node::SharedPtr node_ptr,
176 std::shared_ptr<ActionContextType> action_context_ptr, uint8_t mode_id,
bool deactivate_before_completion)
177:
auto_apms_util::ActionWrapper<ActionT>(action_name, node_ptr, action_context_ptr),
178 vehicle_command_client_(*node_ptr),
180 deactivate_before_completion_(deactivate_before_completion)
185template <
class ActionT>
186ModeExecutor<ActionT>::ModeExecutor(
187 const std::string & action_name,
const rclcpp::NodeOptions & options, uint8_t mode_id,
188 bool deactivate_before_completion)
190 vehicle_command_client_(*this->node_ptr_),
192 deactivate_before_completion_(deactivate_before_completion)
197template <
class ActionT>
198ModeExecutor<ActionT>::ModeExecutor(
199 const std::string & action_name,
const rclcpp::NodeOptions & options, FlightMode flight_mode,
200 bool deactivate_before_completion)
201:
ModeExecutor<ActionT>(action_name, options, static_cast<uint8_t>(flight_mode), deactivate_before_completion)
205template <
class ActionT>
206void ModeExecutor<ActionT>::setUp()
208 vehicle_status_sub_ptr_ = this->node_ptr_->template create_subscription<px4_msgs::msg::VehicleStatus>(
209 "/fmu/out/vehicle_status", rclcpp::QoS(1).best_effort(),
210 [
this](px4_msgs::msg::VehicleStatus::UniquePtr msg) { last_vehicle_status_ptr_ = std::move(msg); });
212 mode_completed_sub_ptr_ = this->node_ptr_->template create_subscription<px4_msgs::msg::ModeCompleted>(
213 "/fmu/out/mode_completed", rclcpp::QoS(1).best_effort(), [
this](px4_msgs::msg::ModeCompleted::UniquePtr msg) {
214 if (msg->nav_state == mode_id_) {
215 if (msg->result == px4_msgs::msg::ModeCompleted::RESULT_SUCCESS) {
216 this->mode_completed_ =
true;
218 RCLCPP_ERROR(this->node_ptr_->get_logger(),
"Flight mode %i failed to execute. Aborting...", this->mode_id_);
219 this->action_context_ptr_->abort();
226template <
class ActionT>
232 bool is_holding = isCurrentNavState(
static_cast<uint8_t
>(FlightMode::Hold));
233 if (state_ == State::WAIT_FOR_ACTIVATION) {
235 auto & clock = *this->node_ptr_->get_clock();
236 RCLCPP_DEBUG_THROTTLE(
237 this->node_ptr_->get_logger(), clock, 250,
"Waiting for flight mode %i to become active before deactivating...",
239 return ActionStatus::RUNNING;
241 state_ = State::COMPLETE;
246 RCLCPP_DEBUG(this->node_ptr_->get_logger(),
"Deactivated flight mode successfully (HOLD is active)");
247 return ActionStatus::SUCCESS;
250 if (!deactivation_command_sent_) {
251 if (!vehicle_command_client_.syncActivateFlightMode(FlightMode::Hold)) {
252 RCLCPP_ERROR(this->node_ptr_->get_logger(),
"Failed to send command to activate HOLD");
253 return ActionStatus::FAILURE;
256 last_vehicle_status_ptr_ =
nullptr;
257 deactivation_command_sent_ =
true;
261 return ActionStatus::RUNNING;
264template <
class ActionT>
267 state_ = State::REQUEST_ACTIVATION;
268 deactivation_command_sent_ =
false;
269 mode_completed_ =
false;
270 activation_timeout_ = rclcpp::Duration::from_seconds(fmin(this->param_listener_.get_params().loop_rate * 15, 1.5));
274template <
class ActionT>
276 std::shared_ptr<const Goal> , std::shared_ptr<Result> )
278 if (deactivate_before_completion_) {
281 this->node_ptr_->get_logger(),
"Cancellation requested! Will deactivate before termination (Enter HOLD)...");
283 RCLCPP_DEBUG(this->node_ptr_->get_logger(),
"Cancellation requested!");
288template <
class ActionT>
290 std::shared_ptr<const Goal> , std::shared_ptr<Result> )
292 if (deactivate_before_completion_) {
293 return asyncDeactivateFlightMode();
295 return ActionStatus::SUCCESS;
298template <
class ActionT>
299bool ModeExecutor<ActionT>::isCurrentNavState(uint8_t nav_state)
301 if (last_vehicle_status_ptr_ && last_vehicle_status_ptr_->nav_state == nav_state) {
307template <
class ActionT>
309 std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Feedback> feedback_ptr, std::shared_ptr<Result> )
312 case State::REQUEST_ACTIVATION:
313 if (!sendActivationCommand(vehicle_command_client_, goal_ptr)) {
315 this->node_ptr_->get_logger(),
"Failed to send activation command for flight mode %i. Aborting...", mode_id_);
316 return ActionStatus::FAILURE;
319 last_vehicle_status_ptr_ =
nullptr;
320 state_ = State::WAIT_FOR_ACTIVATION;
321 activation_command_sent_time_ = this->node_ptr_->now();
323 this->node_ptr_->get_logger(),
"Activation command for flight mode %i was sent successfully", mode_id_);
324 return ActionStatus::RUNNING;
325 case State::WAIT_FOR_ACTIVATION:
326 if (isCurrentNavState(mode_id_)) {
327 RCLCPP_DEBUG(this->node_ptr_->get_logger(),
"Flight mode %i is active", mode_id_);
328 state_ = State::WAIT_FOR_COMPLETION_SIGNAL;
329 }
else if (this->node_ptr_->now() - activation_command_sent_time_ > activation_timeout_) {
330 RCLCPP_ERROR(this->node_ptr_->get_logger(),
"Timeout activating flight mode %i. Aborting...", mode_id_);
331 return ActionStatus::FAILURE;
333 return ActionStatus::RUNNING;
334 case State::WAIT_FOR_COMPLETION_SIGNAL:
336 setFeedback(feedback_ptr, *last_vehicle_status_ptr_);
339 if (isCompleted(goal_ptr, *last_vehicle_status_ptr_)) {
340 state_ = State::COMPLETE;
341 if (deactivate_before_completion_) {
344 this->node_ptr_->get_logger(),
345 "Flight mode %i complete! Will deactivate before termination (Enter HOLD)...", mode_id_);
348 this->node_ptr_->get_logger(),
349 "Flight mode %i complete! Will leave current navigation state as is. User is "
350 "responsible for initiating the next flight mode...",
358 if (!isCurrentNavState(mode_id_)) {
359 RCLCPP_WARN(this->node_ptr_->get_logger(),
"Flight mode %i was deactivated externally. Aborting...", mode_id_);
360 return ActionStatus::FAILURE;
362 return ActionStatus::RUNNING;
363 case State::COMPLETE:
367 if (deactivate_before_completion_) {
368 const auto deactivation_state = asyncDeactivateFlightMode();
369 if (deactivation_state != ActionStatus::SUCCESS) {
370 return deactivation_state;
375 RCLCPP_DEBUG(this->node_ptr_->get_logger(),
"Flight mode %i execution termination", mode_id_);
376 return ActionStatus::SUCCESS;