|
PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Provides VTOL transition command. More...
#include <px4_ros2/control/vtol.hpp>
Public Types | |
| enum class | State { Undefined = 0 , TransitionToFixedWing = 1 , TransitionToMulticopter = 2 , Multicopter = 3 , FixedWing = 4 } |
Public Member Functions | |
| VTOL (Context &context, const VTOLConfig &config=VTOLConfig{}) | |
| bool | toMulticopter () |
| bool | toFixedwing () |
| Eigen::Vector3f | computeAccelerationSetpointDuringTransition (std::optional< float > back_transition_deceleration_m_s2=std::nullopt) |
| State | getCurrentState () const |
Provides VTOL transition command.
| bool px4_ros2::VTOL::toMulticopter | ( | ) |
VTOL Transition