Browse Source

Land detector: Move back to more agile raw airspeed

sbg
Lorenz Meier 9 years ago
parent
commit
515d81b8d6
  1. 9
      src/modules/land_detector/FixedwingLandDetector.cpp
  2. 5
      src/modules/land_detector/FixedwingLandDetector.h

9
src/modules/land_detector/FixedwingLandDetector.cpp

@ -50,11 +50,13 @@ FixedwingLandDetector::FixedwingLandDetector() : LandDetector(), @@ -50,11 +50,13 @@ FixedwingLandDetector::FixedwingLandDetector() : LandDetector(),
_paramHandle(),
_params(),
_controlStateSub(-1),
_controlState{},
_vehicleStatusSub(-1),
_armingSub(-1),
_airspeedSub(-1),
_controlState{},
_vehicleStatus{},
_arming{},
_airspeed{},
_parameterSub(-1),
_velocity_xy_filtered(0.0f),
_velocity_z_filtered(0.0f),
@ -76,6 +78,7 @@ void FixedwingLandDetector::initialize() @@ -76,6 +78,7 @@ void FixedwingLandDetector::initialize()
_controlStateSub = orb_subscribe(ORB_ID(control_state));
_vehicleStatusSub = orb_subscribe(ORB_ID(vehicle_status));
_armingSub = orb_subscribe(ORB_ID(actuator_armed));
_airspeedSub = orb_subscribe(ORB_ID(airspeed));
updateParameterCache(true);
}
@ -85,6 +88,7 @@ void FixedwingLandDetector::updateSubscriptions() @@ -85,6 +88,7 @@ void FixedwingLandDetector::updateSubscriptions()
orb_update(ORB_ID(control_state), _controlStateSub, &_controlState);
orb_update(ORB_ID(vehicle_status), _vehicleStatusSub, &_vehicleStatus);
orb_update(ORB_ID(actuator_armed), _armingSub, &_arming);
orb_update(ORB_ID(airspeed), _airspeedSub, &_airspeed);
}
bool FixedwingLandDetector::update()
@ -117,7 +121,7 @@ bool FixedwingLandDetector::update() @@ -117,7 +121,7 @@ bool FixedwingLandDetector::update()
_velocity_z_filtered = val;
}
_airspeed_filtered = 0.95f * _airspeed_filtered + 0.05f * _controlState.airspeed;
_airspeed_filtered = 0.95f * _airspeed_filtered + 0.05f * _airspeed.true_airspeed_m_s;
if (_lastTime != 0) {
/* a leaking integrator prevents biases from building up, but
@ -125,6 +129,7 @@ bool FixedwingLandDetector::update() @@ -125,6 +129,7 @@ bool FixedwingLandDetector::update()
*/
_accel_x_integral = _accel_x_integral * 0.8f + _controlState.horz_acc_mag * 0.18f;
}
}
// crude land detector for fixedwing

5
src/modules/land_detector/FixedwingLandDetector.h

@ -46,6 +46,7 @@ @@ -46,6 +46,7 @@
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/airspeed.h>
#include <systemlib/param/param.h>
class FixedwingLandDetector : public LandDetector
@ -94,11 +95,13 @@ private: @@ -94,11 +95,13 @@ private:
private:
int _controlStateSub; /**< notification of local position */
struct control_state_s _controlState; /**< the result from local position subscription */
int _vehicleStatusSub;
int _armingSub;
int _airspeedSub;
struct control_state_s _controlState; /**< the result from local position subscription */
struct vehicle_status_s _vehicleStatus;
struct actuator_armed_s _arming;
struct airspeed_s _airspeed;
int _parameterSub;
float _velocity_xy_filtered;

Loading…
Cancel
Save