Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[WIP] Flight task auto #9253

Closed
wants to merge 81 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
81 commits
Select commit Hold shift + click to select a range
bd938c1
FlightTaskAuto: abstract class for mapping triplets to quadruple
Stifael Jan 12, 2018
bd9b9bf
PositionControl: auto takeoff with constant speed
Stifael Jan 23, 2018
3a5f65c
FlightTaskAutoLine: check if yaw_wp is finite
Stifael Feb 7, 2018
a2eb7f9
PositionControl: if valid velocity and position setpoint available, a…
Stifael Feb 7, 2018
06f5697
ControlMath: by value to reference
Stifael Feb 8, 2018
20e5696
FlightTaskAuto minor clean up
Stifael Feb 8, 2018
ffb1f62
mc_pos_control: update to _dt
Stifael Feb 8, 2018
f4c5915
mavlink_messages: add yawspeed to local position setpoint sent over m…
Stifael Feb 9, 2018
4b2bd53
mc_pos_control: set thrust to zero if in idle
Stifael Feb 9, 2018
59c0ec0
mc_pos_control: remove unused method
Stifael Feb 9, 2018
cc44ee0
mc_pos_control: idle state fix
Stifael Feb 10, 2018
289556c
mc_pos_control: only adjust thrust setpoint for ground/maybe landed i…
Stifael Feb 10, 2018
0d3025b
position control: remove empty space
Stifael Feb 10, 2018
12d5a66
FlightTaskAuto: remove unused include
Stifael Feb 10, 2018
efa38f1
FlightTaskAuto: pure virtual reset method
Stifael Feb 13, 2018
6f850ab
FlightTaskAuto: comment fix
Stifael Feb 13, 2018
5fe72c9
FlightTaskAutoLine: override _reset method
Stifael Feb 13, 2018
49f3f1d
FlightTaskAuto: simplify logic by just updating waypoints if anything…
Stifael Feb 14, 2018
7383f08
FlightTaskAutoLine: simplify logic by setting setpoints directly
Stifael Feb 14, 2018
82c0a63
FlightTaskAuto: remove warning message
Feb 19, 2018
f710e38
FlightTaskIndex: add AutoLine
Feb 23, 2018
651a5f4
mc_pos_control: replace thr with thrust
Feb 23, 2018
2855076
FlightTaskAuto: typo fix
Feb 23, 2018
16d24ec
FlightTaskAuto: always update cruise speed
Feb 23, 2018
9dec2e8
FlightTaskAutoLine: replace xy/z setpoints with FlightTask base setpo…
Mar 1, 2018
29e8152
FlightTask: remove global to local map
Mar 1, 2018
2a56a16
FlightTaskAutoLine: introduce previous type which used to reset setpo…
Mar 1, 2018
c1a74c9
FlightTaskAutoLine: move method
Mar 1, 2018
57bddf0
FlightTaskAutoLine: first activate and then reset
Mar 1, 2018
2b48087
FlightTaskAutoLine: if previous type was idle, set thrust to NAN agai…
Mar 1, 2018
99834ed
mc_pos_control: remove logic which was only present due to legacy code
Mar 1, 2018
c27072c
mc_pos_control: remove smooth takeoff for pure manual
Mar 1, 2018
057ca7b
comment fix
Mar 1, 2018
0b60eca
FlightTaskAutoLine: don't reset during normal operation
Mar 1, 2018
e903d31
mc_pos_control: don't stay idle when landed but in pure manual
Mar 1, 2018
e1fa9d1
FlightTaskManualStabilized: replace minimum throttle with minum throt…
Mar 1, 2018
fcb1613
PositionControl: make distinction for throttle minimum depending on mode
Mar 1, 2018
d0d5b06
mc_pos_control auto takeoff: smooth takeoff until speed of 0.8 is rea…
Mar 2, 2018
8311910
FlightTaskAuto: always update type
Mar 2, 2018
61da394
PositionControl: parameter subscription declaration
Mar 5, 2018
a957665
mc_pos_control takeoff: smooth-takeoff starts if position setpoint la…
Mar 8, 2018
e9dfb79
mc_pos_contorl: comment update
Mar 8, 2018
f6b7de4
mc_pos_control: stay in smooth-takeoff only if altitude is not reache…
Mar 8, 2018
1916cb5
mc_pos_control: only use flighttask if rotary wing
Mar 9, 2018
04cf518
mc_pos_control: set all unused att_sp members to false
Mar 9, 2018
b31c878
FlightTask: move geo-lib include to FlightTaskAuto where it is required
Mar 9, 2018
01e2fea
FlightTask: split _evalutateVehiclePosition into _evaluateVehicleLoca…
Mar 9, 2018
5d8e140
FlightTaskAuto: fix global reference update
Mar 9, 2018
970830a
ControlMath: add derivation and simplify computation
Mar 9, 2018
d5bcb6c
mc_pos_control: replace constant takeoffspeed with parameter
Mar 9, 2018
794b536
mc_pos_control ground-contact: replace body thrust to zero with local…
Mar 9, 2018
6cb983d
ControlMath constrainxy: fix one of the condition
Mar 9, 2018
fbcc15c
mc_pos_control: update comment
Mar 9, 2018
9cdf15c
test_controlmath: add first few tests for constrain function in xy
Mar 9, 2018
3e4283d
mc_pos_control: simplify logic by considering valid velocity and posi…
Mar 9, 2018
452a2a1
FlightTask: comment fixes
Mar 19, 2018
01e7b32
PositionControl: variable replacement
Mar 19, 2018
915ef3f
mc_pos_control: make sure that auto takeoff setpoint is at least 20cm…
Mar 20, 2018
41438c7
PositionControl: add integral reset methods
Mar 23, 2018
bcd9b8c
Positioncontrol: limit velocity upwards during smooth takeoff
Mar 23, 2018
21dc8fa
mc_pos_control landed/ground contact: reset PID-integrals
Mar 23, 2018
a8dc4e3
FlightTaskAutoLine: fix greater sign
Mar 23, 2018
d02846d
FlightTaskAuto: always update yaw
Mar 23, 2018
0e34b7c
mc_pos_control: clean up of comments
Mar 27, 2018
6264c1e
PositionControl: check if constraints are below global maximum
Mar 27, 2018
cb52bbd
PositionControl/mc_pos_control: update comments
Mar 27, 2018
a174cea
PositionControl parameter renaming. Use the the name as stored in the…
Mar 28, 2018
f595c76
FlightTaskAuto: comments refactor
Mar 29, 2018
af0038e
ControlMath: comments refactor
Mar 29, 2018
85c7542
PositionControl: bug fix Pv replacement with Pp
Apr 5, 2018
4d8ee3c
mc_pos_control and FlightTaskAuto rebase fix
Apr 6, 2018
d6ef432
PositionControl: degrees to radians
Apr 6, 2018
87c6e6e
test_controlmath rebase fix: EPS to FLT_EPSILON
Apr 11, 2018
f603c49
mc_pos_control: takeoff speed to new param type
Apr 11, 2018
b705ef5
FlightTasksAuto/Line: replace BlockParams with module params
Apr 11, 2018
09c2354
PositionControl.hpp: inherit from ModuleParams and replace params wit…
Apr 11, 2018
557dfef
PositionControl.cpp: replace all params with ModuleParams type. Add m…
Apr 11, 2018
92424c3
mc_pos_control: PositionControl class adjustement to new ModuleParams
Apr 11, 2018
af861f4
px4_module_params: make updateParams virtual
Apr 11, 2018
311ef95
PositionControl: replace overwrite with ModuleParams updateParams method
Apr 11, 2018
a5a506c
PositionControl: format clean up
Apr 11, 2018
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions src/lib/FlightTasks/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ px4_add_module(
tasks/FlightTaskManualAltitudeSmooth.cpp
tasks/FlightTaskManualPosition.cpp
tasks/FlightTaskManualPositionSmooth.cpp
tasks/FlightTaskAuto.cpp
tasks/FlightTaskAutoLine.cpp
tasks/Utility/ManualSmoothingZ.cpp
tasks/Utility/ManualSmoothingXY.cpp
SubscriptionArray.cpp
Expand Down
4 changes: 4 additions & 0 deletions src/lib/FlightTasks/FlightTasks.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,10 @@ int FlightTasks::switchTask(FlightTaskIndex new_task_index)
_current_task = new (&_task_union.sport) FlightTaskSport();
break;

case FlightTaskIndex::AutoLine:
_current_task = new (&_task_union.autoLine) FlightTaskAutoLine();
break;

default:
/* invalid task */
return -1;
Expand Down
3 changes: 3 additions & 0 deletions src/lib/FlightTasks/FlightTasks.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@
#include "tasks/FlightTaskManualPosition.hpp"
#include "tasks/FlightTaskManualPositionSmooth.hpp"
#include "tasks/FlightTaskManualStabilized.hpp"
#include "tasks/FlightTaskAutoLine.hpp"
#include "tasks/FlightTaskOrbit.hpp"
#include "tasks/FlightTaskSport.hpp"

Expand All @@ -63,6 +64,7 @@ enum class FlightTaskIndex : int {
PositionSmooth,
Orbit,
Sport,
AutoLine,

Count // number of tasks
};
Expand Down Expand Up @@ -139,6 +141,7 @@ class FlightTasks
FlightTaskManualPositionSmooth position_smooth;
FlightTaskOrbit orbit;
FlightTaskSport sport;
FlightTaskAutoLine autoLine;
} _task_union; /**< storage for the currently active task */

