diff --git a/examples/cpp/modes/manual/include/mode.hpp b/examples/cpp/modes/manual/include/mode.hpp index b5ffa5c..bb30506 100644 --- a/examples/cpp/modes/manual/include/mode.hpp +++ b/examples/cpp/modes/manual/include/mode.hpp @@ -7,7 +7,7 @@ #include #include #include -#include +#include #include @@ -47,7 +47,7 @@ class FlightModeTest : public px4_ros2::ModeBase _manual_control_input = std::make_shared(*this); _rates_setpoint = std::make_shared(*this); _attitude_setpoint = std::make_shared(*this); - _offboard_actuator_controls = std::make_shared(*this); + _peripheral_actuator_controls = std::make_shared(*this); } void onActivate() override {} @@ -82,15 +82,15 @@ class FlightModeTest : public px4_ros2::ModeBase _attitude_setpoint->update(qd, thrust_sp, yaw_rate); } - // Example to control a servo by passing through RC aux1 channel to 'Offboard Actuator Set 1' - _offboard_actuator_controls->set(_manual_control_input->aux1()); + // Example to control a servo by passing through RC aux1 channel to 'Peripheral Actuator Set 1' + _peripheral_actuator_controls->set(_manual_control_input->aux1()); } private: std::shared_ptr _manual_control_input; std::shared_ptr _rates_setpoint; std::shared_ptr _attitude_setpoint; - std::shared_ptr _offboard_actuator_controls; + std::shared_ptr _peripheral_actuator_controls; float _yaw{0.F}; }; diff --git a/px4_ros2_cpp/CMakeLists.txt b/px4_ros2_cpp/CMakeLists.txt index bc7ced7..f7ac39f 100644 --- a/px4_ros2_cpp/CMakeLists.txt +++ b/px4_ros2_cpp/CMakeLists.txt @@ -30,7 +30,7 @@ set(HEADER_FILES include/px4_ros2/components/mode_executor.hpp include/px4_ros2/components/overrides.hpp include/px4_ros2/components/wait_for_fmu.hpp - include/px4_ros2/control/offboard_actuators.hpp + include/px4_ros2/control/peripheral_actuators.hpp include/px4_ros2/control/setpoint_types/direct_actuators.hpp include/px4_ros2/control/setpoint_types/experimental/attitude.hpp include/px4_ros2/control/setpoint_types/experimental/rates.hpp @@ -49,7 +49,7 @@ add_library(px4_ros2_cpp src/components/overrides.cpp src/components/registration.cpp src/components/wait_for_fmu.cpp - src/control/offboard_actuators.cpp + src/control/peripheral_actuators.cpp src/control/setpoint_types/direct_actuators.cpp src/control/setpoint_types/experimental/attitude.cpp src/control/setpoint_types/experimental/rates.cpp diff --git a/px4_ros2_cpp/include/px4_ros2/control/offboard_actuators.hpp b/px4_ros2_cpp/include/px4_ros2/control/peripheral_actuators.hpp similarity index 83% rename from px4_ros2_cpp/include/px4_ros2/control/offboard_actuators.hpp rename to px4_ros2_cpp/include/px4_ros2/control/peripheral_actuators.hpp index f23a483..d5ffdef 100644 --- a/px4_ros2_cpp/include/px4_ros2/control/offboard_actuators.hpp +++ b/px4_ros2_cpp/include/px4_ros2/control/peripheral_actuators.hpp @@ -14,15 +14,15 @@ namespace px4_ros2 { /** - * Control one or more extra actuators. It maps to the 'Offboard Actuator Set' output functions on the PX4 side. + * Control one or more extra actuators. It maps to the 'Peripheral Actuator Set' output functions on the PX4 side. * This can be used by a mode independent from the setpoints. */ -class OffboardActuatorControls +class PeripheralActuatorControls { public: static constexpr int kNumActuators = 6; - explicit OffboardActuatorControls(Context & context); + explicit PeripheralActuatorControls(Context & context); /** * Control actuators diff --git a/px4_ros2_cpp/src/control/offboard_actuators.cpp b/px4_ros2_cpp/src/control/peripheral_actuators.cpp similarity index 82% rename from px4_ros2_cpp/src/control/offboard_actuators.cpp rename to px4_ros2_cpp/src/control/peripheral_actuators.cpp index 756a08e..3fb2d2c 100644 --- a/px4_ros2_cpp/src/control/offboard_actuators.cpp +++ b/px4_ros2_cpp/src/control/peripheral_actuators.cpp @@ -3,14 +3,14 @@ * SPDX-License-Identifier: BSD-3-Clause ****************************************************************************/ -#include +#include using namespace std::chrono_literals; namespace px4_ros2 { -OffboardActuatorControls::OffboardActuatorControls(Context & context) +PeripheralActuatorControls::PeripheralActuatorControls(Context & context) : _node(context.node()) { _vehicle_command_pub = _node.create_publisher( @@ -18,7 +18,7 @@ OffboardActuatorControls::OffboardActuatorControls(Context & context) _last_update = _node.get_clock()->now(); } -void OffboardActuatorControls::set(const Eigen::Matrix & values) +void PeripheralActuatorControls::set(const Eigen::Matrix & values) { // Rate-limit to avoid spamming the FC with commands at high frequency const auto now = _node.get_clock()->now(); @@ -41,7 +41,7 @@ void OffboardActuatorControls::set(const Eigen::Matrix } } -void OffboardActuatorControls::set(float value, unsigned int index) +void PeripheralActuatorControls::set(float value, unsigned int index) { Eigen::Matrix values; values.setConstant(NAN);