Daniel Agar
4 years ago
committed by
Lorenz Meier
79 changed files with 351 additions and 609 deletions
@ -1,125 +0,0 @@
@@ -1,125 +0,0 @@
|
||||
############################################################################ |
||||
# |
||||
# Copyright (c) 2017 - 2020 PX4 Development Team. All rights reserved. |
||||
# |
||||
# Redistribution and use in source and binary forms, with or without |
||||
# modification, are permitted provided that the following conditions |
||||
# are met: |
||||
# |
||||
# 1. Redistributions of source code must retain the above copyright |
||||
# notice, this list of conditions and the following disclaimer. |
||||
# 2. Redistributions in binary form must reproduce the above copyright |
||||
# notice, this list of conditions and the following disclaimer in |
||||
# the documentation and/or other materials provided with the |
||||
# distribution. |
||||
# 3. Neither the name PX4 nor the names of its contributors may be |
||||
# used to endorse or promote products derived from this software |
||||
# without specific prior written permission. |
||||
# |
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
# POSSIBILITY OF SUCH DAMAGE. |
||||
# |
||||
############################################################################ |
||||
|
||||
########################################### |
||||
# Prepare flight tasks |
||||
########################################### |
||||
|
||||
# add upstream flight tasks (they are being handled differently from the core inside the python script) |
||||
list(APPEND flight_tasks_to_add |
||||
Orbit |
||||
) |
||||
# remove possible duplicates |
||||
list(REMOVE_DUPLICATES flight_tasks_to_add) |
||||
|
||||
# remove flight tasks depending on target |
||||
if(flight_tasks_to_remove) |
||||
list(REMOVE_ITEM flight_tasks_to_add |
||||
${flight_tasks_to_remove} |
||||
) |
||||
endif() |
||||
|
||||
# add core flight tasks to list |
||||
list(APPEND flight_tasks_all |
||||
ManualAltitude |
||||
ManualAltitudeSmoothVel |
||||
ManualPosition |
||||
ManualPositionSmoothVel |
||||
AutoLineSmoothVel |
||||
AutoFollowMe |
||||
Offboard |
||||
Failsafe |
||||
Descend |
||||
Transition |
||||
ManualAcceleration |
||||
${flight_tasks_to_add} |
||||
) |
||||
|
||||
# set the files to be generated |
||||
set(files_to_generate |
||||
FlightTasks_generated.hpp |
||||
FlightTasks_generated.cpp |
||||
) |
||||
|
||||
# generate files needed for Flight Tasks |
||||
set(python_args |
||||
-t ${flight_tasks_all} |
||||
-i ${CMAKE_CURRENT_SOURCE_DIR}/Templates |
||||
-o ${CMAKE_CURRENT_BINARY_DIR} |
||||
-f ${files_to_generate} |
||||
) |
||||
|
||||
# add the additional tasks for the python script (if there are any) |
||||
if(flight_tasks_to_add) |
||||
list(APPEND python_args |
||||
-s ${flight_tasks_to_add} |
||||
) |
||||
endif() |
||||
|
||||
# generate the files using the python script and template |
||||
add_custom_command( |
||||
OUTPUT |
||||
${CMAKE_CURRENT_BINARY_DIR}/FlightTasks_generated.hpp |
||||
${CMAKE_CURRENT_BINARY_DIR}/FlightTasks_generated.cpp |
||||
COMMAND ${PYTHON_EXECUTABLE} generate_flight_tasks.py ${python_args} |
||||
COMMENT "Generating Flight Tasks" |
||||
DEPENDS |
||||
Templates/FlightTasks_generated.cpp.em |
||||
Templates/FlightTasks_generated.hpp.em |
||||
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} |
||||
VERBATIM |
||||
) |
||||
|
||||
########################################### |
||||
# Create Flight Tasks Library |
||||
########################################### |
||||
|
||||
add_compile_options( |
||||
-Wno-cast-align |
||||
) # TODO: fix and enable |
||||
|
||||
px4_add_library(FlightTasks |
||||
FlightTasks.cpp |
||||
FlightTasks_generated.cpp |
||||
) |
||||
|
||||
# add directories to target |
||||
target_include_directories(FlightTasks PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_BINARY_DIR}) |
||||
|
||||
# add all flight task dependencies |
||||
foreach(task ${flight_tasks_all}) |
||||
target_link_libraries(FlightTasks PUBLIC FlightTask${task}) |
||||
endforeach() |
||||
|
||||
# add subdirectory containing all tasks |
||||
add_subdirectory(tasks) |
@ -1,191 +0,0 @@
@@ -1,191 +0,0 @@
|
||||
#include "FlightTasks.hpp" |
||||
|
||||
#include <uORB/topics/vehicle_command.h> |
||||
#include <uORB/topics/vehicle_command_ack.h> |
||||
|
||||
FlightTasks::FlightTasks() |
||||
{ |
||||
// initialize all flight-tasks
|
||||
// currently this is required to get all parameters read
|
||||
for (int i = 0; i < static_cast<int>(FlightTaskIndex::Count); i++) { |
||||
_initTask(static_cast<FlightTaskIndex>(i)); |
||||
} |
||||
|
||||
// disable all tasks
|
||||
_initTask(FlightTaskIndex::None); |
||||
} |
||||
|
||||
bool FlightTasks::update() |
||||
{ |
||||
_updateCommand(); |
||||
|
||||
if (isAnyTaskActive()) { |
||||
return _current_task.task->updateInitialize() && _current_task.task->update() && _current_task.task->updateFinalize(); |
||||
} |
||||
|
||||
return false; |
||||
} |
||||
|
||||
const vehicle_local_position_setpoint_s FlightTasks::getPositionSetpoint() |
||||
{ |
||||
if (isAnyTaskActive()) { |
||||
return _current_task.task->getPositionSetpoint(); |
||||
|
||||
} else { |
||||
return FlightTask::empty_setpoint; |
||||
} |
||||
} |
||||
|
||||
const ekf_reset_counters_s FlightTasks::getResetCounters() |
||||
{ |
||||
if (isAnyTaskActive()) { |
||||
return _current_task.task->getResetCounters(); |
||||
|
||||
} else { |
||||
return FlightTask::zero_reset_counters; |
||||
} |
||||
} |
||||
|
||||
const vehicle_constraints_s FlightTasks::getConstraints() |
||||
{ |
||||
if (isAnyTaskActive()) { |
||||
return _current_task.task->getConstraints(); |
||||
|
||||
} else { |
||||
return FlightTask::empty_constraints; |
||||
} |
||||
} |
||||
|
||||
const landing_gear_s FlightTasks::getGear() |
||||
{ |
||||
if (isAnyTaskActive()) { |
||||
return _current_task.task->getGear(); |
||||
|
||||
} else { |
||||
return FlightTask::empty_landing_gear_default_keep; |
||||
} |
||||
} |
||||
|
||||
FlightTaskError FlightTasks::switchTask(FlightTaskIndex new_task_index) |
||||
{ |
||||
// switch to the running task, nothing to do
|
||||
if (new_task_index == _current_task.index) { |
||||
return FlightTaskError::NoError; |
||||
} |
||||
|
||||
// Save current setpoints for the next FlightTask
|
||||
const vehicle_local_position_setpoint_s last_setpoint = getPositionSetpoint(); |
||||
const ekf_reset_counters_s last_reset_counters = getResetCounters(); |
||||
|
||||
if (_initTask(new_task_index)) { |
||||
// invalid task
|
||||
return FlightTaskError::InvalidTask; |
||||
} |
||||
|
||||
if (!isAnyTaskActive()) { |
||||
// no task running
|
||||
return FlightTaskError::NoError; |
||||
} |
||||
|
||||
// activation failed
|
||||
if (!_current_task.task->updateInitialize() || !_current_task.task->activate(last_setpoint)) { |
||||
_current_task.task->~FlightTask(); |
||||
_current_task.task = nullptr; |
||||
_current_task.index = FlightTaskIndex::None; |
||||
return FlightTaskError::ActivationFailed; |
||||
} |
||||
|
||||
_current_task.task->setResetCounters(last_reset_counters); |
||||
|
||||
return FlightTaskError::NoError; |
||||
} |
||||
|
||||
FlightTaskError FlightTasks::switchTask(int new_task_index) |
||||
{ |
||||
// make sure we are in range of the enumeration before casting
|
||||
if (static_cast<int>(FlightTaskIndex::None) <= new_task_index && |
||||
static_cast<int>(FlightTaskIndex::Count) > new_task_index) { |
||||
return switchTask(FlightTaskIndex(new_task_index)); |
||||
} |
||||
|
||||
switchTask(FlightTaskIndex::None); |
||||
return FlightTaskError::InvalidTask; |
||||
} |
||||
|
||||
void FlightTasks::handleParameterUpdate() |
||||
{ |
||||
if (isAnyTaskActive()) { |
||||
_current_task.task->handleParameterUpdate(); |
||||
} |
||||
} |
||||
|
||||
const char *FlightTasks::errorToString(const FlightTaskError error) |
||||
{ |
||||
for (auto e : _taskError) { |
||||
if (static_cast<FlightTaskError>(e.error) == error) { |
||||
return e.msg; |
||||
} |
||||
} |
||||
|
||||
return "This error is not mapped to a string or is unknown."; |
||||
} |
||||
|
||||
void FlightTasks::reActivate() |
||||
{ |
||||
if (isAnyTaskActive()) { |
||||
_current_task.task->reActivate(); |
||||
} |
||||
} |
||||
|
||||
void FlightTasks::_updateCommand() |
||||
{ |
||||
// check if there's any new command
|
||||
bool updated = _sub_vehicle_command.updated(); |
||||
|
||||
if (!updated) { |
||||
return; |
||||
} |
||||
|
||||
// get command
|
||||
vehicle_command_s command{}; |
||||
_sub_vehicle_command.copy(&command); |
||||
|
||||
// check what command it is
|
||||
FlightTaskIndex desired_task = switchVehicleCommand(command.command); |
||||
|
||||
if (desired_task == FlightTaskIndex::None) { |
||||
// ignore all unkown commands
|
||||
return; |
||||
} |
||||
|
||||
// switch to the commanded task
|
||||
FlightTaskError switch_result = switchTask(desired_task); |
||||
uint8_t cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED; |
||||
|
||||
// if we are in/switched to the desired task
|
||||
if (switch_result >= FlightTaskError::NoError) { |
||||
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED; |
||||
|
||||
// if the task is running apply parameters to it and see if it rejects
|
||||
if (isAnyTaskActive() && !_current_task.task->applyCommandParameters(command)) { |
||||
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_DENIED; |
||||
|
||||
// if we just switched and parameters are not accepted, go to failsafe
|
||||
if (switch_result >= FlightTaskError::NoError) { |
||||
switchTask(FlightTaskIndex::ManualPosition); |
||||
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED; |
||||
} |
||||
} |
||||
} |
||||
|
||||
// send back acknowledgment
|
||||
vehicle_command_ack_s command_ack{}; |
||||
command_ack.timestamp = hrt_absolute_time(); |
||||
command_ack.command = command.command; |
||||
command_ack.result = cmd_result; |
||||
command_ack.result_param1 = static_cast<int>(switch_result); |
||||
command_ack.target_system = command.source_system; |
||||
command_ack.target_component = command.source_component; |
||||
|
||||
_pub_vehicle_command_ack.publish(command_ack); |
||||
} |
@ -1,202 +0,0 @@
@@ -1,202 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2017 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file flight_taks.h |
||||
* |
||||
* Library class to hold and manage all implemented flight task instances |
||||
* |
||||
* @author Matthias Grob <maetugr@gmail.com> |
||||
*/ |
||||
|
||||
#pragma once |
||||
|
||||
#include "FlightTask.hpp" |
||||
#include "FlightTasks_generated.hpp" |
||||
#include <lib/weather_vane/WeatherVane.hpp> |
||||
#include <uORB/Publication.hpp> |
||||
#include <uORB/Subscription.hpp> |
||||
#include <uORB/topics/vehicle_command_ack.h> |
||||
#include <uORB/topics/vehicle_command.h> |
||||
|
||||
#include <new> |
||||
|
||||
enum class FlightTaskError : int { |
||||
NoError = 0, |
||||
InvalidTask = -1, |
||||
ActivationFailed = -2 |
||||
}; |
||||
|
||||
class FlightTasks |
||||
{ |
||||
public: |
||||
FlightTasks(); |
||||
|
||||
~FlightTasks() |
||||
{ |
||||
if (_current_task.task) { |
||||
_current_task.task->~FlightTask(); |
||||
} |
||||
} |
||||
|
||||
/**
|
||||
* Call regularly in the control loop cycle to execute the task |
||||
* @return true on success, false on error |
||||
*/ |
||||
bool update(); |
||||
|
||||
/**
|
||||
* Get the output data from the current task |
||||
* @return output setpoint, to be executed by position control |
||||
*/ |
||||
const vehicle_local_position_setpoint_s getPositionSetpoint(); |
||||
|
||||
/**
|
||||
* Get the local frame and attitude reset counters of the estimator from the current task |
||||
* @return the reset counters |
||||
*/ |
||||
const ekf_reset_counters_s getResetCounters(); |
||||
|
||||
/**
|
||||
* Get task dependent constraints |
||||
* @return setpoint constraints that has to be respected by the position controller |
||||
*/ |
||||
const vehicle_constraints_s getConstraints(); |
||||
|
||||
/**
|
||||
* Get landing gear position. |
||||
* @return landing gear |
||||
*/ |
||||
const landing_gear_s getGear(); |
||||
|
||||
/**
|
||||
* Get task avoidance desired waypoints |
||||
* @return auto triplets in the mc_pos_control |
||||
*/ |
||||
const vehicle_trajectory_waypoint_s getAvoidanceWaypoint(); |
||||
|
||||
/**
|
||||
* Get empty avoidance desired waypoints |
||||
* @return empty triplets in the mc_pos_control |
||||
*/ |
||||
const vehicle_trajectory_waypoint_s &getEmptyAvoidanceWaypoint(); |
||||
|
||||
/**
|
||||
* Switch to the next task in the available list (for testing) |
||||
* @return 0 on success, <0 on error |
||||
*/ |
||||
FlightTaskError switchTask() { return switchTask(static_cast<int>(_current_task.index) + 1); } |
||||
|
||||
/**
|
||||
* Switch to a specific task (for normal usage) |
||||
* @param task index to switch to |
||||
* @return 0 on success, <0 on error |
||||
*/ |
||||
FlightTaskError switchTask(FlightTaskIndex new_task_index); |
||||
FlightTaskError switchTask(int new_task_index); |
||||
|
||||
/**
|
||||
* Get the number of the active task |
||||
* @return number of active task, -1 if there is none |
||||
*/ |
||||
int getActiveTask() const { return static_cast<int>(_current_task.index); } |
||||
|
||||
/**
|
||||
* Check if any task is active |
||||
* @return true if a task is active, false if not |
||||
*/ |
||||
bool isAnyTaskActive() const { return _current_task.task; } |
||||
|
||||
/**
|
||||
* Call this whenever a parameter update notification is received (parameter_update uORB message) |
||||
*/ |
||||
void handleParameterUpdate(); |
||||
|
||||
/**
|
||||
* Call this method to get the description of a task error. |
||||
*/ |
||||
const char *errorToString(const FlightTaskError error); |
||||
|
||||
/**
|
||||
* Sets an external yaw handler. The active flight task can use the yaw handler to implement a different yaw control strategy. |
||||
*/ |
||||
void setYawHandler(WeatherVane *ext_yaw_handler) {_current_task.task->setYawHandler(ext_yaw_handler);} |
||||
|
||||
/**
|
||||
* This method will re-activate current task. |
||||
*/ |
||||
void reActivate(); |
||||
|
||||
void updateVelocityControllerIO(const matrix::Vector3f &vel_sp, const matrix::Vector3f &thrust_sp) {_current_task.task->updateVelocityControllerIO(vel_sp, thrust_sp); } |
||||
|
||||
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. |
||||
*/ |
||||
TaskUnion _task_union; /**< storage for the currently active task */ |
||||
|
||||
struct flight_task_t { |
||||
FlightTask *task; |
||||
FlightTaskIndex index; |
||||
}; |
||||
flight_task_t _current_task = {nullptr, FlightTaskIndex::None}; |
||||
|
||||
struct task_error_t { |
||||
int error; |
||||
const char *msg; |
||||
}; |
||||
|
||||
static constexpr int _numError = 3; |
||||
/**
|
||||
* Map from Error int to user friendly string. |
||||
*/ |
||||
task_error_t _taskError[_numError] = { |
||||
{static_cast<int>(FlightTaskError::NoError), "No Error"}, |
||||
{static_cast<int>(FlightTaskError::InvalidTask), "Invalid Task "}, |
||||
{static_cast<int>(FlightTaskError::ActivationFailed), "Activation Failed"} |
||||
}; |
||||
|
||||
/**
|
||||
* Check for vehicle commands (received via MAVLink), evaluate and acknowledge them |
||||
*/ |
||||
void _updateCommand(); |
||||
FlightTaskIndex switchVehicleCommand(const int command); |
||||
|
||||
uORB::Subscription _sub_vehicle_command{ORB_ID(vehicle_command)}; /**< topic handle on which commands are received */ |
||||
|
||||
uORB::Publication<vehicle_command_ack_s> _pub_vehicle_command_ack{ORB_ID(vehicle_command_ack)}; |
||||
|
||||
int _initTask(FlightTaskIndex task_index); |
||||
}; |
@ -1,5 +1,6 @@
@@ -1,5 +1,6 @@
|
||||
#include <gtest/gtest.h> |
||||
#include <flight_tasks/tasks/AutoLineSmoothVel/TrajectoryConstraints.hpp> |
||||
|
||||
#include "TrajectoryConstraints.hpp" |
||||
|
||||
using namespace matrix; |
||||
using namespace math::trajectory; |
Loading…
Reference in new issue