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

Provides access to manually input control setpoints. More...

#include <px4_ros2/components/manual_control_input.hpp>

Public Member Functions

 ManualControlInput (Context &context, bool is_optional=false)
 
float roll () const
 
float pitch () const
 
float yaw () const
 
float throttle () const
 
float aux1 () const
 
float aux2 () const
 
float aux3 () const
 
float aux4 () const
 
float aux5 () const
 
float aux6 () const
 
bool isValid () const
 

Detailed Description

Provides access to manually input control setpoints.

Member Function Documentation

◆ pitch()

float px4_ros2::ManualControlInput::pitch ( ) const
inline

Stick position in [-1,1]. Move forward, negative pitch rotation, nose down

◆ roll()

float px4_ros2::ManualControlInput::roll ( ) const
inline

Stick position in [-1,1]. Move right, positive roll rotation, right side down

◆ throttle()

float px4_ros2::ManualControlInput::throttle ( ) const
inline

Stick position in [-1,1]. Move up, positive thrust, -1 is minimum available 0% or -100%, +1 is 100% thrust

◆ yaw()

float px4_ros2::ManualControlInput::yaw ( ) const
inline

Stick position in [-1,1]. Positive yaw rotation, clockwise when seen top down


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