Skip to content

Commit

Permalink
land_detector: Implement ModuleParams inheritance in the FixedwingLan…
Browse files Browse the repository at this point in the history
…dDetector class.
  • Loading branch information
mcsauder authored and dagar committed Jun 28, 2019
1 parent 0b2af5c commit c22ed93
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 38 deletions.
34 changes: 15 additions & 19 deletions src/modules/land_detector/FixedwingLandDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,30 +51,25 @@ namespace land_detector

FixedwingLandDetector::FixedwingLandDetector()
{
_paramHandle.maxVelocity = param_find("LNDFW_VEL_XY_MAX");
_paramHandle.maxClimbRate = param_find("LNDFW_VEL_Z_MAX");
_paramHandle.maxAirSpeed = param_find("LNDFW_AIRSPD_MAX");
_paramHandle.maxXYAccel = param_find("LNDFW_XYACC_MAX");

// Use Trigger time when transitioning from in-air (false) to landed (true) / ground contact (true).
_landed_hysteresis.set_hysteresis_time_from(false, LANDED_TRIGGER_TIME_US);

_landed_hysteresis.set_hysteresis_time_from(true, FLYING_TRIGGER_TIME_US);
}

void FixedwingLandDetector::_update_topics()
{
_airspeedSub.update(&_airspeed);
_airspeed_sub.update(&_airspeed);
_sensor_bias_sub.update(&_sensor_bias);
_vehicle_local_position_sub.update(&_vehicle_local_position);
}

void FixedwingLandDetector::_update_params()
{
param_get(_paramHandle.maxVelocity, &_params.maxVelocity);
param_get(_paramHandle.maxClimbRate, &_params.maxClimbRate);
param_get(_paramHandle.maxAirSpeed, &_params.maxAirSpeed);
param_get(_paramHandle.maxXYAccel, &_params.maxXYAccel);
parameter_update_s param_update;

if (_param_update_sub.update(&param_update)) {
_update_params();
}
}

float FixedwingLandDetector::_get_max_altitude()
Expand All @@ -96,15 +91,15 @@ bool FixedwingLandDetector::_get_landed_state()

if (hrt_elapsed_time(&_vehicle_local_position.timestamp) < 500 * 1000) {

// horizontal velocity
// Horizontal velocity complimentary filter.
float val = 0.97f * _velocity_xy_filtered + 0.03f * sqrtf(_vehicle_local_position.vx * _vehicle_local_position.vx +
_vehicle_local_position.vy * _vehicle_local_position.vy);

if (PX4_ISFINITE(val)) {
_velocity_xy_filtered = val;
}

// vertical velocity
// Vertical velocity complimentary filter.
val = 0.99f * _velocity_z_filtered + 0.01f * fabsf(_vehicle_local_position.vz);

if (PX4_ISFINITE(val)) {
Expand All @@ -113,17 +108,18 @@ bool FixedwingLandDetector::_get_landed_state()

_airspeed_filtered = 0.95f * _airspeed_filtered + 0.05f * _airspeed.true_airspeed_m_s;

// a leaking lowpass prevents biases from building up, but
// gives a mostly correct response for short impulses
// A leaking lowpass prevents biases from building up, but
// gives a mostly correct response for short impulses.
const float acc_hor = sqrtf(_sensor_bias.accel_x * _sensor_bias.accel_x +
_sensor_bias.accel_y * _sensor_bias.accel_y);

_accel_horz_lp = _accel_horz_lp * 0.8f + acc_hor * 0.18f;

// crude land detector for fixedwing
landDetected = _velocity_xy_filtered < _params.maxVelocity
&& _velocity_z_filtered < _params.maxClimbRate
&& _airspeed_filtered < _params.maxAirSpeed
&& _accel_horz_lp < _params.maxXYAccel;
landDetected = _accel_horz_lp < _param_lndfw_xyaccel_max.get()
&& _airspeed_filtered < _param_lndfw_airspd.get()
&& _velocity_xy_filtered < _param_lndfw_vel_xy_max.get()
&& _velocity_z_filtered < _param_lndfw_vel_z_max.get();

} else {
// Control state topic has timed out and we need to assume we're landed.
Expand Down
32 changes: 14 additions & 18 deletions src/modules/land_detector/FixedwingLandDetector.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,32 +73,28 @@ class FixedwingLandDetector final : public LandDetector
static constexpr hrt_abstime LANDED_TRIGGER_TIME_US = 2_s;
static constexpr hrt_abstime FLYING_TRIGGER_TIME_US = 0_us;

struct {
param_t maxVelocity;
param_t maxClimbRate;
param_t maxAirSpeed;
param_t maxXYAccel;
} _paramHandle{};

struct {
float maxVelocity;
float maxClimbRate;
float maxAirSpeed;
float maxXYAccel;
} _params{};

uORB::Subscription _airspeedSub{ORB_ID(airspeed)};
uORB::Subscription _airspeed_sub{ORB_ID(airspeed)};
uORB::Subscription _param_update_sub{ORB_ID(parameter_update)};
uORB::Subscription _sensor_bias_sub{ORB_ID(sensor_bias)};
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position});
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};

airspeed_s _airspeed{};
sensor_bias_s _sensor_bias{};
vehicle_local_position_s _vehicle_local_position{};

float _accel_horz_lp{0.0f};
float _airspeed_filtered{0.0f};
float _velocity_xy_filtered{0.0f};
float _velocity_z_filtered{0.0f};
float _airspeed_filtered{0.0f};
float _accel_horz_lp{0.0f};

DEFINE_PARAMETERS_CUSTOM_PARENT(
LandDetector,
(ParamFloat<px4::params::LNDFW_XYACC_MAX>) _param_lndfw_xyaccel_max,
(ParamFloat<px4::params::LNDFW_AIRSPD_MAX>) _param_lndfw_airspd,
(ParamFloat<px4::params::LNDFW_VEL_XY_MAX>) _param_lndfw_vel_xy_max,
(ParamFloat<px4::params::LNDFW_VEL_Z_MAX>) _param_lndfw_vel_z_max
);

};

} // namespace land_detector
3 changes: 2 additions & 1 deletion src/modules/land_detector/LandDetector.h
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,8 @@ class LandDetector : public ModuleBase<LandDetector>, ModuleParams, px4::Schedul
uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)};
uORB::Subscription _param_update_sub{ORB_ID(parameter_update)};

DEFINE_PARAMETERS(
DEFINE_PARAMETERS_CUSTOM_PARENT(
ModuleParams,
(ParamInt<px4::params::LND_FLIGHT_T_HI>) _param_total_flight_time_high,
(ParamInt<px4::params::LND_FLIGHT_T_LO>) _param_total_flight_time_low
);
Expand Down

0 comments on commit c22ed93

Please sign in to comment.