PX4 Firmware
PX4 Autopilot Software http://px4.io
FlightTaskManual Class Reference

#include <FlightTaskManual.hpp>

Inheritance diagram for FlightTaskManual:
Collaboration diagram for FlightTaskManual:

Public Member Functions

 FlightTaskManual ()=default
 
virtual ~FlightTaskManual ()=default
 
bool applyCommandParameters (const vehicle_command_s &command) override
 To be called to adopt parameters from an arrived vehicle command. More...
 
bool updateInitialize () override
 Call before activate() or update() to initialize time and input data. More...
 
- Public Member Functions inherited from FlightTask
 FlightTask ()
 
virtual ~FlightTask ()=default
 
virtual bool activate (vehicle_local_position_setpoint_s last_setpoint)
 Call once on the event where you switch to the task. More...
 
virtual void reActivate ()
 Call this to reset an active Flight Task. More...
 
virtual bool update ()=0
 To be called regularly in the control loop cycle to execute the task. More...
 
virtual bool updateFinalize ()
 Call after update() to constrain the generated setpoints in order to comply with the constraints of the current mode. More...
 
const vehicle_local_position_setpoint_s getPositionSetpoint ()
 Get the output data. More...
 
const vehicle_constraints_sgetConstraints ()
 Get vehicle constraints. More...
 
const landing_gear_sgetGear ()
 Get landing gear position. More...
 
const vehicle_trajectory_waypoint_sgetAvoidanceWaypoint ()
 Get avoidance desired waypoint. More...
 
void handleParameterUpdate ()
 Call this whenever a parameter update notification is received (parameter_update uORB message) More...
 
virtual void setYawHandler (WeatherVane *ext_yaw_handler)
 Sets an external yaw handler which can be used by any flight task to implement a different yaw control strategy. More...
 
void updateVelocityControllerIO (const matrix::Vector3f &vel_sp, const matrix::Vector3f &thrust_sp)
 

Protected Member Functions

float stickDeadzone () const
 
- Protected Member Functions inherited from FlightTask
void _resetSetpoints ()
 Reset all setpoints to NAN. More...
 
void _evaluateVehicleLocalPosition ()
 Check and update local position. More...
 
virtual void _setDefaultConstraints ()
 Set constraints to default values. More...
 
virtual bool _checkTakeoff ()
 Determine when to trigger a takeoff (ignored in flight) More...
 
void _initEkfResetCounters ()
 Monitor the EKF reset counters and call the appropriate handling functions in case of a reset event. More...
 
void _checkEkfResetCounters ()
 
virtual void _ekfResetHandlerPositionXY ()
 
virtual void _ekfResetHandlerVelocityXY ()
 
virtual void _ekfResetHandlerPositionZ ()
 
virtual void _ekfResetHandlerVelocityZ ()
 
virtual void _ekfResetHandlerHeading (float delta_psi)
 

Protected Attributes

bool _sticks_data_required = true
 let inherited task-class define if it depends on stick data More...
 
matrix::Vector< float, 4 > _sticks
 unmodified manual stick inputs More...
 
matrix::Vector< float, 4 > _sticks_expo
 modified manual sticks using expo function More...
 
int _gear_switch_old = manual_control_setpoint_s::SWITCH_POS_NONE
 old switch state More...
 
- Protected Attributes inherited from FlightTask
uORB::SubscriptionData< vehicle_local_position_s_sub_vehicle_local_position {ORB_ID(vehicle_local_position)}
 
uORB::SubscriptionData< vehicle_attitude_s_sub_attitude {ORB_ID(vehicle_attitude)}
 
float _time = 0
 passed time in seconds since the task was activated More...
 
float _deltatime = 0
 passed time in seconds since the task was last updated More...
 
hrt_abstime _time_stamp_activate = 0
 time stamp when task was activated More...
 
hrt_abstime _time_stamp_current = 0
 time stamp at the beginning of the current task update More...
 
hrt_abstime _time_stamp_last = 0
 time stamp when task was last updated More...
 
matrix::Vector3f _position
 current vehicle position More...
 
matrix::Vector3f _velocity
 current vehicle velocity More...
 
float _yaw = 0.f
 current vehicle yaw heading More...
 
float _dist_to_bottom = 0.0f
 current height above ground level More...
 
matrix::Vector3f _position_setpoint
 Setpoints which the position controller has to execute. More...
 
matrix::Vector3f _velocity_setpoint
 
matrix::Vector3f _acceleration_setpoint
 
matrix::Vector3f _jerk_setpoint
 
matrix::Vector3f _thrust_setpoint
 
float _yaw_setpoint
 
float _yawspeed_setpoint
 
matrix::Vector3f _velocity_setpoint_feedback
 
matrix::Vector3f _thrust_setpoint_feedback
 
struct {
   uint8_t   xy = 0
 
   uint8_t   vxy = 0
 
