PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
px4_ros2::DirectActuatorsSetpointType Class Reference

Setpoint type for direct actuator control (servos and/or motors) More...

#include <px4_ros2/control/setpoint_types/direct_actuators.hpp>

Inheritance diagram for px4_ros2::DirectActuatorsSetpointType:
px4_ros2::SetpointBase

Public Member Functions

 DirectActuatorsSetpointType (Context &context)
 
Configuration getConfiguration () override
 
float desiredUpdateRateHz () override
 
void updateServos (const Eigen::Matrix< float, kMaxNumServos, 1 > &servo_commands)
 
void updateMotors (const Eigen::Matrix< float, kMaxNumMotors, 1 > &motor_commands)
 
- Public Member Functions inherited from px4_ros2::SetpointBase
 SetpointBase (Context &context)
 
std::shared_ptr< SetpointBasegetSharedPtr ()
 
void setShouldActivateCallback (const ShouldActivateCB &should_activate_cb)
 
void setActive (bool active)
 

Static Public Attributes

static constexpr int kMaxNumMotors = px4_msgs::msg::ActuatorMotors::NUM_CONTROLS
 
static constexpr int kMaxNumServos = px4_msgs::msg::ActuatorServos::NUM_CONTROLS
 

Additional Inherited Members

- Public Types inherited from px4_ros2::SetpointBase
using ShouldActivateCB = std::function< void()>
 
- Protected Member Functions inherited from px4_ros2::SetpointBase
void onUpdate ()
 

Detailed Description

Setpoint type for direct actuator control (servos and/or motors)

Member Function Documentation

◆ updateMotors()

void px4_ros2::DirectActuatorsSetpointType::updateMotors ( const Eigen::Matrix< float, kMaxNumMotors, 1 > &  motor_commands)

Send motors setpoint

Parameters
motor_commandsrange: [-1, 1], where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN), and NaN maps to disarmed (stop the motors)

◆ updateServos()

void px4_ros2::DirectActuatorsSetpointType::updateServos ( const Eigen::Matrix< float, kMaxNumServos, 1 > &  servo_commands)

Send servos setpoint

Parameters
servo_commandsrange: [-1, 1], where 1 means maximum positive position, -1 maximum negative and NaN maps to disarmed

The documentation for this class was generated from the following file: