aboutsummaryrefslogtreecommitdiff
path: root/src/modules/land_detector/FixedwingLandDetector.cpp
diff options
context:
space:
mode:
authorJohan Jansen <jnsn.johan@gmail.com>2015-01-07 23:19:35 +0100
committerJohan Jansen <jnsn.johan@gmail.com>2015-01-15 14:37:51 +0100
commit10a2dd8a346a6a08a0d9b52739f20b842d460646 (patch)
tree206dad6badb67c73a5e5e9f922d92b3754d8d736 /src/modules/land_detector/FixedwingLandDetector.cpp
parent784fa9f4699c434671edfd1e4fb48897bea54d8f (diff)
downloadpx4-firmware-10a2dd8a346a6a08a0d9b52739f20b842d460646.tar.gz
px4-firmware-10a2dd8a346a6a08a0d9b52739f20b842d460646.tar.bz2
px4-firmware-10a2dd8a346a6a08a0d9b52739f20b842d460646.zip
LandDetector: Merged fixedwing and multicopter into one module handling both algorithms
Diffstat (limited to 'src/modules/land_detector/FixedwingLandDetector.cpp')
-rw-r--r--src/modules/land_detector/FixedwingLandDetector.cpp103
1 files changed, 103 insertions, 0 deletions
diff --git a/src/modules/land_detector/FixedwingLandDetector.cpp b/src/modules/land_detector/FixedwingLandDetector.cpp
new file mode 100644
index 000000000..42735f38c
--- /dev/null
+++ b/src/modules/land_detector/FixedwingLandDetector.cpp
@@ -0,0 +1,103 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 FixedwingLandDetector.cpp
+ * Land detection algorithm for fixedwings
+ *
+ * @author Johan Jansen <jnsn.johan@gmail.com>
+ */
+
+#include "FixedwingLandDetector.h"
+
+#include <cmath>
+#include <drivers/drv_hrt.h>
+
+FixedwingLandDetector::FixedwingLandDetector() :
+ _vehicleLocalPositionSub(-1),
+ _vehicleLocalPosition({}),
+ _airspeedSub(-1),
+ _airspeed({}),
+
+ _velocity_xy_filtered(0.0f),
+ _velocity_z_filtered(0.0f),
+ _airspeed_filtered(0.0f),
+ _landDetectTrigger(0)
+{
+ //ctor
+}
+
+void FixedwingLandDetector::initialize()
+{
+ //Subscribe to local position and airspeed data
+ _vehicleLocalPositionSub = orb_subscribe(ORB_ID(vehicle_local_position));
+ _airspeedSub = orb_subscribe(ORB_ID(airspeed));
+}
+
+void FixedwingLandDetector::updateSubscriptions()
+{
+ orb_update(ORB_ID(vehicle_local_position), _vehicleLocalPositionSub, &_vehicleLocalPosition);
+ orb_update(ORB_ID(airspeed), _airspeedSub, &_airspeed);
+}
+
+bool FixedwingLandDetector::update()
+{
+ //First poll for new data from our subscriptions
+ updateSubscriptions();
+
+ const uint64_t now = hrt_absolute_time();
+ bool landDetected = false;
+
+ //TODO: reset filtered values on arming?
+ _velocity_xy_filtered = 0.95f * _velocity_xy_filtered + 0.05f * sqrtf(_vehicleLocalPosition.vx *
+ _vehicleLocalPosition.vx + _vehicleLocalPosition.vy * _vehicleLocalPosition.vy);
+ _velocity_z_filtered = 0.95f * _velocity_z_filtered + 0.05f * fabsf(_vehicleLocalPosition.vz);
+ _airspeed_filtered = 0.95f * _airspeed_filtered + 0.05f * _airspeed.true_airspeed_m_s;
+
+ /* crude land detector for fixedwing */
+ if (_velocity_xy_filtered < FW_LAND_DETECTOR_VELOCITY_MAX
+ && _velocity_z_filtered < FW_LAND_DETECTOR_CLIMBRATE_MAX
+ && _airspeed_filtered < FW_LAND_DETECTOR_AIRSPEED_MAX) {
+
+ //These conditions need to be stable for a period of time before we trust them
+ if (now > _landDetectTrigger) {
+ landDetected = true;
+ }
+
+ } else {
+ //reset land detect trigger
+ _landDetectTrigger = now + FW_LAND_DETECTOR_TRIGGER_TIME;
+ }
+
+ return landDetected;
+}