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

#include <FlightTasks.hpp>

Collaboration diagram for FlightTasks:

Classes

struct  flight_task_t
 
struct  task_error_t
 

Public Member Functions

 FlightTasks ()
 
 ~FlightTasks ()
 
bool update ()
 Call regularly in the control loop cycle to execute the task. More...
 
const vehicle_local_position_setpoint_s getPositionSetpoint ()
 Get the output data from the current task. More...
 
const vehicle_constraints_s getConstraints ()
 Get task dependent constraints. More...
 
const landing_gear_s getGear ()
 Get landing gear position. More...
 
const vehicle_trajectory_waypoint_s getAvoidanceWaypoint ()
 Get task avoidance desired waypoints. More...
 
const vehicle_trajectory_waypoint_sgetEmptyAvoidanceWaypoint ()
 Get empty avoidance desired waypoints. More...
 
FlightTaskError switchTask ()
 Switch to the next task in the available list (for testing) More...
 
FlightTaskError switchTask (FlightTaskIndex new_task_index)
 Switch to a specific task (for normal usage) More...
 
FlightTaskError switchTask (int new_task_index)
 
int getActiveTask () const
 Get the number of the active task. More...
 
bool isAnyTaskActive () const
 Check if any task is active. More...
 
void handleParameterUpdate ()
 Call this whenever a parameter update notification is received (parameter_update uORB message) More...
 
const char * errorToString (const FlightTaskError error)
 Call this method to get the description of a task error. More...
 
void setYawHandler (WeatherVane *ext_yaw_handler)
 Sets an external yaw handler. More...
 
void reActivate ()
 This method will re-activate current task. More...
 
void updateVelocityControllerIO (const matrix::Vector3f &vel_sp, const matrix::Vector3f &thrust_sp)
 

Private Member Functions

void _updateCommand ()
 Check for vehicle commands (received via MAVLink), evaluate and acknowledge them. More...
 
FlightTaskIndex switchVehicleCommand (const int command)
 
int _initTask (FlightTaskIndex task_index)
 

Private Attributes

TaskUnion _task_union
 Union with all existing tasks: we use it to make sure that only the memory of the largest existing task is needed, and to avoid using dynamic memory allocations. More...
 
flight_task_t _current_task = {nullptr, FlightTaskIndex::None}
 
task_error_t _taskError [_numError]
 Map from Error int to user friendly string. More...
 
uORB::Subscription _sub_vehicle_command {ORB_ID(vehicle_command)}
 topic handle on which commands are received More...
 
uORB::PublicationQueued< vehicle_command_ack_s_pub_vehicle_command_ack {ORB_ID(vehicle_command_ack)}
 

Static Private Attributes

static constexpr int _numError = 3
 

Detailed Description

Definition at line 60 of file FlightTasks.hpp.

Constructor & Destructor Documentation

◆ FlightTasks()

FlightTasks::FlightTasks ( )

Definition at line 6 of file FlightTasks.cpp.

References _initTask().

Here is the call graph for this function:

◆ ~FlightTasks()

FlightTasks::~FlightTasks ( )
inline

Definition at line 65 of file FlightTasks.hpp.

Member Function Documentation

◆ _initTask()

int FlightTasks::_initTask ( FlightTaskIndex  task_index)
private

Referenced by FlightTasks(), and switchTask().

Here is the caller graph for this function:

◆ _updateCommand()

void FlightTasks::_updateCommand ( )
private

Check for vehicle commands (received via MAVLink), evaluate and acknowledge them.

Definition at line 127 of file FlightTasks.cpp.

References _current_task, _pub_vehicle_command_ack, _sub_vehicle_command, FlightTask::applyCommandParameters(), command, uORB::Subscription::copy(), hrt_absolute_time(), isAnyTaskActive(), NoError, uORB::PublicationQueued< T >::publish(), switchTask(), switchVehicleCommand(), FlightTasks::flight_task_t::task, vehicle_command_ack_s::timestamp, and uORB::Subscription::updated().