   uint8_t   z = 0
 
   uint8_t   vz = 0
 
   uint8_t   quat = 0
 
_reset_counters
 
vehicle_constraints_s _constraints {}
 Vehicle constraints. More...
 
landing_gear_s _gear {}
 
vehicle_trajectory_waypoint_s _desired_waypoint {}
 Desired waypoints. More...
 

Private Member Functions

bool _evaluateSticks ()
 checks and sets stick inputs More...
 
void _applyGearSwitch (uint8_t gswitch)
 Sets gears according to switch. More...
 

Private Attributes

uORB::SubscriptionData< manual_control_setpoint_s_sub_manual_control_setpoint {ORB_ID(manual_control_setpoint)}
 

Additional Inherited Members

- Static Public Attributes inherited from FlightTask
static const vehicle_local_position_setpoint_s empty_setpoint = {0, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, {NAN, NAN, NAN}, {NAN, NAN, NAN}, {NAN, NAN, NAN}, {}}
 Empty setpoint. More...
 
static const vehicle_constraints_s empty_constraints = {0, NAN, NAN, NAN, NAN, NAN, NAN, NAN, false, {}}
 Empty constraints. More...
 
static const landing_gear_s empty_landing_gear_default_keep = {0, landing_gear_s::GEAR_KEEP, {}}
 default landing gear state More...
 
- Static Protected Attributes inherited from FlightTask
static constexpr uint64_t _timeout = 500000
 maximal time in us before a loop or data times out More...
 

Detailed Description

Definition at line 46 of file FlightTaskManual.hpp.

Constructor & Destructor Documentation

◆ FlightTaskManual()

FlightTaskManual::FlightTaskManual ( )
default

◆ ~FlightTaskManual()

virtual FlightTaskManual::~FlightTaskManual ( )
virtualdefault

Member Function Documentation

◆ _applyGearSwitch()

void FlightTaskManual::_applyGearSwitch ( uint8_t  gswitch)
private

Sets gears according to switch.

Definition at line 107 of file FlightTaskManual.cpp.

Referenced by stickDeadzone().

Here is the caller graph for this function:

◆ _evaluateSticks()

bool FlightTaskManual::_evaluateSticks ( )
private

checks and sets stick inputs

Definition at line 60 of file FlightTaskManual.cpp.

References math::expo_deadzone(), f(), and hrt_abstime.

Referenced by stickDeadzone().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ applyCommandParameters()

bool FlightTaskManual::applyCommandParameters ( const vehicle_command_s command)
inlineoverridevirtual

To be called to adopt parameters from an arrived vehicle command.

Parameters
commandreceived command message containing the parameters
Returns
true if accepted, false if declined

Reimplemented from FlightTask.

Reimplemented in FlightTaskOrbit.

Definition at line 53 of file FlightTaskManual.hpp.

References FlightTask::applyCommandParameters(), and updateInitialize().

Here is the call graph for this function:

◆ stickDeadzone()

float FlightTaskManual::stickDeadzone ( ) const
inlineprotected

Definition at line 63 of file FlightTaskManual.hpp.

References _applyGearSwitch(), and _evaluateSticks().

Here is the call graph for this function:

◆ updateInitialize()

bool FlightTaskManual::updateInitialize ( )
overridevirtual

Call before activate() or update() to initialize time and input data.

Returns
true on success, false on error

Reimplemented from FlightTask.

Reimplemented in FlightTaskManualPosition, and FlightTaskManualAltitude.

Definition at line 45 of file FlightTaskManual.cpp.

References FlightTask::updateInitialize().

Referenced by applyCommandParameters(), and FlightTaskManualAltitude::updateInitialize().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _gear_switch_old

int FlightTaskManual::_gear_switch_old = manual_control_setpoint_s::SWITCH_POS_NONE
protected

old switch state

Definition at line 61 of file FlightTaskManual.hpp.

◆ _sticks

matrix::Vector<float, 4> FlightTaskManual::_sticks
protected

unmodified manual stick inputs

Definition at line 59 of file FlightTaskManual.hpp.

◆ _sticks_data_required

bool FlightTaskManual::_sticks_data_required = true
protected

let inherited task-class define if it depends on stick data

Definition at line 58 of file FlightTaskManual.hpp.

Referenced by FlightTaskOrbit::FlightTaskOrbit().

◆ _sticks_expo

matrix::Vector<float, 4> FlightTaskManual::_sticks_expo
protected

modified manual sticks using expo function

Definition at line 60 of file FlightTaskManual.hpp.

Referenced by FlightTaskManualPosition::_scaleSticks(), and FlightTaskOrbit::update().

◆ _sub_manual_control_setpoint

uORB::SubscriptionData<manual_control_setpoint_s> FlightTaskManual::_sub_manual_control_setpoint {ORB_ID(manual_control_setpoint)}
private

Definition at line 70 of file FlightTaskManual.hpp.


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