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

Setpoint type for fixedwing control. More...

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

Inheritance diagram for px4_ros2::FwLateralLongitudinalSetpointType:
px4_ros2::SetpointBase

Public Member Functions

 FwLateralLongitudinalSetpointType (Context &context)
 
Configuration getConfiguration () override
 
void update (const FwLateralLongitudinalSetpoint &setpoint, const FwControlConfiguration &config)
 Update the setpoint with full flexibility by passing a FwLateralLongitudinalSetpoint and FwControlConfiguration struct.
 
void update (const FwLateralLongitudinalSetpoint &setpoint)
 Update the setpoint with full flexibility by passing a FwLateralLongitudinalSetpoint.
 
void updateWithAltitude (float altitude_amsl_sp, float course_sp, std::optional< float > equivalent_airspeed_sp={}, std::optional< float > lateral_acceleration_sp={})
 Update the setpoint with simplest set of inputs: Altitude and Course. Lateral acceleration setpoints will be used as feedforward when course is provided. To directly control lateral acceleration, set course_sp to NAN.
 
void updateWithHeightRate (float height_rate_sp, float course_sp, std::optional< float > equivalent_airspeed_sp={}, std::optional< float > lateral_acceleration_sp={})
 Update the setpoint with simplest set of inputs: Height rate and Course. Lateral acceleration setpoints will be used as feedforward when course is provided. To directly control lateral acceleration, set course_sp to NAN.
 
float desiredUpdateRateHz () override
 
- 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)
 

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 fixedwing control.

Member Function Documentation

◆ desiredUpdateRateHz()

float px4_ros2::FwLateralLongitudinalSetpointType::desiredUpdateRateHz ( )
inlineoverridevirtual

Reimplemented from px4_ros2::SetpointBase.

◆ getConfiguration()

Configuration px4_ros2::FwLateralLongitudinalSetpointType::getConfiguration ( )
overridevirtual

◆ update() [1/2]

void px4_ros2::FwLateralLongitudinalSetpointType::update ( const FwLateralLongitudinalSetpoint setpoint)

Update the setpoint with full flexibility by passing a FwLateralLongitudinalSetpoint.

Parameters
setpointa FwLateralLongitudinalSetpoint object where course, airspeed direction, lateral acceleration, altitude, height rate and equivalent airspeed can be set for full flexibility. See https://docs.px4.io/main/en/msg_docs/FixedWingLateralSetpoint.html and https://docs.px4.io/main/en/msg_docs/FixedWingLongitudinalSetpoint.html for more information on this setpoint type.
Warning
Any previously set configurations will be maintained when this method is called. If no configurations have been previously set, PX4 will set default configuration.

◆ update() [2/2]

void px4_ros2::FwLateralLongitudinalSetpointType::update ( const FwLateralLongitudinalSetpoint setpoint,
const FwControlConfiguration config 
)

Update the setpoint with full flexibility by passing a FwLateralLongitudinalSetpoint and FwControlConfiguration struct.

Parameters
setpointa FwLateralLongitudinalSetpoint object where course, airspeed direction, lateral acceleration, altitude, height rate and equivalent airspeed can be set for full flexibility. See https://docs.px4.io/main/en/msg_docs/FixedWingLateralSetpoint.html and https://docs.px4.io/main/en/msg_docs/FixedWingLongitudinalSetpoint.html for more information on this setpoint type.
configa FwControlConfiguration object where pitch, throttle, lateral acceleration configuration can be set. See https://docs.px4.io/main/en/msg_docs/LateralControlConfiguration.html and https://docs.px4.io/main/en/msg_docs/LongitudinalControlConfiguration.html for more information on how to configure the setpoint.

◆ updateWithAltitude()

void px4_ros2::FwLateralLongitudinalSetpointType::updateWithAltitude ( float  altitude_amsl_sp,
float  course_sp,
std::optional< float >  equivalent_airspeed_sp = {},
std::optional< float >  lateral_acceleration_sp = {} 
)

Update the setpoint with simplest set of inputs: Altitude and Course. Lateral acceleration setpoints will be used as feedforward when course is provided. To directly control lateral acceleration, set course_sp to NAN.

Warning
Any previously set configurations will be maintained when this method is called. If no configurations have been previously set, PX4 will set default configurations.

◆ updateWithHeightRate()

void px4_ros2::FwLateralLongitudinalSetpointType::updateWithHeightRate ( float  height_rate_sp,
float  course_sp,
std::optional< float >  equivalent_airspeed_sp = {},
std::optional< float >  lateral_acceleration_sp = {} 
)

Update the setpoint with simplest set of inputs: Height rate and Course. Lateral acceleration setpoints will be used as feedforward when course is provided. To directly control lateral acceleration, set course_sp to NAN.

Warning
Any previously set configurations will be maintained when this method is called. If no configurations have been previously set, PX4 will set default configurations.

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