Referenced by update().

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

◆ errorToString()

const char * FlightTasks::errorToString ( const FlightTaskError  error)

Call this method to get the description of a task error.

Definition at line 109 of file FlightTasks.cpp.

References _taskError.

Referenced by MulticopterPositionControl::start_flight_task().

Here is the caller graph for this function:

◆ getActiveTask()

int FlightTasks::getActiveTask ( ) const
inline

Get the number of the active task.

Returns
number of active task, -1 if there is none

Definition at line 126 of file FlightTasks.hpp.

Referenced by MulticopterPositionControl::print_status().

Here is the caller graph for this function:

◆ getAvoidanceWaypoint()

const vehicle_trajectory_waypoint_s FlightTasks::getAvoidanceWaypoint ( )

Get task avoidance desired waypoints.

Returns
auto triplets in the mc_pos_control

◆ getConstraints()

const vehicle_constraints_s FlightTasks::getConstraints ( )

Get task dependent constraints.

Returns
setpoint constraints that has to be respected by the position controller

Definition at line 39 of file FlightTasks.cpp.

References _current_task, FlightTask::empty_constraints, FlightTask::getConstraints(), isAnyTaskActive(), and FlightTasks::flight_task_t::task.

Referenced by MulticopterPositionControl::Run().

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

◆ getEmptyAvoidanceWaypoint()

const vehicle_trajectory_waypoint_s& FlightTasks::getEmptyAvoidanceWaypoint ( )

Get empty avoidance desired waypoints.

Returns
empty triplets in the mc_pos_control

◆ getGear()

const landing_gear_s FlightTasks::getGear ( )

Get landing gear position.

Returns
landing gear

Definition at line 49 of file FlightTasks.cpp.

References _current_task, FlightTask::empty_landing_gear_default_keep, FlightTask::getGear(), isAnyTaskActive(), and FlightTasks::flight_task_t::task.

Referenced by MulticopterPositionControl::Run().

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

◆ getPositionSetpoint()

const vehicle_local_position_setpoint_s FlightTasks::getPositionSetpoint ( )

Get the output data from the current task.

Returns
output setpoint, to be executed by position control

Definition at line 29 of file FlightTasks.cpp.

References _current_task, FlightTask::empty_setpoint, FlightTask::getPositionSetpoint(), isAnyTaskActive(), and FlightTasks::flight_task_t::task.

Referenced by MulticopterPositionControl::Run(), and switchTask().

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

◆ handleParameterUpdate()

void FlightTasks::handleParameterUpdate ( )

Call this whenever a parameter update notification is received (parameter_update uORB message)

Definition at line 102 of file FlightTasks.cpp.

References _current_task, FlightTask::handleParameterUpdate(), isAnyTaskActive(), and FlightTasks::flight_task_t::task.

Referenced by MulticopterPositionControl::parameters_update().

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

◆ isAnyTaskActive()

bool FlightTasks::isAnyTaskActive ( ) const
inline

Check if any task is active.

Returns
true if a task is active, false if not

Definition at line 132 of file FlightTasks.hpp.

Referenced by _updateCommand(), getConstraints(), getGear(), getPositionSetpoint(), handleParameterUpdate(), MulticopterPositionControl::print_status(), MulticopterPositionControl::Run(), and update().

Here is the caller graph for this function:

◆ reActivate()

void FlightTasks::reActivate ( )

This method will re-activate current task.

Definition at line 120 of file FlightTasks.cpp.

References _current_task, FlightTask::reActivate(), and FlightTasks::flight_task_t::task.

Referenced by MulticopterPositionControl::Run().

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

◆ setYawHandler()

void FlightTasks::setYawHandler ( WeatherVane ext_yaw_handler)
inline

Sets an external yaw handler.

The active flight task can use the yaw handler to implement a different yaw control strategy.

