Browse Source

FlightTaskAutoMapper: move remaining members into FlightTaskAutoLineSmooth

master
Matthias Grob 3 years ago
parent
commit
59a395f6a0
  1. 4
      src/modules/flight_mode_manager/tasks/AutoLineSmoothVel/FlightTaskAutoLineSmoothVel.cpp
  2. 12
      src/modules/flight_mode_manager/tasks/AutoLineSmoothVel/FlightTaskAutoLineSmoothVel.hpp
  3. 5
      src/modules/flight_mode_manager/tasks/AutoMapper/FlightTaskAutoMapper.cpp
  4. 14
      src/modules/flight_mode_manager/tasks/AutoMapper/FlightTaskAutoMapper.hpp

4
src/modules/flight_mode_manager/tasks/AutoLineSmoothVel/FlightTaskAutoLineSmoothVel.cpp

@ -40,6 +40,10 @@ @@ -40,6 +40,10 @@
using namespace matrix;
FlightTaskAutoLineSmoothVel::FlightTaskAutoLineSmoothVel() :
_sticks(this),
_stick_acceleration_xy(this)
{}
bool FlightTaskAutoLineSmoothVel::activate(const vehicle_local_position_setpoint_s &last_setpoint)
{

12
src/modules/flight_mode_manager/tasks/AutoLineSmoothVel/FlightTaskAutoLineSmoothVel.hpp

@ -42,11 +42,14 @@ @@ -42,11 +42,14 @@
#include "FlightTaskAutoMapper.hpp"
#include <motion_planning/PositionSmoothing.hpp>
#include "Sticks.hpp"
#include "StickAccelerationXY.hpp"
#include "StickYaw.hpp"
class FlightTaskAutoLineSmoothVel : public FlightTaskAutoMapper
{
public:
FlightTaskAutoLineSmoothVel() = default;
FlightTaskAutoLineSmoothVel();
virtual ~FlightTaskAutoLineSmoothVel() = default;
bool activate(const vehicle_local_position_setpoint_s &last_setpoint) override;
@ -92,6 +95,13 @@ protected: @@ -92,6 +95,13 @@ protected:
void updateParams() override; /**< See ModuleParam class */
Sticks _sticks;
StickAccelerationXY _stick_acceleration_xy;
StickYaw _stick_yaw;
matrix::Vector3f _land_position;
float _land_heading;
WaypointType _type_previous{WaypointType::idle}; /**< Previous type of current target triplet. */
DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTaskAutoMapper,
(ParamFloat<px4::params::MIS_YAW_ERR>) _param_mis_yaw_err, // yaw-error threshold
(ParamFloat<px4::params::MPC_ACC_HOR>) _param_mpc_acc_hor, // acceleration in flight

5
src/modules/flight_mode_manager/tasks/AutoMapper/FlightTaskAutoMapper.cpp

@ -36,8 +36,3 @@ @@ -36,8 +36,3 @@
*/
#include "FlightTaskAutoMapper.hpp"
FlightTaskAutoMapper::FlightTaskAutoMapper() :
_sticks(this),
_stick_acceleration_xy(this)
{}

14
src/modules/flight_mode_manager/tasks/AutoMapper/FlightTaskAutoMapper.hpp

@ -41,14 +41,11 @@ @@ -41,14 +41,11 @@
#pragma once
#include "FlightTaskAuto.hpp"
#include "Sticks.hpp"
#include "StickAccelerationXY.hpp"
#include "StickYaw.hpp"
class FlightTaskAutoMapper : public FlightTaskAuto
{
public:
FlightTaskAutoMapper();
FlightTaskAutoMapper() = default;
virtual ~FlightTaskAutoMapper() = default;
protected:
@ -65,13 +62,4 @@ protected: @@ -65,13 +62,4 @@ protected:
_param_mpc_tko_ramp_t, // time constant for smooth takeoff ramp
(ParamFloat<px4::params::MPC_MAN_Y_MAX>) _param_mpc_man_y_max
);
protected:
Sticks _sticks;
StickAccelerationXY _stick_acceleration_xy;
StickYaw _stick_yaw;
matrix::Vector3f _land_position;
float _land_heading;
WaypointType _type_previous{WaypointType::idle}; /**< Previous type of current target triplet. */
};

Loading…
Cancel
Save