15#include "auto_apms_px4_interfaces/action/takeoff.hpp"
17#include "auto_apms_px4/mode_executor.hpp"
18#include "px4_msgs/msg/vehicle_global_position.hpp"
19#include "px4_ros2/utils/message_version.hpp"
24class TakeoffSkill :
public ModeExecutor<auto_apms_px4_interfaces::action::Takeoff>
27 explicit TakeoffSkill(
const rclcpp::NodeOptions & options)
28 : ModeExecutor(_AUTO_APMS_PX4__TAKEOFF_ACTION_NAME, options, FlightMode::Takeoff)
30 vehicle_global_position_sub_ptr_ = this->node_ptr_->create_subscription<px4_msgs::msg::VehicleGlobalPosition>(
31 "fmu/out/vehicle_global_position" + px4_ros2::getMessageNameVersion<px4_msgs::msg::VehicleGlobalPosition>(),
32 rclcpp::SensorDataQoS(), [
this](
const px4_msgs::msg::VehicleGlobalPosition::SharedPtr msg_ptr) {
33 last_vehicle_global_position_ = std::move(*msg_ptr);
38 bool sendActivationCommand(
const VehicleCommandClient & client, std::shared_ptr<const Goal> goal_ptr)
override final
40 float target_altitude = goal_ptr->alt;
41 if (!goal_ptr->use_amsl) {
42 target_altitude += last_vehicle_global_position_.alt;
45 node_ptr_->get_logger(),
"Target altitude: %f m (AMSL) - Heading: %f rad", target_altitude,
46 goal_ptr->heading_rad);
47 return client.takeoff(target_altitude, goal_ptr->heading_rad);
50 rclcpp::Subscription<px4_msgs::msg::VehicleGlobalPosition>::SharedPtr vehicle_global_position_sub_ptr_;
51 px4_msgs::msg::VehicleGlobalPosition last_vehicle_global_position_;
56#include "rclcpp_components/register_node_macro.hpp"
57RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::TakeoffSkill)
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.