17#include "auto_apms_px4/mode.hpp"
18#include "auto_apms_px4/mode_executor.hpp"
19#include "auto_apms_px4_interfaces/action/set_actuators.hpp"
20#include "px4_ros2/control/setpoint_types/direct_actuators.hpp"
25using SetActuatorsActionType = auto_apms_px4_interfaces::action::SetActuators;
27class SetActuatorsMode :
public ModeBase<SetActuatorsActionType>
29 std::shared_ptr<px4_ros2::DirectActuatorsSetpointType> actuator_setpoint_ptr_;
30 rclcpp::Time activation_time_;
34 rclcpp::Node & node, px4_ros2::ModeBase::Settings settings, std::shared_ptr<ActionContextType> action_context_ptr)
35 : ModeBase{node, settings, action_context_ptr}
37 actuator_setpoint_ptr_ = std::make_shared<px4_ros2::DirectActuatorsSetpointType>(*
this);
41 void onActivateWithGoal(std::shared_ptr<const Goal> )
final
43 activation_time_ = node().get_clock()->now();
48 constexpr auto kNaN = std::numeric_limits<float>::quiet_NaN();
49 constexpr int kMaxMotors = px4_ros2::DirectActuatorsSetpointType::kMaxNumMotors;
50 constexpr int kMaxServos = px4_ros2::DirectActuatorsSetpointType::kMaxNumServos;
51 actuator_setpoint_ptr_->updateMotors(Eigen::Matrix<float, kMaxMotors, 1>::Constant(kNaN));
52 actuator_setpoint_ptr_->updateServos(Eigen::Matrix<float, kMaxServos, 1>::Constant(kNaN));
55 void onDeactivateWithGoal(std::shared_ptr<const Goal> )
final { stopActuators(); }
57 void updateSetpointOnCancel(
58 float , std::shared_ptr<const Goal> , std::shared_ptr<Feedback> ,
59 std::shared_ptr<Result> )
final
62 completed(px4_ros2::Result::Success);
65 void updateSetpointWithGoal(
66 float , std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Feedback> ,
67 std::shared_ptr<Result> )
final
69 constexpr auto kNaN = std::numeric_limits<float>::quiet_NaN();
70 constexpr int kMaxMotors = px4_ros2::DirectActuatorsSetpointType::kMaxNumMotors;
71 constexpr int kMaxServos = px4_ros2::DirectActuatorsSetpointType::kMaxNumServos;
74 Eigen::Matrix<float, kMaxMotors, 1> motor_cmds = Eigen::Matrix<float, kMaxMotors, 1>::Constant(kNaN);
75 for (
size_t i = 0; i < std::min(goal_ptr->motor_commands.size(),
static_cast<size_t>(kMaxMotors)); ++i) {
76 motor_cmds(i) = goal_ptr->motor_commands[i];
80 Eigen::Matrix<float, kMaxServos, 1> servo_cmds = Eigen::Matrix<float, kMaxServos, 1>::Constant(kNaN);
81 for (
size_t i = 0; i < std::min(goal_ptr->servo_commands.size(),
static_cast<size_t>(kMaxServos)); ++i) {
82 servo_cmds(i) = goal_ptr->servo_commands[i];
85 const rclcpp::Duration elapsed = node().get_clock()->now() - activation_time_;
86 const rclcpp::Duration hold_duration =
87 rclcpp::Duration::from_nanoseconds(
static_cast<int64_t
>(goal_ptr->hold_period_ms) * 1'000'000LL);
89 if (elapsed < hold_duration) {
91 actuator_setpoint_ptr_->updateMotors(motor_cmds);
92 actuator_setpoint_ptr_->updateServos(servo_cmds);
96 completed(px4_ros2::Result::Success);
101class SetActuatorsSkill :
public ModeExecutorFactory<SetActuatorsActionType, SetActuatorsMode>
104 explicit SetActuatorsSkill(
const rclcpp::NodeOptions & options)
105 : ModeExecutorFactory{
106 _AUTO_APMS_PX4__SET_ACTUATORS_ACTION_NAME, options, VehicleCommandClient::FlightMode::Unset, true}
113#include "rclcpp_components/register_node_macro.hpp"
114RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::SetActuatorsSkill)
Generic template class for a custom PX4 mode.
Helper template class that creates a ModeExecutor for a custom PX4 mode implemented by inheriting fro...
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.