FlightTask *_current_task = nullptr;
Expand Down
4 changes: 2 additions & 2 deletions src/lib/FlightTasks/tasks/FlightTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ bool FlightTask::updateInitialize()
_time = (_time_stamp_current - _time_stamp_activate) / 1e6f;
_deltatime = math::min((_time_stamp_current - _time_stamp_last), _timeout) / 1e6f;
_time_stamp_last = _time_stamp_current;
return _evaluateVehiclePosition();
return _evaluateVehicleLocalPosition();
}

const vehicle_local_position_setpoint_s FlightTask::getPositionSetpoint()
Expand All @@ -53,7 +53,7 @@ void FlightTask::_resetSetpoints()
_yaw_setpoint = _yawspeed_setpoint = NAN;
}

bool FlightTask::_evaluateVehiclePosition()
bool FlightTask::_evaluateVehicleLocalPosition()
{
if ((_time_stamp_current - _sub_vehicle_local_position->get().timestamp) < _timeout) {
_position = matrix::Vector3f(&_sub_vehicle_local_position->get().x);
Expand Down
6 changes: 1 addition & 5 deletions src/lib/FlightTasks/tasks/FlightTask.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,10 +47,8 @@
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
#include <uORB/topics/vehicle_command.h>

#include "../SubscriptionArray.hpp"


class FlightTask : public ModuleParams
{
public:
Expand Down Expand Up @@ -134,8 +132,6 @@ class FlightTask : public ModuleParams
*/
void _resetSetpoints();

private:
uORB::Subscription<vehicle_local_position_s> *_sub_vehicle_local_position{nullptr};

bool _evaluateVehiclePosition();
bool _evaluateVehicleLocalPosition();
};
182 changes: 182 additions & 0 deletions src/lib/FlightTasks/tasks/FlightTaskAuto.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,182 @@
/****************************************************************************
*
* Copyright (c) 2018 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 FlightTaskAuto.cpp
*/

#include "FlightTaskAuto.hpp"
#include <mathlib/mathlib.h>
#include <float.h>

using namespace matrix;

bool FlightTaskAuto::initializeSubscriptions(SubscriptionArray &subscription_array)
{
if (!FlightTask::initializeSubscriptions(subscription_array)) {
return false;
}

if (!subscription_array.get(ORB_ID(position_setpoint_triplet), _sub_triplet_setpoint)) {
return false;
}

return true;
}

bool FlightTaskAuto::activate()
{
_prev_prev_wp = _prev_wp = _target = _next_wp = _position;
_yaw_wp = _yaw;
return FlightTask::activate();
}

bool FlightTaskAuto::updateInitialize()
{
bool ret = FlightTask::updateInitialize();
_evaluateVehicleGlobalPosition();
return (ret && _evaluateTriplets());
}

bool FlightTaskAuto::_evaluateTriplets()
{
// TODO: fix the issues mentioned below
// We add here some conditions that are only required because:
// 1. navigator continuously sends triplet during mission due to yaw setpoint. This
// should be removed in the navigator and only updates if the current setpoint actually has changed.
//
// 2. navigator should be responsible to send always three valid setpoints. If there is only one setpoint,
// then previous will be set to current vehicle position and next will be set equal to setpoint.
//
// 3. navigator originally only supports gps guided maneuvers. However, it now also supports some flow-specific features
// such as land and takeoff. The navigator should use for auto takeoff/land with flow the position in xy at the moment the
// takeoff/land was initiated. Until then we do this kind of logic here.

if (!_sub_triplet_setpoint->get().current.valid) {
// best we can do is to just set all waypoints to current state
_prev_prev_wp = _prev_wp = _target = _next_wp = _position;
_yaw_wp = _yaw;
_type = WaypointType::position;
return false;
}

_type = (WaypointType)_sub_triplet_setpoint->get().current.type;
// always update cruise speed since that can change without waypoint changes
_mc_cruise_speed = _sub_triplet_setpoint->get().current.cruising_speed;

if (!PX4_ISFINITE(_mc_cruise_speed) || (_mc_cruise_speed < 0.0f)) {
// use default
_mc_cruise_speed = _mc_cruise_default.get();
}

// get target waypoint.
matrix::Vector3f target;
map_projection_project(&_reference_position,
_sub_triplet_setpoint->get().current.lat, _sub_triplet_setpoint->get().current.lon, &target(0), &target(1));
target(2) = -(_sub_triplet_setpoint->get().current.alt - _reference_altitude);


_yaw_wp = _sub_triplet_setpoint->get().current.yaw;

if (!PX4_ISFINITE(_yaw_wp)) {
_yaw_wp = _yaw;

}

// Check if anything has changed. We do that by comparing the target
// setpoint to the previous target.
// TODO This is a hack and it would be much better if the navigator only sends out a waypoints once tthey have changed.

// dont't do any updates if the current target has not changed
if (!(fabsf(target(0) - _target(0)) > 0.001f || fabsf(target(1) - _target(1)) > 0.001f
|| fabsf(target(2) - _target(2)) > 0.001f)) {
// nothing has changed: just keep old waypoints
return true;
}

// update all waypoints
_target = target;

if (!PX4_ISFINITE(_target(0)) || !PX4_ISFINITE(_target(1))) {
// Horizontal target is not finite. */
_target(0) = _position(0);
_target(1) = _position(1);
}

if (!PX4_ISFINITE(_target(2))) {
_target(2) = _position(2);
}

_prev_prev_wp = _prev_wp;

if (_isFinite(_sub_triplet_setpoint->get().previous) && _sub_triplet_setpoint->get().previous.valid) {
map_projection_project(&_reference_position, _sub_triplet_setpoint->get().previous.lat,
_sub_triplet_setpoint->get().previous.lon, &_prev_wp(0), &_prev_wp(1));
_prev_wp(2) = -(_sub_triplet_setpoint->get().previous.alt - _reference_altitude);

} else {
_prev_wp = _position;
}

if (_type == WaypointType::loiter) {
_next_wp = _target;

} else if (_isFinite(_sub_triplet_setpoint->get().next) && _sub_triplet_setpoint->get().next.valid) {
map_projection_project(&_reference_position, _sub_triplet_setpoint->get().next.lat,
_sub_triplet_setpoint->get().next.lon, &_next_wp(0), &_next_wp(1));
_next_wp(2) = -(_sub_triplet_setpoint->get().next.alt - _reference_altitude);

} else {
_next_wp = _target;
}

return true;
}

bool FlightTaskAuto::_isFinite(const position_setpoint_s sp)
{
return (PX4_ISFINITE(sp.lat) && PX4_ISFINITE(sp.lon) && PX4_ISFINITE(sp.alt));
}

void FlightTaskAuto::_evaluateVehicleGlobalPosition()
{
FlightTask::_evaluateVehicleLocalPosition();

// check if reference has changed and update.
if (_sub_vehicle_local_position->get().ref_timestamp != _time_stamp_reference) {
map_projection_init(&_reference_position,
_sub_vehicle_local_position->get().ref_lat,
_sub_vehicle_local_position->get().ref_lon);
_reference_altitude = _sub_vehicle_local_position->get().ref_alt;
_time_stamp_reference = _sub_vehicle_local_position->get().ref_timestamp;
}
}
96 changes: 96 additions & 0 deletions src/lib/FlightTasks/tasks/FlightTaskAuto.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,96 @@
/****************************************************************************
*
* Copyright (c) 2018 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 FlightTaskAuto.hpp
*
* Map from global triplet to local quadruple.
*/

#pragma once

#include "FlightTask.hpp"
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/position_setpoint.h>
#include <lib/ecl/geo/geo.h>

/**
* This enum has to agree with position_setpoint_s type definition
* The only reason for not using the struct position_setpoint is because
* of the size
*/
enum class WaypointType : int {
position = 0,
velocity,
loiter,
takeoff,
land,
idle
};

class FlightTaskAuto : public FlightTask
{
public:
FlightTaskAuto() = default;

virtual ~FlightTaskAuto() = default;
bool initializeSubscriptions(SubscriptionArray &subscription_array) override;
bool activate() override;
bool updateInitialize() override;

protected:
matrix::Vector3f _prev_prev_wp{}; /**< Pre-previous waypoint (local frame). This will be used for smoothing trajectories -> not used yet. */
matrix::Vector3f _prev_wp{}; /**< Previous waypoint (local frame). If no previous triplet is available, the prev_wp is set to current position. */
matrix::Vector3f _target{}; /**< Target waypoint (local frame).*/
matrix::Vector3f _next_wp{}; /**< The next waypoint after target (local frame). If no next setpoint is available, next is set to target. */
float _yaw_wp{0.0f}; /**< Triplet yaw waypoint. Currently it is not a yaw-waypoint, but rather a yaw setpoint at each time stamp. */
float _mc_cruise_speed{0.0f}; /**< Requested cruise speed. If not valid, default cruise speed is used. */
WaypointType _type{WaypointType::idle}; /**< Type of current target triplet. */

private:
uORB::Subscription<position_setpoint_triplet_s> *_sub_triplet_setpoint{nullptr};

DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTask,
(ParamFloat<px4::params::MPC_XY_CRUISE>) _mc_cruise_default); /**< Default mc cruise speed.*/

map_projection_reference_s _reference; /**< Reference frame from global to local. */

map_projection_reference_s _reference_position{}; /**< Structure used to project lat/lon setpoint into local frame. */
float _reference_altitude = 0.0f; /**< Altitude relative to ground. */
hrt_abstime _time_stamp_reference = 0; /**< time stamp when last reference update occured. */

bool _evaluateTriplets(); /**< Checks and sets triplets. */
bool _isFinite(const position_setpoint_s sp); /**< Checks if all waypoint triplets are finite. */
void _updateReference(); /**< Updates the local reference. */
void _evaluateVehicleGlobalPosition(); /**< Checks if global position is valid. */
};
Loading