Skip to content

Commit

Permalink
rename OffboardActuatorControls to PeripheralActuatorControls
Browse files Browse the repository at this point in the history
To avoid any confusion with the Offboard interface.
  • Loading branch information
bkueng committed Nov 10, 2023
1 parent df7eba7 commit c9a0acd
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 14 deletions.
10 changes: 5 additions & 5 deletions examples/cpp/modes/manual/include/mode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include <px4_ros2/components/mode.hpp>
#include <px4_ros2/control/setpoint_types/experimental/rates.hpp>
#include <px4_ros2/control/setpoint_types/experimental/attitude.hpp>
#include <px4_ros2/control/offboard_actuators.hpp>
#include <px4_ros2/control/peripheral_actuators.hpp>

#include <Eigen/Eigen>

Expand Down Expand Up @@ -47,7 +47,7 @@ class FlightModeTest : public px4_ros2::ModeBase
_manual_control_input = std::make_shared<px4_ros2::ManualControlInput>(*this);
_rates_setpoint = std::make_shared<px4_ros2::RatesSetpointType>(*this);
_attitude_setpoint = std::make_shared<px4_ros2::AttitudeSetpointType>(*this);
_offboard_actuator_controls = std::make_shared<px4_ros2::OffboardActuatorControls>(*this);
_peripheral_actuator_controls = std::make_shared<px4_ros2::PeripheralActuatorControls>(*this);
}

void onActivate() override {}
Expand Down Expand Up @@ -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<px4_ros2::ManualControlInput> _manual_control_input;
std::shared_ptr<px4_ros2::RatesSetpointType> _rates_setpoint;
std::shared_ptr<px4_ros2::AttitudeSetpointType> _attitude_setpoint;
std::shared_ptr<px4_ros2::OffboardActuatorControls> _offboard_actuator_controls;
std::shared_ptr<px4_ros2::PeripheralActuatorControls> _peripheral_actuator_controls;
float _yaw{0.F};
};

Expand Down
4 changes: 2 additions & 2 deletions px4_ros2_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,22 +3,22 @@
* SPDX-License-Identifier: BSD-3-Clause
****************************************************************************/

#include <px4_ros2/control/offboard_actuators.hpp>
#include <px4_ros2/control/peripheral_actuators.hpp>

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<px4_msgs::msg::VehicleCommand>(
context.topicNamespacePrefix() + "/fmu/in/vehicle_command", 1);
_last_update = _node.get_clock()->now();
}

void OffboardActuatorControls::set(const Eigen::Matrix<float, kNumActuators, 1> & values)
void PeripheralActuatorControls::set(const Eigen::Matrix<float, kNumActuators, 1> & values)
{
// Rate-limit to avoid spamming the FC with commands at high frequency
const auto now = _node.get_clock()->now();
Expand All @@ -41,7 +41,7 @@ void OffboardActuatorControls::set(const Eigen::Matrix<float, kNumActuators, 1>
}
}

void OffboardActuatorControls::set(float value, unsigned int index)
void PeripheralActuatorControls::set(float value, unsigned int index)
{
Eigen::Matrix<float, kNumActuators, 1> values;
values.setConstant(NAN);
Expand Down

0 comments on commit c9a0acd

Please sign in to comment.