Browse Source

FlighTasks: remove FlightTaskSport

This mode was just kept as an example after
its usage in a single case. It's basically untested
and doesn't make much sense anymore since it's
incompatible with the jerk limited trajectory
implementations. It's implementation only switched
hte configuration parameter of the velocity resulting
from maximum stick deflection to be
MPC_XY_VEL_MAX instead of MPC_VEL_MANUAL.
This is according to todays understanding undesired
because when hitting that limit the position
controller has no room for corrections anymore.

Also it saves some flash space on omnibus to remove
the task at this point and makes romm for the
acceleration feed-forward.
sbg
Matthias Grob 5 years ago
parent
commit
91057fe024
  1. 1
      src/lib/flight_tasks/CMakeLists.txt
  2. 43
      src/lib/flight_tasks/tasks/Sport/CMakeLists.txt
  3. 64
      src/lib/flight_tasks/tasks/Sport/FlightTaskSport.hpp
  4. 6
      src/modules/mc_pos_control/mc_pos_control_main.cpp
  5. 3
      src/modules/mc_pos_control/mc_pos_control_params.c

1
src/lib/flight_tasks/CMakeLists.txt

@ -57,7 +57,6 @@ list(APPEND flight_tasks_all @@ -57,7 +57,6 @@ list(APPEND flight_tasks_all
ManualPosition
ManualPositionSmooth
ManualPositionSmoothVel
Sport
AutoLineSmoothVel
AutoFollowMe
Offboard

43
src/lib/flight_tasks/tasks/Sport/CMakeLists.txt

@ -1,43 +0,0 @@ @@ -1,43 +0,0 @@
############################################################################
#
# 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.
#
############################################################################
# create header only library
add_library(FlightTaskSport INTERFACE)
# include header directory
target_include_directories(FlightTaskSport
INTERFACE
${CMAKE_CURRENT_SOURCE_DIR}
)
target_link_libraries(FlightTaskSport INTERFACE FlightTaskManual)

64
src/lib/flight_tasks/tasks/Sport/FlightTaskSport.hpp

@ -1,64 +0,0 @@ @@ -1,64 +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 FlightTaskSport.hpp
*
* Manual controlled position with maximum speed and no smoothing.
*/
#pragma once
#include "FlightTaskManualPosition.hpp"
#include "mathlib/mathlib.h"
#include <float.h>
using namespace matrix;
class FlightTaskSport : public FlightTaskManualPosition
{
public:
FlightTaskSport() = default;
virtual ~FlightTaskSport() = default;
bool activate(vehicle_local_position_setpoint_s last_setpoint) override
{
bool ret = FlightTaskManualPosition::activate(last_setpoint);
// default constraints already are the maximum allowed limits
_setDefaultConstraints();
return ret;
}
};

6
src/modules/mc_pos_control/mc_pos_control_main.cpp

@ -42,6 +42,7 @@ @@ -42,6 +42,7 @@
#include <lib/flight_tasks/FlightTasks.hpp>
#include <lib/hysteresis/hysteresis.h>
#include <lib/mathlib/mathlib.h>
#include <lib/matrix/matrix/math.hpp>
#include <lib/perf/perf_counter.h>
#include <lib/systemlib/mavlink_log.h>
#include <lib/weather_vane/WeatherVane.hpp>
@ -74,6 +75,7 @@ @@ -74,6 +75,7 @@
#include <float.h>
using namespace time_literals;
using namespace matrix;
/**
* Multicopter position control app start / stop handling function
@ -849,10 +851,6 @@ MulticopterPositionControl::start_flight_task() @@ -849,10 +851,6 @@ MulticopterPositionControl::start_flight_task()
error = _flight_tasks.switchTask(FlightTaskIndex::ManualPositionSmooth);
break;
case 2:
error = _flight_tasks.switchTask(FlightTaskIndex::Sport);
break;
case 3:
error = _flight_tasks.switchTask(FlightTaskIndex::ManualPositionSmoothVel);
break;

3
src/modules/mc_pos_control/mc_pos_control_params.c

@ -449,7 +449,7 @@ PARAM_DEFINE_FLOAT(MPC_VELD_LP, 5.0f); @@ -449,7 +449,7 @@ PARAM_DEFINE_FLOAT(MPC_VELD_LP, 5.0f);
/**
* Maximum horizontal acceleration for auto mode and for manual mode
*
* Maximum deceleration for MPC_POS_MODE 1 and 2. Maximum acceleration and deceleration for MPC_POS_MODE 3.
* Maximum deceleration for MPC_POS_MODE 1. Maximum acceleration and deceleration for MPC_POS_MODE 3.
*
* @unit m/s/s
* @min 2.0
@ -719,7 +719,6 @@ PARAM_DEFINE_FLOAT(MPC_TKO_RAMP_T, 3.0f); @@ -719,7 +719,6 @@ PARAM_DEFINE_FLOAT(MPC_TKO_RAMP_T, 3.0f);
*
* @value 0 Default position control
* @value 1 Smooth position control
* @value 2 Sport position control
* @value 3 Smooth position control (Velocity)
* @group Multicopter Position Control
*/

Loading…
Cancel
Save