AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
enable_hold.cpp
Go to the documentation of this file.
1// Copyright 2024 Robin Müller
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// https://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#include "auto_apms_interfaces/action/enable_hold.hpp"
16
19
20namespace auto_apms_px4
21{
22
23class EnableHoldTask : public ModeExecutor<auto_apms_interfaces::action::EnableHold>
24{
25public:
26 explicit EnableHoldTask(const rclcpp::NodeOptions& options)
27 : ModeExecutor{ ENABLE_HOLD_TASK_NAME, options, FlightMode::Hold, false }
28 {
29 }
30
31private:
32 bool isCompleted(std::shared_ptr<const Goal> goal_ptr, const px4_msgs::msg::VehicleStatus& vehicle_status) final
33 {
34 (void)goal_ptr;
35 (void)vehicle_status;
36 // For HOLD mode there is no completion signal. Once activated it is considered complete.
37 return true;
38 }
39};
40
41} // namespace auto_apms_px4
42
43#include "rclcpp_components/register_node_macro.hpp"
44RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::EnableHoldTask)
ModeExecutor(const std::string &name, rclcpp::Node::SharedPtr node_ptr, std::shared_ptr< ActionContextType > action_context_ptr, uint8_t mode_id, bool deactivate_before_completion=true, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
const char ENABLE_HOLD_TASK_NAME[]
Definition constants.hpp:22