15#include "auto_apms_interfaces/action/land.hpp"
17#include "auto_apms_px4/mode_executor.hpp"
18#include "px4_ros2/vehicle_state/land_detected.hpp"
23class LandSkill :
public ModeExecutor<auto_apms_interfaces::action::Land>
26 explicit LandSkill(
const rclcpp::NodeOptions & options)
27 : ModeExecutor(_AUTO_APMS_PX4__LAND_ACTION_NAME, options, FlightMode::Land)
29 px4_ros2::Context context(*node_ptr_,
"");
30 land_detected_ptr_ = std::make_unique<px4_ros2::LandDetected>(context);
34 bool sendActivationCommand(
35 const VehicleCommandClient & client, std::shared_ptr<const Goal> )
override final
41 std::shared_ptr<const Goal> goal_ptr,
const px4_msgs::msg::VehicleStatus & vehicle_status)
override final
43 return (land_detected_ptr_->lastValid(std::chrono::seconds(3)) && land_detected_ptr_->landed()) ||
44 ModeExecutor::isCompleted(goal_ptr, vehicle_status);
47 std::unique_ptr<px4_ros2::LandDetected> land_detected_ptr_;
52#include "rclcpp_components/register_node_macro.hpp"
53RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::LandSkill)
Generic template class for executing a PX4 mode implementing the interface of a standard ROS 2 action...
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.