PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <FlightTasks.hpp>
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_s & | getEmptyAvoidanceWaypoint () |
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 |
Definition at line 60 of file FlightTasks.hpp.
FlightTasks::FlightTasks | ( | ) |
Definition at line 6 of file FlightTasks.cpp.
References _initTask().
|
inline |
Definition at line 65 of file FlightTasks.hpp.
|
private |
|
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().
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().
|
inline |
Get the number of the active task.
Definition at line 126 of file FlightTasks.hpp.
Referenced by MulticopterPositionControl::print_status().
const vehicle_trajectory_waypoint_s FlightTasks::getAvoidanceWaypoint | ( | ) |
Get task avoidance desired waypoints.
const vehicle_constraints_s FlightTasks::getConstraints | ( | ) |
Get task dependent constraints.
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().
const vehicle_trajectory_waypoint_s& FlightTasks::getEmptyAvoidanceWaypoint | ( | ) |
Get empty avoidance desired waypoints.
const landing_gear_s FlightTasks::getGear | ( | ) |
Get landing gear position.
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().
const vehicle_local_position_setpoint_s FlightTasks::getPositionSetpoint | ( | ) |
Get the output data from the current task.
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().
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().
|
inline |
Check if any task is active.
Definition at line 132 of file FlightTasks.hpp.
Referenced by _updateCommand(), getConstraints(), getGear(), getPositionSetpoint(), handleParameterUpdate(), MulticopterPositionControl::print_status(), MulticopterPositionControl::Run(), and update().
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().
|
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().
|
inline |
Switch to the next task in the available list (for testing)
Definition at line 112 of file FlightTasks.hpp.
References switchTask().
Referenced by _updateCommand(), MulticopterPositionControl::start_flight_task(), and switchTask().
FlightTaskError FlightTasks::switchTask | ( | FlightTaskIndex | new_task_index | ) |
Switch to a specific task (for normal usage)
task | index to switch to |
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().
FlightTaskError FlightTasks::switchTask | ( | int | new_task_index | ) |
Definition at line 90 of file FlightTasks.cpp.
References InvalidTask, and switchTask().
|
private |
bool FlightTasks::update | ( | ) |
Call regularly in the control loop cycle to execute the task.
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().
|
inline |
Definition at line 154 of file FlightTasks.hpp.
Referenced by MulticopterPositionControl::Run().
|
private |
Definition at line 168 of file FlightTasks.hpp.
Referenced by _updateCommand(), getConstraints(), getGear(), getPositionSetpoint(), handleParameterUpdate(), reActivate(), switchTask(), and update().
|
staticprivate |
Definition at line 175 of file FlightTasks.hpp.
|
private |
Definition at line 193 of file FlightTasks.hpp.
Referenced by _updateCommand().
|
private |
topic handle on which commands are received
Definition at line 191 of file FlightTasks.hpp.
Referenced by _updateCommand().
|
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.
|
private |
Map from Error int to user friendly string.
Definition at line 179 of file FlightTasks.hpp.
Referenced by errorToString().