FlightTaskAuto/Mapper/Line: move landing gear to mapper; fix comments

This commit is contained in:
Dennis Mannhart 2018-07-31 10:32:50 +02:00 committed by ChristophTobler
parent 338ca3104c
commit a06ff4a2ce
5 changed files with 25 additions and 31 deletions

View File

@ -57,7 +57,7 @@ enum class WaypointType : int {
takeoff,
land,
idle,
offboard, // only part of this structure due to legacy reason. It is not used
offboard, // only part of this structure due to legacy reason. It is not used within the Auto flighttasks
follow_target
};
@ -105,13 +105,16 @@ protected:
private:
matrix::Vector2f _lock_position_xy{NAN, NAN};
matrix::Vector2f _lock_position_xy{NAN, NAN}; /**< if no valid triplet is received, lock positition to current position */
uORB::Subscription<position_setpoint_triplet_s> *_sub_triplet_setpoint{nullptr};
matrix::Vector3f _triplet_target; /**< current triplet from navigator which may differ from the intenal one (_target) depending on the vehicle state. */
matrix::Vector3f _triplet_prev_wp; /**< previous triplet from navigator which may differ from the intenal one (_prev_wp) depending on the vehicle state.*/
matrix::Vector3f _triplet_next_wp; /**< next triplet from navigator which may differ from the intenal one (_next_wp) depending on the vehicle state.*/
matrix::Vector3f
_triplet_target; /**< current triplet from navigator which may differ from the intenal one (_target) depending on the vehicle state. */
matrix::Vector3f
_triplet_prev_wp; /**< previous triplet from navigator which may differ from the intenal one (_prev_wp) depending on the vehicle state.*/
matrix::Vector3f
_triplet_next_wp; /**< next triplet from navigator which may differ from the intenal one (_next_wp) depending on the vehicle state.*/
matrix::Vector2f _closest_pt; /**< closest point to the vehicle position on the line previous - target */
map_projection_reference_s _reference_position{}; /**< Structure used to project lat/lon setpoint into local frame. */

View File

@ -40,19 +40,13 @@
using namespace matrix;
#define SIGMA_SINGLE_OP 0.000001f
#define SIGMA_NORM 0.001f
static constexpr float SIGMA_SINGLE_OP = 0.000001f;
static constexpr float SIGMA_NORM = 0.001f;
void FlightTaskAutoLine::_generateSetpoints()
{
_generateAltitudeSetpoints();
_generateXYsetpoints();
// during mission and reposition, raise the landing gears but only
// if altitude is high enough
if (_highEnoughForLandingGear()) {
_constraints.landing_gear = vehicle_constraints_s::GEAR_UP;
}
}
void FlightTaskAutoLine::_generateXYsetpoints()
@ -238,10 +232,3 @@ void FlightTaskAutoLine::_generateAltitudeSetpoints()
_position_setpoint(2) = _target(2);
}
}
bool FlightTaskAutoLine::_highEnoughForLandingGear()
{
// return true if altitude is above two meters
return _alt_above_ground > 2.0f;
}

View File

@ -57,13 +57,8 @@ protected:
(ParamFloat<px4::params::MPC_ACC_DOWN_MAX>) MPC_ACC_DOWN_MAX
);
void _generateSetpoints() override;
void _generateSetpoints() override; /**< Generate setpoints along line. */
void _generateAltitudeSetpoints(); /**< Generate velocity and position setpoints for following line along z. */
void _generateXYsetpoints(); /**< Generate velocity and position setpoints for following line along xy. */
private:
bool _highEnoughForLandingGear(); /**< Checks if gears can be lowered. */
};

View File

@ -40,8 +40,6 @@
using namespace matrix;
bool FlightTaskAutoMapper::activate()
{
bool ret = FlightTaskAuto::activate();
@ -88,6 +86,12 @@ bool FlightTaskAutoMapper::update()
_generateVelocitySetpoints();
}
// during mission and reposition, raise the landing gears but only
// if altitude is high enough
if (_highEnoughForLandingGear()) {
_constraints.landing_gear = vehicle_constraints_s::GEAR_UP;
}
// update previous type
_type_previous = _type;
@ -165,3 +169,9 @@ void FlightTaskAutoMapper::updateParams()
// make sure that alt1 is above alt2
MPC_LAND_ALT1.set(math::max(MPC_LAND_ALT1.get(), MPC_LAND_ALT2.get()));
}
bool FlightTaskAutoMapper::_highEnoughForLandingGear()
{
// return true if altitude is above two meters
return _alt_above_ground > 2.0f;
}

View File

@ -42,7 +42,6 @@
#include "FlightTaskAuto.hpp"
class FlightTaskAutoMapper : public FlightTaskAuto
{
public:
@ -76,5 +75,5 @@ protected:
private:
void _reset(); /**< Resets member variables to current vehicle state */
WaypointType _type_previous{WaypointType::idle}; /**< Previous type of current target triplet. */
bool _highEnoughForLandingGear(); /**< Checks if gears can be lowered. */
};