Definition at line 147 of file FlightTasks.hpp.

Referenced by MulticopterPositionControl::Run().

Here is the caller graph for this function:

◆ switchTask() [1/3]

FlightTaskError FlightTasks::switchTask ( )
inline

Switch to the next task in the available list (for testing)

Returns
0 on success, <0 on error

Definition at line 112 of file FlightTasks.hpp.

References switchTask().

Referenced by _updateCommand(), MulticopterPositionControl::start_flight_task(), and switchTask().

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

◆ switchTask() [2/3]

FlightTaskError FlightTasks::switchTask ( FlightTaskIndex  new_task_index)

Switch to a specific task (for normal usage)

Parameters
taskindex to switch to
Returns
0 on success, <0 on error

Definition at line 59 of file FlightTasks.cpp.

References _current_task, _initTask(), FlightTask::activate(), ActivationFailed, getPositionSetpoint(), FlightTasks::flight_task_t::index, InvalidTask, NoError, FlightTasks::flight_task_t::task, FlightTask::updateInitialize(), and FlightTask::~FlightTask().

Here is the call graph for this function:

◆ switchTask() [3/3]

FlightTaskError FlightTasks::switchTask ( int  new_task_index)

Definition at line 90 of file FlightTasks.cpp.

References InvalidTask, and switchTask().

Here is the call graph for this function:

◆ switchVehicleCommand()

FlightTaskIndex FlightTasks::switchVehicleCommand ( const int  command)
private

Referenced by _updateCommand().

Here is the caller graph for this function:

◆ update()

bool FlightTasks::update ( )

Call regularly in the control loop cycle to execute the task.

Returns
true on success, false on error

Definition at line 18 of file FlightTasks.cpp.

References _current_task, _updateCommand(), isAnyTaskActive(), FlightTasks::flight_task_t::task, FlightTask::update(), FlightTask::updateFinalize(), and FlightTask::updateInitialize().

Referenced by MulticopterPositionControl::Run().

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

◆ updateVelocityControllerIO()

void FlightTasks::updateVelocityControllerIO ( const matrix::Vector3f vel_sp,
const matrix::Vector3f thrust_sp 
)
inline

Definition at line 154 of file FlightTasks.hpp.

Referenced by MulticopterPositionControl::Run().

Here is the caller graph for this function:

Member Data Documentation

◆ _current_task

flight_task_t FlightTasks::_current_task = {nullptr, FlightTaskIndex::None}
private

◆ _numError

constexpr int FlightTasks::_numError = 3
staticprivate

Definition at line 175 of file FlightTasks.hpp.

◆ _pub_vehicle_command_ack

uORB::PublicationQueued<vehicle_command_ack_s> FlightTasks::_pub_vehicle_command_ack {ORB_ID(vehicle_command_ack)}
private

Definition at line 193 of file FlightTasks.hpp.

Referenced by _updateCommand().

◆ _sub_vehicle_command

uORB::Subscription FlightTasks::_sub_vehicle_command {ORB_ID(vehicle_command)}
private

topic handle on which commands are received

Definition at line 191 of file FlightTasks.hpp.

Referenced by _updateCommand().

◆ _task_union

TaskUnion FlightTasks::_task_union
private

Union with all existing tasks: we use it to make sure that only the memory of the largest existing task is needed, and to avoid using dynamic memory allocations.

storage for the currently active task

Definition at line 162 of file FlightTasks.hpp.

◆ _taskError

task_error_t FlightTasks::_taskError[_numError]
private
Initial value:
= {
{static_cast<int>(FlightTaskError::NoError), "No Error"},
{static_cast<int>(FlightTaskError::InvalidTask), "Invalid Task "},
{static_cast<int>(FlightTaskError::ActivationFailed), "Activation Failed"}
}

Map from Error int to user friendly string.

Definition at line 179 of file FlightTasks.hpp.

Referenced by errorToString().


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