PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
px4_ros2::VTOLConfig Struct Reference

Public Member Functions

VTOLConfigwithBackTransitionDeceleration (const float back_transition_deceleration)
 
VTOLConfigwithDecelerationIntegratorLimit (const float deceleration_integrator_limit)
 
VTOLConfigwithBackTransitionDecelerationIGain (const float back_transition_deceleration_setpoint_to_pitch_i)
 
VTOLConfigwithStatusTimeout (const std::chrono::seconds timeout)
 

Public Attributes

float back_transition_deceleration
 
float back_transition_deceleration_setpoint_to_pitch_i
 
float deceleration_integrator_limit {0.3f}
 
std::chrono::seconds status_timeout
 

Member Data Documentation

◆ back_transition_deceleration

float px4_ros2::VTOLConfig::back_transition_deceleration
Initial value:
{
2.f}

vehicle deceleration during back-transition [m/s^2].

◆ back_transition_deceleration_setpoint_to_pitch_i

float px4_ros2::VTOLConfig::back_transition_deceleration_setpoint_to_pitch_i
Initial value:
{
0.1f}

Backtransition deceleration setpoint to pitch I gain [rad s/m].

◆ status_timeout

std::chrono::seconds px4_ros2::VTOLConfig::status_timeout
Initial value:
{
5}

Maximum age of VtolVehicleStatus before state is considered unknown [s].


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