aboutsummaryrefslogtreecommitdiff
path: root/src/modules/navigator
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-07-07 00:05:29 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-07-07 00:05:29 +0200
commit5559e568b6e5502ad51ec96fd531876c1191d641 (patch)
treebc6356b5bed0481cced4a7d7e7ef99bd225d91a7 /src/modules/navigator
parent863385dbc4243c8ecb19890a0dfce4a0b7ead9d6 (diff)
parentd67089b23f58ac152253f58c5deaebbd57db0362 (diff)
downloadpx4-firmware-safelink.tar.gz
px4-firmware-safelink.tar.bz2
px4-firmware-safelink.zip
Merged master into safelinksafelink
Diffstat (limited to 'src/modules/navigator')
-rw-r--r--src/modules/navigator/geofence.cpp298
-rw-r--r--src/modules/navigator/geofence.h94
-rw-r--r--src/modules/navigator/geofence_params.c60
-rw-r--r--src/modules/navigator/loiter.cpp78
-rw-r--r--src/modules/navigator/loiter.h74
-rw-r--r--src/modules/navigator/mission.cpp461
-rw-r--r--src/modules/navigator/mission.h178
-rw-r--r--src/modules/navigator/mission_block.cpp244
-rw-r--r--src/modules/navigator/mission_block.h106
-rw-r--r--src/modules/navigator/mission_feasibility_checker.cpp234
-rw-r--r--src/modules/navigator/mission_feasibility_checker.h86
-rw-r--r--src/modules/navigator/mission_params.c69
-rw-r--r--src/modules/navigator/module.mk18
-rw-r--r--src/modules/navigator/navigator.h219
-rw-r--r--src/modules/navigator/navigator_main.cpp677
-rw-r--r--src/modules/navigator/navigator_mode.cpp70
-rw-r--r--src/modules/navigator/navigator_mode.h86
-rw-r--r--src/modules/navigator/navigator_params.c31
-rw-r--r--src/modules/navigator/rtl.cpp320
-rw-r--r--src/modules/navigator/rtl.h110
-rw-r--r--src/modules/navigator/rtl_params.c98
21 files changed, 3224 insertions, 387 deletions
diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp
new file mode 100644
index 000000000..266215308
--- /dev/null
+++ b/src/modules/navigator/geofence.cpp
@@ -0,0 +1,298 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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 geofence.cpp
+ * Provides functions for handling the geofence
+ *
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+#include "geofence.h"
+
+#include <uORB/topics/vehicle_global_position.h>
+#include <string.h>
+#include <dataman/dataman.h>
+#include <systemlib/err.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <ctype.h>
+#include <nuttx/config.h>
+#include <unistd.h>
+
+
+/* Oddly, ERROR is not defined for C++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+Geofence::Geofence() :
+ SuperBlock(NULL, "GF"),
+ _fence_pub(-1),
+ _altitude_min(0),
+ _altitude_max(0),
+ _verticesCount(0),
+ param_geofence_on(this, "ON")
+{
+ /* Load initial params */
+ updateParams();
+}
+
+Geofence::~Geofence()
+{
+
+}
+
+
+bool Geofence::inside(const struct vehicle_global_position_s *vehicle)
+{
+ double lat = vehicle->lat / 1e7d;
+ double lon = vehicle->lon / 1e7d;
+ //float alt = vehicle->alt;
+
+ return inside(lat, lon, vehicle->alt);
+}
+
+bool Geofence::inside(double lat, double lon, float altitude)
+{
+ /* Return true if geofence is disabled */
+ if (param_geofence_on.get() != 1)
+ return true;
+
+ if (valid()) {
+
+ if (!isEmpty()) {
+ /* Vertical check */
+ if (altitude > _altitude_max || altitude < _altitude_min)
+ return false;
+
+ /*Horizontal check */
+ /* Adaptation of algorithm originally presented as
+ * PNPOLY - Point Inclusion in Polygon Test
+ * W. Randolph Franklin (WRF) */
+
+ bool c = false;
+
+ struct fence_vertex_s temp_vertex_i;
+ struct fence_vertex_s temp_vertex_j;
+
+ /* Red until fence is finished */
+ for (unsigned i = 0, j = _verticesCount - 1; i < _verticesCount; j = i++) {
+ if (dm_read(DM_KEY_FENCE_POINTS, i, &temp_vertex_i, sizeof(struct fence_vertex_s)) != sizeof(struct fence_vertex_s)) {
+ break;
+ }
+ if (dm_read(DM_KEY_FENCE_POINTS, j, &temp_vertex_j, sizeof(struct fence_vertex_s)) != sizeof(struct fence_vertex_s)) {
+ break;
+ }
+
+ // skip vertex 0 (return point)
+ if (((double)temp_vertex_i.lon >= lon) != ((double)temp_vertex_j.lon >= lon) &&
+ (lat <= (double)(temp_vertex_j.lat - temp_vertex_i.lat) * (lon - (double)temp_vertex_i.lon) /
+ (double)(temp_vertex_j.lon - temp_vertex_i.lon) + (double)temp_vertex_i.lat)) {
+ c = !c;
+ }
+
+ }
+
+ return c;
+ } else {
+ /* Empty fence --> accept all points */
+ return true;
+ }
+
+ } else {
+ /* Invalid fence --> accept all points */
+ return true;
+ }
+}
+
+bool
+Geofence::valid()
+{
+ // NULL fence is valid
+ if (isEmpty())
+ return true;
+
+ // Otherwise
+ if ((_verticesCount < 4) || (_verticesCount > GEOFENCE_MAX_VERTICES)) {
+ warnx("Fence must have at least 3 sides and not more than %d", GEOFENCE_MAX_VERTICES - 1);
+ return false;
+ }
+
+ return true;
+}
+
+void
+Geofence::addPoint(int argc, char *argv[])
+{
+ int ix, last;
+ double lon, lat;
+ struct fence_vertex_s vertex;
+ char *end;
+
+ if ((argc == 1) && (strcmp("-clear", argv[0]) == 0)) {
+ dm_clear(DM_KEY_FENCE_POINTS);
+ publishFence(0);
+ return;
+ }
+
+ if (argc < 3)
+ errx(1, "Specify: -clear | sequence latitude longitude [-publish]");
+
+ ix = atoi(argv[0]);
+ if (ix >= DM_KEY_FENCE_POINTS_MAX)
+ errx(1, "Sequence must be less than %d", DM_KEY_FENCE_POINTS_MAX);
+
+ lat = strtod(argv[1], &end);
+ lon = strtod(argv[2], &end);
+
+ last = 0;
+ if ((argc > 3) && (strcmp(argv[3], "-publish") == 0))
+ last = 1;
+
+ vertex.lat = (float)lat;
+ vertex.lon = (float)lon;
+
+ if (dm_write(DM_KEY_FENCE_POINTS, ix, DM_PERSIST_POWER_ON_RESET, &vertex, sizeof(vertex)) == sizeof(vertex)) {
+ if (last)
+ publishFence((unsigned)ix + 1);
+ return;
+ }
+
+ errx(1, "can't store fence point");
+}
+
+void
+Geofence::publishFence(unsigned vertices)
+{
+ if (_fence_pub == -1)
+ _fence_pub = orb_advertise(ORB_ID(fence), &vertices);
+ else
+ orb_publish(ORB_ID(fence), _fence_pub, &vertices);
+}
+
+int
+Geofence::loadFromFile(const char *filename)
+{
+ FILE *fp;
+ char line[120];
+ int pointCounter = 0;
+ bool gotVertical = false;
+ const char commentChar = '#';
+
+ /* Make sure no data is left in the datamanager */
+ clearDm();
+
+ /* open the mixer definition file */
+ fp = fopen(GEOFENCE_FILENAME, "r");
+ if (fp == NULL) {
+ return ERROR;
+ }
+
+ /* create geofence points from valid lines and store in DM */
+ for (;;) {
+
+ /* get a line, bail on error/EOF */
+ if (fgets(line, sizeof(line), fp) == NULL)
+ break;
+
+ /* Trim leading whitespace */
+ size_t textStart = 0;
+ while((textStart < sizeof(line)/sizeof(char)) && isspace(line[textStart])) textStart++;
+
+ /* if the line starts with #, skip */
+ if (line[textStart] == commentChar)
+ continue;
+
+ if (gotVertical) {
+ /* Parse the line as a geofence point */
+ struct fence_vertex_s vertex;
+
+ /* if the line starts with DMS, this means that the coordinate is given as degree minute second instead of decimal degrees */
+ if (line[textStart] == 'D' && line[textStart + 1] == 'M' && line[textStart + 2] == 'S') {
+ /* Handle degree minute second format */
+ float lat_d, lat_m, lat_s, lon_d, lon_m, lon_s;
+
+ if (sscanf(line, "DMS %f %f %f %f %f %f", &lat_d, &lat_m, &lat_s, &lon_d, &lon_m, &lon_s) != 6)
+ return ERROR;
+
+// warnx("Geofence DMS: %.5f %.5f %.5f ; %.5f %.5f %.5f", (double)lat_d, (double)lat_m, (double)lat_s, (double)lon_d, (double)lon_m, (double)lon_s);
+
+ vertex.lat = lat_d + lat_m/60.0f + lat_s/3600.0f;
+ vertex.lon = lon_d + lon_m/60.0f + lon_s/3600.0f;
+
+ } else {
+ /* Handle decimal degree format */
+
+ if (sscanf(line, "%f %f", &(vertex.lat), &(vertex.lon)) != 2)
+ return ERROR;
+ }
+
+ if (dm_write(DM_KEY_FENCE_POINTS, pointCounter, DM_PERSIST_POWER_ON_RESET, &vertex, sizeof(vertex)) != sizeof(vertex))
+ return ERROR;
+
+ warnx("Geofence: point: %d, lat %.5f: lon: %.5f", pointCounter, (double)vertex.lat, (double)vertex.lon);
+
+ pointCounter++;
+ } else {
+ /* Parse the line as the vertical limits */
+ if (sscanf(line, "%f %f", &_altitude_min, &_altitude_max) != 2)
+ return ERROR;
+
+
+ warnx("Geofence: alt min: %.4f, alt_max: %.4f", (double)_altitude_min, (double)_altitude_max);
+ gotVertical = true;
+ }
+
+
+ }
+
+ fclose(fp);
+
+ /* Check if import was successful */
+ if(gotVertical && pointCounter > 0)
+ {
+ _verticesCount = pointCounter;
+ warnx("Geofence: imported successfully");
+ } else {
+ warnx("Geofence: import error");
+ }
+
+ return ERROR;
+}
+
+int Geofence::clearDm()
+{
+ dm_clear(DM_KEY_FENCE_POINTS);
+ return OK;
+}
diff --git a/src/modules/navigator/geofence.h b/src/modules/navigator/geofence.h
new file mode 100644
index 000000000..2eb126ab5
--- /dev/null
+++ b/src/modules/navigator/geofence.h
@@ -0,0 +1,94 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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 geofence.h
+ * Provides functions for handling the geofence
+ *
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#ifndef GEOFENCE_H_
+#define GEOFENCE_H_
+
+#include <uORB/topics/fence.h>
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#define GEOFENCE_FILENAME "/fs/microsd/etc/geofence.txt"
+
+class Geofence : public control::SuperBlock
+{
+private:
+ orb_advert_t _fence_pub; /**< publish fence topic */
+
+ float _altitude_min;
+ float _altitude_max;
+
+ unsigned _verticesCount;
+
+ /* Params */
+ control::BlockParamInt param_geofence_on;
+public:
+ Geofence();
+ ~Geofence();
+
+ /**
+ * Return whether craft is inside geofence.
+ *
+ * Calculate whether point is inside arbitrary polygon
+ * @param craft pointer craft coordinates
+ * @param fence pointer to array of coordinates, one per vertex. First and last vertex are assumed connected
+ * @return true: craft is inside fence, false:craft is outside fence
+ */
+ bool inside(const struct vehicle_global_position_s *craft);
+ bool inside(double lat, double lon, float altitude);
+
+ int clearDm();
+
+ bool valid();
+
+ /**
+ * Specify fence vertex position.
+ */
+ void addPoint(int argc, char *argv[]);
+
+ void publishFence(unsigned vertices);
+
+ int loadFromFile(const char *filename);
+
+ bool isEmpty() {return _verticesCount == 0;}
+};
+
+
+#endif /* GEOFENCE_H_ */
diff --git a/src/modules/navigator/geofence_params.c b/src/modules/navigator/geofence_params.c
new file mode 100644
index 000000000..653b1ad84
--- /dev/null
+++ b/src/modules/navigator/geofence_params.c
@@ -0,0 +1,60 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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 geofence_params.c
+ *
+ * Parameters for geofence
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * Geofence parameters, accessible via MAVLink
+ */
+
+/**
+ * Enable geofence.
+ *
+ * Set to 1 to enable geofence.
+ * Defaults to 1 because geofence is only enabled when the geofence.txt file is present.
+ *
+ * @min 0
+ * @max 1
+ * @group Geofence
+ */
+PARAM_DEFINE_INT32(GF_ON, 1);
diff --git a/src/modules/navigator/loiter.cpp b/src/modules/navigator/loiter.cpp
new file mode 100644
index 000000000..542483fb1
--- /dev/null
+++ b/src/modules/navigator/loiter.cpp
@@ -0,0 +1,78 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 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 loiter.cpp
+ *
+ * Helper class to loiter
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+
+#include "loiter.h"
+
+Loiter::Loiter(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name)
+{
+ /* load initial params */
+ updateParams();
+ /* initial reset */
+ on_inactive();
+}
+
+Loiter::~Loiter()
+{
+}
+
+bool
+Loiter::on_active(struct position_setpoint_triplet_s *pos_sp_triplet)
+{
+ /* set loiter item, don't reuse an existing position setpoint */
+ return set_loiter_item(pos_sp_triplet);
+}
+
+void
+Loiter::on_inactive()
+{
+}
diff --git a/src/modules/navigator/loiter.h b/src/modules/navigator/loiter.h
new file mode 100644
index 000000000..65ff5c31e
--- /dev/null
+++ b/src/modules/navigator/loiter.h
@@ -0,0 +1,74 @@
+/***************************************************************************
+ *
+ * Copyright (c) 2014 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 loiter.h
+ *
+ * Helper class to loiter
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#ifndef NAVIGATOR_LOITER_H
+#define NAVIGATOR_LOITER_H
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include "navigator_mode.h"
+#include "mission_block.h"
+
+class Loiter : public MissionBlock
+{
+public:
+ /**
+ * Constructor
+ */
+ Loiter(Navigator *navigator, const char *name);
+
+ /**
+ * Destructor
+ */
+ ~Loiter();
+
+ /**
+ * This function is called while the mode is inactive
+ */
+ virtual void on_inactive();
+
+ /**
+ * This function is called while the mode is active
+ */
+ virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet);
+};
+
+#endif
diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp
new file mode 100644
index 000000000..72255103b
--- /dev/null
+++ b/src/modules/navigator/mission.cpp
@@ -0,0 +1,461 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 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 navigator_mission.cpp
+ *
+ * Helper class to access missions
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#include <sys/types.h>
+#include <string.h>
+#include <stdlib.h>
+#include <unistd.h>
+
+#include <drivers/drv_hrt.h>
+
+#include <dataman/dataman.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/mission_result.h>
+
+#include "navigator.h"
+#include "mission.h"
+
+Mission::Mission(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name),
+ _param_onboard_enabled(this, "ONBOARD_EN"),
+ _onboard_mission({0}),
+ _offboard_mission({0}),
+ _current_onboard_mission_index(-1),
+ _current_offboard_mission_index(-1),
+ _mission_result_pub(-1),
+ _mission_result({0}),
+ _mission_type(MISSION_TYPE_NONE)
+{
+ /* load initial params */
+ updateParams();
+ /* set initial mission items */
+ on_inactive();
+
+}
+
+Mission::~Mission()
+{
+}
+
+void
+Mission::on_inactive()
+{
+ _first_run = true;
+
+ /* check anyway if missions have changed so that feedback to groundstation is given */
+ bool onboard_updated;
+ orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated);
+ if (onboard_updated) {
+ update_onboard_mission();
+ }
+
+ bool offboard_updated;
+ orb_check(_navigator->get_offboard_mission_sub(), &offboard_updated);
+ if (offboard_updated) {
+ update_offboard_mission();
+ }
+}
+
+bool
+Mission::on_active(struct position_setpoint_triplet_s *pos_sp_triplet)
+{
+ bool updated = false;
+
+ /* check if anything has changed */
+ bool onboard_updated;
+ orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated);
+ if (onboard_updated) {
+ update_onboard_mission();
+ }
+
+ bool offboard_updated;
+ orb_check(_navigator->get_offboard_mission_sub(), &offboard_updated);
+ if (offboard_updated) {
+ update_offboard_mission();
+ }
+
+ /* reset mission items if needed */
+ if (onboard_updated || offboard_updated || _first_run) {
+ set_mission_items(pos_sp_triplet);
+ updated = true;
+ _first_run = false;
+ }
+
+ /* lets check if we reached the current mission item */
+ if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) {
+ advance_mission();
+ set_mission_items(pos_sp_triplet);
+ updated = true;
+ }
+
+ return updated;
+}
+
+void
+Mission::update_onboard_mission()
+{
+ if (orb_copy(ORB_ID(onboard_mission), _navigator->get_onboard_mission_sub(), &_onboard_mission) == OK) {
+ /* accept the current index set by the onboard mission if it is within bounds */
+ if (_onboard_mission.current_index >=0
+ && _onboard_mission.current_index < (int)_onboard_mission.count) {
+ _current_onboard_mission_index = _onboard_mission.current_index;
+ } else {
+ /* if less WPs available, reset to first WP */
+ if (_current_onboard_mission_index >= (int)_onboard_mission.count) {
+ _current_onboard_mission_index = 0;
+ /* if not initialized, set it to 0 */
+ } else if (_current_onboard_mission_index < 0) {
+ _current_onboard_mission_index = 0;
+ }
+ /* otherwise, just leave it */
+ }
+ } else {
+ _onboard_mission.count = 0;
+ _onboard_mission.current_index = 0;
+ _current_onboard_mission_index = 0;
+ }
+}
+
+void
+Mission::update_offboard_mission()
+{
+ if (orb_copy(ORB_ID(offboard_mission), _navigator->get_offboard_mission_sub(), &_offboard_mission) == OK) {
+
+ /* determine current index */
+ if (_offboard_mission.current_index >= 0
+ && _offboard_mission.current_index < (int)_offboard_mission.count) {
+ _current_offboard_mission_index = _offboard_mission.current_index;
+ } else {
+ /* if less WPs available, reset to first WP */
+ if (_current_offboard_mission_index >= (int)_offboard_mission.count) {
+ _current_offboard_mission_index = 0;
+ /* if not initialized, set it to 0 */
+ } else if (_current_offboard_mission_index < 0) {
+ _current_offboard_mission_index = 0;
+ }
+ /* otherwise, just leave it */
+ }
+
+ /* Check mission feasibility, for now do not handle the return value,
+ * however warnings are issued to the gcs via mavlink from inside the MissionFeasiblityChecker */
+ dm_item_t dm_current;
+
+ if (_offboard_mission.dataman_id == 0) {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ } else {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ }
+
+ missionFeasiblityChecker.checkMissionFeasible(_navigator->get_vstatus()->is_rotary_wing, dm_current,
+ (size_t)_offboard_mission.count,
+ _navigator->get_geofence(),
+ _navigator->get_home_position()->alt);
+ } else {
+ _offboard_mission.count = 0;
+ _offboard_mission.current_index = 0;
+ _current_offboard_mission_index = 0;
+ }
+ report_current_offboard_mission_item();
+}
+
+
+void
+Mission::advance_mission()
+{
+ switch (_mission_type) {
+ case MISSION_TYPE_ONBOARD:
+ _current_onboard_mission_index++;
+ break;
+
+ case MISSION_TYPE_OFFBOARD:
+ _current_offboard_mission_index++;
+ break;
+
+ case MISSION_TYPE_NONE:
+ default:
+ break;
+ }
+}
+
+void
+Mission::set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet)
+{
+ set_previous_pos_setpoint(pos_sp_triplet);
+
+ /* try setting onboard mission item */
+ if (is_current_onboard_mission_item_set(&pos_sp_triplet->current)) {
+ /* if mission type changed, notify */
+ if (_mission_type != MISSION_TYPE_ONBOARD) {
+ mavlink_log_info(_navigator->get_mavlink_fd(),
+ "#audio: onboard mission running");
+ }
+ _mission_type = MISSION_TYPE_ONBOARD;
+ _navigator->set_can_loiter_at_sp(false);
+
+ /* try setting offboard mission item */
+ } else if (is_current_offboard_mission_item_set(&pos_sp_triplet->current)) {
+ /* if mission type changed, notify */
+ if (_mission_type != MISSION_TYPE_OFFBOARD) {
+ mavlink_log_info(_navigator->get_mavlink_fd(),
+ "#audio: offboard mission running");
+ }
+ _mission_type = MISSION_TYPE_OFFBOARD;
+ _navigator->set_can_loiter_at_sp(false);
+ } else {
+ if (_mission_type != MISSION_TYPE_NONE) {
+ mavlink_log_info(_navigator->get_mavlink_fd(),
+ "#audio: mission finished");
+ } else {
+ mavlink_log_info(_navigator->get_mavlink_fd(),
+ "#audio: no mission available");
+ }
+ _mission_type = MISSION_TYPE_NONE;
+ _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached);
+
+ set_loiter_item(pos_sp_triplet);
+ reset_mission_item_reached();
+ report_mission_finished();
+ }
+}
+
+bool
+Mission::is_current_onboard_mission_item_set(struct position_setpoint_s *current_pos_sp)
+{
+ /* make sure param is up to date */
+ updateParams();
+ if (_param_onboard_enabled.get() > 0 &&
+ _current_onboard_mission_index >= 0&&
+ _current_onboard_mission_index < (int)_onboard_mission.count) {
+ struct mission_item_s new_mission_item;
+ if (read_mission_item(DM_KEY_WAYPOINTS_ONBOARD, true, &_current_onboard_mission_index,
+ &new_mission_item)) {
+ /* convert the current mission item and set it valid */
+ mission_item_to_position_setpoint(&new_mission_item, current_pos_sp);
+ current_pos_sp->valid = true;
+
+ reset_mission_item_reached();
+
+ /* TODO: report this somehow */
+ memcpy(&_mission_item, &new_mission_item, sizeof(struct mission_item_s));
+ return true;
+ }
+ }
+ return false;
+}
+
+bool
+Mission::is_current_offboard_mission_item_set(struct position_setpoint_s *current_pos_sp)
+{
+ if (_current_offboard_mission_index >= 0 &&
+ _current_offboard_mission_index < (int)_offboard_mission.count) {
+ dm_item_t dm_current;
+ if (_offboard_mission.dataman_id == 0) {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ } else {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ }
+ struct mission_item_s new_mission_item;
+ if (read_mission_item(dm_current, true, &_current_offboard_mission_index, &new_mission_item)) {
+ /* convert the current mission item and set it valid */
+ mission_item_to_position_setpoint(&new_mission_item, current_pos_sp);
+ current_pos_sp->valid = true;
+
+ reset_mission_item_reached();
+
+ report_current_offboard_mission_item();
+ memcpy(&_mission_item, &new_mission_item, sizeof(struct mission_item_s));
+ return true;
+ }
+ }
+ return false;
+}
+
+void
+Mission::get_next_onboard_mission_item(struct position_setpoint_s *next_pos_sp)
+{
+ int next_temp_mission_index = _onboard_mission.current_index + 1;
+
+ /* try if there is a next onboard mission */
+ if (_onboard_mission.current_index >= 0 &&
+ next_temp_mission_index < (int)_onboard_mission.count) {
+ struct mission_item_s new_mission_item;
+ if (read_mission_item(DM_KEY_WAYPOINTS_ONBOARD, false, &next_temp_mission_index, &new_mission_item)) {
+ /* convert next mission item to position setpoint */
+ mission_item_to_position_setpoint(&new_mission_item, next_pos_sp);
+ next_pos_sp->valid = true;
+ return;
+ }
+ }
+
+ /* give up */
+ next_pos_sp->valid = false;
+ return;
+}
+
+void
+Mission::get_next_offboard_mission_item(struct position_setpoint_s *next_pos_sp)
+{
+ /* try if there is a next offboard mission */
+ int next_temp_mission_index = _offboard_mission.current_index + 1;
+ warnx("next index: %d, count; %d", next_temp_mission_index, _offboard_mission.count);
+ if (_offboard_mission.current_index >= 0 &&
+ next_temp_mission_index < (int)_offboard_mission.count) {
+ dm_item_t dm_current;
+ if (_offboard_mission.dataman_id == 0) {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ } else {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ }
+ struct mission_item_s new_mission_item;
+ if (read_mission_item(dm_current, false, &next_temp_mission_index, &new_mission_item)) {
+ /* convert next mission item to position setpoint */
+ mission_item_to_position_setpoint(&new_mission_item, next_pos_sp);
+ next_pos_sp->valid = true;
+ return;
+ }
+ }
+ /* give up */
+ next_pos_sp->valid = false;
+ return;
+}
+
+bool
+Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *mission_index,
+ struct mission_item_s *new_mission_item)
+{
+ /* repeat several to get the mission item because we might have to follow multiple DO_JUMPS */
+ for (int i=0; i<10; i++) {
+ const ssize_t len = sizeof(struct mission_item_s);
+
+ /* read mission item from datamanager */
+ if (dm_read(dm_item, *mission_index, new_mission_item, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ mavlink_log_critical(_navigator->get_mavlink_fd(),
+ "#audio: ERROR waypoint could not be read");
+ return false;
+ }
+
+ /* check for DO_JUMP item, and whether it hasn't not already been repeated enough times */
+ if (new_mission_item->nav_cmd == NAV_CMD_DO_JUMP) {
+
+ /* do DO_JUMP as many times as requested */
+ if (new_mission_item->do_jump_current_count < new_mission_item->do_jump_repeat_count) {
+
+ /* only raise the repeat count if this is for the current mission item
+ * but not for the next mission item */
+ if (is_current) {
+ (new_mission_item->do_jump_current_count)++;
+ /* save repeat count */
+ if (dm_write(dm_item, *mission_index, DM_PERSIST_IN_FLIGHT_RESET,
+ new_mission_item, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the
+ * dataman */
+ mavlink_log_critical(_navigator->get_mavlink_fd(),
+ "#audio: ERROR DO JUMP waypoint could not be written");
+ return false;
+ }
+ }
+ /* set new mission item index and repeat
+ * we don't have to validate here, if it's invalid, we should realize this later .*/
+ *mission_index = new_mission_item->do_jump_mission_index;
+ } else {
+ mavlink_log_info(_navigator->get_mavlink_fd(),
+ "#audio: DO JUMP repetitions completed");
+ /* no more DO_JUMPS, therefore just try to continue with next mission item */
+ (*mission_index)++;
+ }
+
+ } else {
+ /* if it's not a DO_JUMP, then we were successful */
+ return true;
+ }
+ }
+
+ /* we have given up, we don't want to cycle forever */
+ mavlink_log_critical(_navigator->get_mavlink_fd(),
+ "#audio: ERROR DO JUMP is cycling, giving up");
+ return false;
+}
+
+void
+Mission::report_mission_item_reached()
+{
+ if (_mission_type == MISSION_TYPE_OFFBOARD) {
+ _mission_result.mission_reached = true;
+ _mission_result.mission_index_reached = _current_offboard_mission_index;
+ }
+ publish_mission_result();
+}
+
+void
+Mission::report_current_offboard_mission_item()
+{
+ _mission_result.index_current_mission = _current_offboard_mission_index;
+ publish_mission_result();
+}
+
+void
+Mission::report_mission_finished()
+{
+ _mission_result.mission_finished = true;
+ publish_mission_result();
+}
+
+void
+Mission::publish_mission_result()
+{
+ /* lazily publish the mission result only once available */
+ if (_mission_result_pub > 0) {
+ /* publish mission result */
+ orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);
+
+ } else {
+ /* advertise and publish */
+ _mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
+ }
+ /* reset reached bool */
+ _mission_result.mission_reached = false;
+ _mission_result.mission_finished = false;
+}
diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h
new file mode 100644
index 000000000..6e4761946
--- /dev/null
+++ b/src/modules/navigator/mission.h
@@ -0,0 +1,178 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 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 mission.h
+ *
+ * Navigator mode to access missions
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#ifndef NAVIGATOR_MISSION_H
+#define NAVIGATOR_MISSION_H
+
+#include <drivers/drv_hrt.h>
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <dataman/dataman.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+#include <uORB/topics/home_position.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/mission_result.h>
+
+#include "navigator_mode.h"
+#include "mission_block.h"
+#include "mission_feasibility_checker.h"
+
+class Navigator;
+
+class Mission : public MissionBlock
+{
+public:
+ /**
+ * Constructor
+ */
+ Mission(Navigator *navigator, const char *name);
+
+ /**
+ * Destructor
+ */
+ virtual ~Mission();
+
+ /**
+ * This function is called while the mode is inactive
+ */
+ virtual void on_inactive();
+
+ /**
+ * This function is called while the mode is active
+ */
+ virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet);
+
+private:
+ /**
+ * Update onboard mission topic
+ */
+ void update_onboard_mission();
+
+ /**
+ * Update offboard mission topic
+ */
+ void update_offboard_mission();
+
+ /**
+ * Move on to next mission item or switch to loiter
+ */
+ void advance_mission();
+
+ /**
+ * Set new mission items
+ */
+ void set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet);
+
+ /**
+ * Try to set the current position setpoint from an onboard mission item
+ * @return true if mission item successfully set
+ */
+ bool is_current_onboard_mission_item_set(struct position_setpoint_s *current_pos_sp);
+
+ /**
+ * Try to set the current position setpoint from an offboard mission item
+ * @return true if mission item successfully set
+ */
+ bool is_current_offboard_mission_item_set(struct position_setpoint_s *current_pos_sp);
+
+ /**
+ * Try to set the next position setpoint from an onboard mission item
+ */
+ void get_next_onboard_mission_item(struct position_setpoint_s *next_pos_sp);
+
+ /**
+ * Try to set the next position setpoint from an offboard mission item
+ */
+ void get_next_offboard_mission_item(struct position_setpoint_s *next_pos_sp);
+
+ /**
+ * Read a mission item from the dataman and watch out for DO_JUMPS
+ * @return true if successful
+ */
+ bool read_mission_item(const dm_item_t dm_item, bool is_current, int *mission_index,
+ struct mission_item_s *new_mission_item);
+
+ /**
+ * Report that a mission item has been reached
+ */
+ void report_mission_item_reached();
+
+ /**
+ * Rport the current mission item
+ */
+ void report_current_offboard_mission_item();
+
+ /**
+ * Report that the mission is finished if one exists or that none exists
+ */
+ void report_mission_finished();
+
+ /**
+ * Publish the mission result so commander and mavlink know what is going on
+ */
+ void publish_mission_result();
+
+ control::BlockParamFloat _param_onboard_enabled;
+
+ struct mission_s _onboard_mission;
+ struct mission_s _offboard_mission;
+
+ int _current_onboard_mission_index;
+ int _current_offboard_mission_index;
+
+ orb_advert_t _mission_result_pub;
+ struct mission_result_s _mission_result;
+
+ enum {
+ MISSION_TYPE_NONE,
+ MISSION_TYPE_ONBOARD,
+ MISSION_TYPE_OFFBOARD
+ } _mission_type;
+
+ MissionFeasibilityChecker missionFeasiblityChecker; /**< class that checks if a mission is feasible */
+};
+
+#endif
diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp
new file mode 100644
index 000000000..26a573544
--- /dev/null
+++ b/src/modules/navigator/mission_block.cpp
@@ -0,0 +1,244 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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 mission_block.cpp
+ *
+ * Helper class to use mission items
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#include <sys/types.h>
+#include <string.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <math.h>
+#include <float.h>
+
+#include <systemlib/err.h>
+#include <geo/geo.h>
+
+#include <uORB/uORB.h>
+
+#include "navigator.h"
+#include "mission_block.h"
+
+
+MissionBlock::MissionBlock(Navigator *navigator, const char *name) :
+ NavigatorMode(navigator, name),
+ _waypoint_position_reached(false),
+ _waypoint_yaw_reached(false),
+ _time_first_inside_orbit(0),
+ _mission_item({0}),
+ _mission_item_valid(false)
+{
+}
+
+MissionBlock::~MissionBlock()
+{
+}
+
+bool
+MissionBlock::is_mission_item_reached()
+{
+ if (_mission_item.nav_cmd == NAV_CMD_LAND) {
+ return _navigator->get_vstatus()->condition_landed;
+ }
+
+ /* TODO: count turns */
+ if ((/*_mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||*/
+ _mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED)) {
+ return false;
+ }
+
+ hrt_abstime now = hrt_absolute_time();
+
+ if (!_waypoint_position_reached) {
+
+ float dist = -1.0f;
+ float dist_xy = -1.0f;
+ float dist_z = -1.0f;
+
+ float altitude_amsl = _mission_item.altitude_is_relative
+ ? _mission_item.altitude + _navigator->get_home_position()->alt
+ : _mission_item.altitude;
+
+ dist = get_distance_to_point_global_wgs84(_mission_item.lat, _mission_item.lon, altitude_amsl,
+ _navigator->get_global_position()->lat,
+ _navigator->get_global_position()->lon,
+ _navigator->get_global_position()->alt,
+ &dist_xy, &dist_z);
+
+ if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF && _navigator->get_vstatus()->is_rotary_wing) {
+ /* require only altitude for takeoff for multicopter */
+ if (_navigator->get_global_position()->alt >
+ altitude_amsl - _navigator->get_acceptance_radius()) {
+ _waypoint_position_reached = true;
+ }
+ } else if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF) {
+ /* for takeoff mission items use the parameter for the takeoff acceptance radius */
+ if (dist >= 0.0f && dist <= _navigator->get_acceptance_radius()) {
+ _waypoint_position_reached = true;
+ }
+ } else {
+ /* for normal mission items used their acceptance radius */
+ if (dist >= 0.0f && dist <= _mission_item.acceptance_radius) {
+ _waypoint_position_reached = true;
+ }
+ }
+ }
+
+ if (_waypoint_position_reached && !_waypoint_yaw_reached) {
+
+ /* TODO: removed takeoff, why? */
+ if (_navigator->get_vstatus()->is_rotary_wing && isfinite(_mission_item.yaw)) {
+
+ /* check yaw if defined only for rotary wing except takeoff */
+ float yaw_err = _wrap_pi(_mission_item.yaw - _navigator->get_global_position()->yaw);
+
+ if (fabsf(yaw_err) < 0.2f) { /* TODO: get rid of magic number */
+ _waypoint_yaw_reached = true;
+ }
+
+ } else {
+ _waypoint_yaw_reached = true;
+ }
+ }
+
+ /* check if the current waypoint was reached */
+ if (_waypoint_position_reached && _waypoint_yaw_reached) {
+
+ if (_time_first_inside_orbit == 0) {
+ _time_first_inside_orbit = now;
+
+ // if (_mission_item.time_inside > 0.01f) {
+ // mavlink_log_info(_mavlink_fd, "#audio: waypoint reached, wait for %.1fs",
+ // (double)_mission_item.time_inside);
+ // }
+ }
+
+ /* check if the MAV was long enough inside the waypoint orbit */
+ if (now - _time_first_inside_orbit >= (hrt_abstime)_mission_item.time_inside * 1e6f) {
+ return true;
+ }
+ }
+ return false;
+}
+
+void
+MissionBlock::reset_mission_item_reached()
+{
+ _waypoint_position_reached = false;
+ _waypoint_yaw_reached = false;
+ _time_first_inside_orbit = 0;
+}
+
+void
+MissionBlock::mission_item_to_position_setpoint(const struct mission_item_s *item, struct position_setpoint_s *sp)
+{
+ sp->valid = true;
+ sp->lat = item->lat;
+ sp->lon = item->lon;
+ sp->alt = item->altitude_is_relative ? item->altitude + _navigator->get_home_position()->alt : item->altitude;
+ sp->yaw = item->yaw;
+ sp->loiter_radius = item->loiter_radius;
+ sp->loiter_direction = item->loiter_direction;
+ sp->pitch_min = item->pitch_min;
+
+ switch (item->nav_cmd) {
+ case NAV_CMD_IDLE:
+ sp->type = SETPOINT_TYPE_IDLE;
+ break;
+
+ case NAV_CMD_TAKEOFF:
+ sp->type = SETPOINT_TYPE_TAKEOFF;
+ break;
+
+ case NAV_CMD_LAND:
+ sp->type = SETPOINT_TYPE_LAND;
+ break;
+
+ case NAV_CMD_LOITER_TIME_LIMIT:
+ case NAV_CMD_LOITER_TURN_COUNT:
+ case NAV_CMD_LOITER_UNLIMITED:
+ sp->type = SETPOINT_TYPE_LOITER;
+ break;
+
+ default:
+ sp->type = SETPOINT_TYPE_POSITION;
+ break;
+ }
+}
+
+void
+MissionBlock::set_previous_pos_setpoint(struct position_setpoint_triplet_s *pos_sp_triplet)
+{
+ /* reuse current setpoint as previous setpoint */
+ if (pos_sp_triplet->current.valid) {
+ memcpy(&pos_sp_triplet->previous, &pos_sp_triplet->current, sizeof(struct position_setpoint_s));
+ }
+}
+
+bool
+MissionBlock::set_loiter_item(struct position_setpoint_triplet_s *pos_sp_triplet)
+{
+ /* don't change setpoint if 'can_loiter_at_sp' flag set */
+ if (!(_navigator->get_can_loiter_at_sp() && pos_sp_triplet->current.valid)) {
+ /* use current position */
+ pos_sp_triplet->current.lat = _navigator->get_global_position()->lat;
+ pos_sp_triplet->current.lon = _navigator->get_global_position()->lon;
+ pos_sp_triplet->current.alt = _navigator->get_global_position()->alt;
+ pos_sp_triplet->current.yaw = NAN; /* NAN means to use current yaw */
+
+ _navigator->set_can_loiter_at_sp(true);
+ }
+
+ if (pos_sp_triplet->current.type != SETPOINT_TYPE_LOITER
+ || (fabsf(pos_sp_triplet->current.loiter_radius - _navigator->get_loiter_radius()) > FLT_EPSILON)
+ || pos_sp_triplet->current.loiter_direction != 1
+ || pos_sp_triplet->previous.valid
+ || !pos_sp_triplet->current.valid
+ || pos_sp_triplet->next.valid) {
+ /* position setpoint triplet should be updated */
+ pos_sp_triplet->current.type = SETPOINT_TYPE_LOITER;
+ pos_sp_triplet->current.loiter_radius = _navigator->get_loiter_radius();
+ pos_sp_triplet->current.loiter_direction = 1;
+
+ pos_sp_triplet->previous.valid = false;
+ pos_sp_triplet->current.valid = true;
+ pos_sp_triplet->next.valid = false;
+ return true;
+ }
+
+ return false;
+}
diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h
new file mode 100644
index 000000000..f99002752
--- /dev/null
+++ b/src/modules/navigator/mission_block.h
@@ -0,0 +1,106 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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 mission_block.h
+ *
+ * Helper class to use mission items
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#ifndef NAVIGATOR_MISSION_BLOCK_H
+#define NAVIGATOR_MISSION_BLOCK_H
+
+#include <drivers/drv_hrt.h>
+
+#include <uORB/topics/mission.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+
+#include "navigator_mode.h"
+
+class Navigator;
+
+class MissionBlock : public NavigatorMode
+{
+public:
+ /**
+ * Constructor
+ */
+ MissionBlock(Navigator *navigator, const char *name);
+
+ /**
+ * Destructor
+ */
+ virtual ~MissionBlock();
+
+ /**
+ * Check if mission item has been reached
+ * @return true if successfully reached
+ */
+ bool is_mission_item_reached();
+ /**
+ * Reset all reached flags
+ */
+ void reset_mission_item_reached();
+
+ /**
+ * Convert a mission item to a position setpoint
+ *
+ * @param the mission item to convert
+ * @param the position setpoint that needs to be set
+ */
+ void mission_item_to_position_setpoint(const mission_item_s *item, position_setpoint_s *sp);
+
+ /**
+ * Set previous position setpoint to current setpoint
+ */
+ void set_previous_pos_setpoint(struct position_setpoint_triplet_s *pos_sp_triplet);
+
+ /**
+ * Set a loiter item, if possible reuse the position setpoint, otherwise take the current position
+ *
+ * @param the position setpoint triplet to set
+ * @return true if setpoint has changed
+ */
+ bool set_loiter_item(position_setpoint_triplet_s *pos_sp_triplet);
+
+ bool _waypoint_position_reached;
+ bool _waypoint_yaw_reached;
+ hrt_abstime _time_first_inside_orbit;
+
+ mission_item_s _mission_item;
+ bool _mission_item_valid;
+};
+
+#endif
diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp
new file mode 100644
index 000000000..dd7f4c801
--- /dev/null
+++ b/src/modules/navigator/mission_feasibility_checker.cpp
@@ -0,0 +1,234 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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 mission_feasibility_checker.cpp
+ * Provides checks if mission is feasible given the navigation capabilities
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ */
+
+#include "mission_feasibility_checker.h"
+
+#include <geo/geo.h>
+#include <math.h>
+#include <mathlib/mathlib.h>
+#include <mavlink/mavlink_log.h>
+#include <fw_pos_control_l1/landingslope.h>
+#include <systemlib/err.h>
+#include <stdio.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <uORB/topics/fence.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+MissionFeasibilityChecker::MissionFeasibilityChecker() : _mavlink_fd(-1), _capabilities_sub(-1), _initDone(false)
+{
+ _nav_caps = {0};
+}
+
+
+bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
+{
+ /* Init if not done yet */
+ init();
+
+ /* Open mavlink fd */
+ if (_mavlink_fd < 0) {
+ /* try to open the mavlink log device every once in a while */
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ }
+
+
+ if (isRotarywing)
+ return checkMissionFeasibleRotarywing(dm_current, nMissionItems, geofence, home_alt);
+ else
+ return checkMissionFeasibleFixedwing(dm_current, nMissionItems, geofence, home_alt);
+}
+
+bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
+{
+
+ return (checkGeofence(dm_current, nMissionItems, geofence) && checkHomePositionAltitude(dm_current, nMissionItems, home_alt));
+}
+
+bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
+{
+ /* Update fixed wing navigation capabilites */
+ updateNavigationCapabilities();
+// warnx("_nav_caps.landing_slope_angle_rad %.4f, _nav_caps.landing_horizontal_slope_displacement %.4f", _nav_caps.landing_slope_angle_rad, _nav_caps.landing_horizontal_slope_displacement);
+
+ return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, geofence) && checkHomePositionAltitude(dm_current, nMissionItems, home_alt));
+}
+
+bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+{
+ /* Check if all mission items are inside the geofence (if we have a valid geofence) */
+ if (geofence.valid()) {
+ for (size_t i = 0; i < nMissionItems; i++) {
+ struct mission_item_s missionitem;
+ const ssize_t len = sizeof(missionitem);
+
+ if (dm_read(dm_current, i, &missionitem, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return false;
+ }
+
+ if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) {
+ mavlink_log_info(_mavlink_fd, "#audio: Geofence violation waypoint %d", i);
+ return false;
+ }
+ }
+ }
+
+ return true;
+}
+
+bool MissionFeasibilityChecker::checkHomePositionAltitude(dm_item_t dm_current, size_t nMissionItems, float home_alt, bool throw_error)
+{
+ /* Check if all all waypoints are above the home altitude, only return false if bool throw_error = true */
+ for (size_t i = 0; i < nMissionItems; i++) {
+ static struct mission_item_s missionitem;
+ const ssize_t len = sizeof(struct mission_item_s);
+
+ if (dm_read(dm_current, i, &missionitem, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ if (throw_error) {
+ return false;
+ } else {
+ return true;
+ }
+ }
+
+ if (home_alt > missionitem.altitude) {
+ if (throw_error) {
+ mavlink_log_info(_mavlink_fd, "Waypoint %d below home", i);
+ return false;
+ } else {
+ mavlink_log_info(_mavlink_fd, "#audio: warning waypoint %d below home", i);
+ return true;
+ }
+ }
+ }
+
+ return true;
+}
+
+bool MissionFeasibilityChecker::checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems)
+{
+ /* Go through all mission items and search for a landing waypoint
+ * if landing waypoint is found: the previous waypoint is checked to be at a feasible distance and altitude given the landing slope */
+
+
+ for (size_t i = 0; i < nMissionItems; i++) {
+ struct mission_item_s missionitem;
+ const ssize_t len = sizeof(missionitem);
+ if (dm_read(dm_current, i, &missionitem, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return false;
+ }
+
+ if (missionitem.nav_cmd == NAV_CMD_LAND) {
+ struct mission_item_s missionitem_previous;
+ if (i != 0) {
+ if (dm_read(dm_current, i-1, &missionitem_previous, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return false;
+ }
+
+ float wp_distance = get_distance_to_next_waypoint(missionitem_previous.lat , missionitem_previous.lon, missionitem.lat, missionitem.lon);
+ float slope_alt_req = Landingslope::getLandingSlopeAbsoluteAltitude(wp_distance, missionitem.altitude, _nav_caps.landing_horizontal_slope_displacement, _nav_caps.landing_slope_angle_rad);
+ float wp_distance_req = Landingslope::getLandingSlopeWPDistance(missionitem_previous.altitude, missionitem.altitude, _nav_caps.landing_horizontal_slope_displacement, _nav_caps.landing_slope_angle_rad);
+ float delta_altitude = missionitem.altitude - missionitem_previous.altitude;
+// warnx("wp_distance %.2f, delta_altitude %.2f, missionitem_previous.altitude %.2f, missionitem.altitude %.2f, slope_alt_req %.2f, wp_distance_req %.2f",
+// wp_distance, delta_altitude, missionitem_previous.altitude, missionitem.altitude, slope_alt_req, wp_distance_req);
+// warnx("_nav_caps.landing_horizontal_slope_displacement %.4f, _nav_caps.landing_slope_angle_rad %.4f, _nav_caps.landing_flare_length %.4f",
+// _nav_caps.landing_horizontal_slope_displacement, _nav_caps.landing_slope_angle_rad, _nav_caps.landing_flare_length);
+
+ if (wp_distance > _nav_caps.landing_flare_length) {
+ /* Last wp is before flare region */
+
+ if (delta_altitude < 0) {
+ if (missionitem_previous.altitude <= slope_alt_req) {
+ /* Landing waypoint is at or below altitude of slope at the given waypoint distance: this is ok, aircraft will intersect the slope */
+ return true;
+ } else {
+ /* Landing waypoint is above altitude of slope at the given waypoint distance */
+ mavlink_log_info(_mavlink_fd, "#audio: Landing: last waypoint too high/too close");
+ mavlink_log_info(_mavlink_fd, "Move down to %.1fm or move further away by %.1fm",
+ (double)(slope_alt_req),
+ (double)(wp_distance_req - wp_distance));
+ return false;
+ }
+ } else {
+ /* Landing waypoint is above last waypoint */
+ mavlink_log_info(_mavlink_fd, "#audio: Landing waypoint above last nav waypoint");
+ return false;
+ }
+ } else {
+ /* Last wp is in flare region */
+ //xxx give recommendations
+ mavlink_log_info(_mavlink_fd, "#audio: Warning: Landing: last waypoint in flare region");
+ return false;
+ }
+ } else {
+ mavlink_log_info(_mavlink_fd, "#audio: Warning: starting with land waypoint");
+ return false;
+ }
+ }
+ }
+
+
+// float slope_alt = wp_altitude + _H0 * expf(-math::max(0.0f, _flare_length - wp_distance)/_flare_constant) - _H1_virt;
+ return false;
+}
+
+void MissionFeasibilityChecker::updateNavigationCapabilities()
+{
+ (void)orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
+}
+
+void MissionFeasibilityChecker::init()
+{
+ if (!_initDone) {
+
+ _capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
+
+ _initDone = true;
+ }
+}
diff --git a/src/modules/navigator/mission_feasibility_checker.h b/src/modules/navigator/mission_feasibility_checker.h
new file mode 100644
index 000000000..96c9209d3
--- /dev/null
+++ b/src/modules/navigator/mission_feasibility_checker.h
@@ -0,0 +1,86 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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 mission_feasibility_checker.h
+ * Provides checks if mission is feasible given the navigation capabilities
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ */
+
+#ifndef MISSION_FEASIBILITY_CHECKER_H_
+#define MISSION_FEASIBILITY_CHECKER_H_
+
+#include <unistd.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/navigation_capabilities.h>
+#include <dataman/dataman.h>
+#include "geofence.h"
+
+
+class MissionFeasibilityChecker
+{
+private:
+ int _mavlink_fd;
+
+ int _capabilities_sub;
+ struct navigation_capabilities_s _nav_caps;
+
+ bool _initDone;
+ void init();
+
+ /* Checks for all airframes */
+ bool checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ bool checkHomePositionAltitude(dm_item_t dm_current, size_t nMissionItems, float home_alt, bool throw_error = false);
+
+ /* Checks specific to fixedwing airframes */
+ bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
+ bool checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems);
+ void updateNavigationCapabilities();
+
+ /* Checks specific to rotarywing airframes */
+ bool checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
+public:
+
+ MissionFeasibilityChecker();
+ ~MissionFeasibilityChecker() {}
+
+ /*
+ * Returns true if mission is feasible and false otherwise
+ */
+ bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
+
+};
+
+
+#endif /* MISSION_FEASIBILITY_CHECKER_H_ */
diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c
new file mode 100644
index 000000000..8692328db
--- /dev/null
+++ b/src/modules/navigator/mission_params.c
@@ -0,0 +1,69 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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 mission_params.c
+ *
+ * Parameters for mission.
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * Mission parameters, accessible via MAVLink
+ */
+
+/**
+ * Take-off altitude
+ *
+ * Even if first waypoint has altitude less then MIS_TAKEOFF_ALT above home position, system will climb to
+ * MIS_TAKEOFF_ALT on takeoff, then go to waypoint.
+ *
+ * @unit meters
+ * @group Mission
+ */
+PARAM_DEFINE_FLOAT(MIS_TAKEOFF_ALT, 10.0f);
+
+
+/**
+ * Enable onboard mission
+ *
+ * @min 0
+ * @max 1
+ * @group Mission
+ */
+PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 0);
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index 0404b06c7..a1e109030 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (c) 2013 PX4 Development Team. All rights reserved.
+# Copyright (c) 2013-2014 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
@@ -38,4 +38,18 @@
MODULE_COMMAND = navigator
SRCS = navigator_main.cpp \
- navigator_params.c
+ navigator_params.c \
+ navigator_mode.cpp \
+ mission_block.cpp \
+ mission.cpp \
+ mission_params.c \
+ loiter.cpp \
+ rtl.cpp \
+ rtl_params.c \
+ mission_feasibility_checker.cpp \
+ geofence.cpp \
+ geofence_params.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h
new file mode 100644
index 000000000..184ecd365
--- /dev/null
+++ b/src/modules/navigator/navigator.h
@@ -0,0 +1,219 @@
+/***************************************************************************
+ *
+ * Copyright (c) 2013-2014 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 navigator.h
+ * Helper class to access missions
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#ifndef NAVIGATOR_H
+#define NAVIGATOR_H
+
+#include <systemlib/perf_counter.h>
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/parameter_update.h>
+
+#include "navigator_mode.h"
+#include "mission.h"
+#include "loiter.h"
+#include "rtl.h"
+#include "geofence.h"
+
+/**
+ * Number of navigation modes that need on_active/on_inactive calls
+ * Currently: mission, loiter, and rtl
+ */
+#define NAVIGATOR_MODE_ARRAY_SIZE 3
+
+class Navigator : public control::SuperBlock
+{
+public:
+ /**
+ * Constructor
+ */
+ Navigator();
+
+ /**
+ * Destructor, also kills the navigators task.
+ */
+ ~Navigator();
+
+ /**
+ * Start the navigator task.
+ *
+ * @return OK on success.
+ */
+ int start();
+
+ /**
+ * Display the navigator status.
+ */
+ void status();
+
+ /**
+ * Add point to geofence
+ */
+ void add_fence_point(int argc, char *argv[]);
+
+ /**
+ * Load fence from file
+ */
+ void load_fence_from_file(const char *filename);
+
+ /**
+ * Setters
+ */
+ void set_can_loiter_at_sp(bool can_loiter) { _can_loiter_at_sp = can_loiter; }
+
+ /**
+ * Getters
+ */
+ struct vehicle_status_s* get_vstatus() { return &_vstatus; }
+ struct vehicle_global_position_s* get_global_position() { return &_global_pos; }
+ struct home_position_s* get_home_position() { return &_home_pos; }
+ int get_onboard_mission_sub() { return _onboard_mission_sub; }
+ int get_offboard_mission_sub() { return _offboard_mission_sub; }
+ Geofence& get_geofence() { return _geofence; }
+ bool get_can_loiter_at_sp() { return _can_loiter_at_sp; }
+ float get_loiter_radius() { return _param_loiter_radius.get(); }
+ float get_acceptance_radius() { return _param_acceptance_radius.get(); }
+ int get_mavlink_fd() { return _mavlink_fd; }
+
+private:
+
+ bool _task_should_exit; /**< if true, sensor task should exit */
+ int _navigator_task; /**< task handle for sensor task */
+
+ int _mavlink_fd; /**< the file descriptor to send messages over mavlink */
+
+ int _global_pos_sub; /**< global position subscription */
+ int _home_pos_sub; /**< home position subscription */
+ int _vstatus_sub; /**< vehicle status subscription */
+ int _capabilities_sub; /**< notification of vehicle capabilities updates */
+ int _control_mode_sub; /**< vehicle control mode subscription */
+ int _onboard_mission_sub; /**< onboard mission subscription */
+ int _offboard_mission_sub; /**< offboard mission subscription */
+ int _param_update_sub; /**< param update subscription */
+
+ orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */
+
+ vehicle_status_s _vstatus; /**< vehicle status */
+ vehicle_control_mode_s _control_mode; /**< vehicle control mode */
+ vehicle_global_position_s _global_pos; /**< global vehicle position */
+ home_position_s _home_pos; /**< home position for RTL */
+ mission_item_s _mission_item; /**< current mission item */
+ navigation_capabilities_s _nav_caps; /**< navigation capabilities */
+ position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */
+
+ bool _mission_item_valid; /**< flags if the current mission item is valid */
+
+ perf_counter_t _loop_perf; /**< loop performance counter */
+
+ Geofence _geofence; /**< class that handles the geofence */
+ bool _geofence_violation_warning_sent; /**< prevents spaming to mavlink */
+
+ bool _fence_valid; /**< flag if fence is valid */
+ bool _inside_fence; /**< vehicle is inside fence */
+
+ NavigatorMode *_navigation_mode; /**< abstract pointer to current navigation mode class */
+ Mission _mission; /**< class that handles the missions */
+ Loiter _loiter; /**< class that handles loiter */
+ RTL _rtl; /**< class that handles RTL */
+
+ NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE]; /**< array of navigation modes */
+
+ bool _can_loiter_at_sp; /**< flags if current position SP can be used to loiter */
+ bool _update_triplet; /**< flags if position SP triplet needs to be published */
+
+ control::BlockParamFloat _param_loiter_radius; /**< loiter radius for fixedwing */
+ control::BlockParamFloat _param_acceptance_radius; /**< acceptance for takeoff */
+ /**
+ * Retrieve global position
+ */
+ void global_position_update();
+
+ /**
+ * Retrieve home position
+ */
+ void home_position_update();
+
+ /**
+ * Retreive navigation capabilities
+ */
+ void navigation_capabilities_update();
+
+ /**
+ * Retrieve vehicle status
+ */
+ void vehicle_status_update();
+
+ /**
+ * Retrieve vehicle control mode
+ */
+ void vehicle_control_mode_update();
+
+ /**
+ * Update parameters
+ */
+ void params_update();
+
+ /**
+ * Shim for calling task_main from task_create.
+ */
+ static void task_main_trampoline(int argc, char *argv[]);
+
+ /**
+ * Main task.
+ */
+ void task_main();
+
+ /**
+ * Translate mission item to a position setpoint.
+ */
+ void mission_item_to_position_setpoint(const mission_item_s *item, position_setpoint_s *sp);
+
+ /**
+ * Publish a new position setpoint triplet for position controllers
+ */
+ void publish_position_setpoint_triplet();
+};
+#endif
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index f6c44444a..546602741 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
+ * Copyright (c) 2013, 2014 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
@@ -32,13 +31,19 @@
*
****************************************************************************/
/**
- * @file navigator_main.c
- * Implementation of the main navigation state machine.
+ * @file navigator_main.cpp
*
- * Handles missions, geo fencing and failsafe navigation behavior.
+ * Handles mission items, geo fencing and failsafe navigation behavior.
+ * Published the position setpoint triplet for the position controller.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <nuttx/config.h>
+
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -48,26 +53,29 @@
#include <math.h>
#include <poll.h>
#include <time.h>
+#include <sys/ioctl.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+
+#include <drivers/device/device.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
+
#include <uORB/uORB.h>
-#include <uORB/topics/airspeed.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_set_triplet.h>
-#include <uORB/topics/vehicle_attitude_setpoint.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/vehicle_rates_setpoint.h>
-#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/home_position.h>
#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/parameter_update.h>
#include <uORB/topics/mission.h>
-#include <systemlib/param/param.h>
+#include <uORB/topics/fence.h>
+#include <uORB/topics/navigation_capabilities.h>
+
#include <systemlib/err.h>
-#include <geo/geo.h>
-#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
+#include <geo/geo.h>
+#include <dataman/dataman.h>
#include <mathlib/mathlib.h>
+#include <mavlink/mavlink_log.h>
+
+#include "navigator.h"
/**
* navigator app start / stop handling function
@@ -76,169 +84,53 @@
*/
extern "C" __EXPORT int navigator_main(int argc, char *argv[]);
-class Navigator
-{
-public:
- /**
- * Constructor
- */
- Navigator();
-
- /**
- * Destructor, also kills the sensors task.
- */
- ~Navigator();
-
- /**
- * Start the sensors task.
- *
- * @return OK on success.
- */
- int start();
-
-private:
-
- bool _task_should_exit; /**< if true, sensor task should exit */
- int _navigator_task; /**< task handle for sensor task */
-
- int _global_pos_sub;
- int _att_sub; /**< vehicle attitude subscription */
- int _attitude_sub; /**< raw rc channels data subscription */
- int _airspeed_sub; /**< airspeed subscription */
- int _vstatus_sub; /**< vehicle status subscription */
- int _params_sub; /**< notification of parameter updates */
- int _manual_control_sub; /**< notification of manual control updates */
- int _mission_sub;
-
- orb_advert_t _triplet_pub; /**< position setpoint */
-
- struct vehicle_attitude_s _att; /**< vehicle attitude */
- struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
- struct manual_control_setpoint_s _manual; /**< r/c channel data */
- struct airspeed_s _airspeed; /**< airspeed */
- struct vehicle_status_s _vstatus; /**< vehicle status */
- struct vehicle_global_position_s _global_pos; /**< global vehicle position */
- struct vehicle_global_position_set_triplet_s _global_triplet; /**< triplet of global setpoints */
-
- perf_counter_t _loop_perf; /**< loop performance counter */
-
- unsigned _mission_items_maxcount; /**< maximum number of mission items supported */
- struct mission_item_s * _mission_items; /**< storage for mission items */
- bool _mission_valid; /**< flag if mission is valid */
-
- /** manual control states */
- float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */
- float _loiter_hold_lat;
- float _loiter_hold_lon;
- float _loiter_hold_alt;
- bool _loiter_hold;
-
- struct {
- float throttle_cruise;
- } _parameters; /**< local copies of interesting parameters */
-
- struct {
- param_t throttle_cruise;
-
- } _parameter_handles; /**< handles for interesting parameters */
-
-
- /**
- * Update our local parameter cache.
- */
- int parameters_update();
-
- /**
- * Update control outputs
- *
- */
- void control_update();
-
- /**
- * Check for changes in vehicle status.
- */
- void vehicle_status_poll();
-
- /**
- * Check for position updates.
- */
- void vehicle_attitude_poll();
-
- /**
- * Check for set triplet updates.
- */
- void mission_poll();
-
- /**
- * Control throttle.
- */
- float control_throttle(float energy_error);
-
- /**
- * Control pitch.
- */
- float control_pitch(float altitude_error);
-
- void calculate_airspeed_errors();
- void calculate_gndspeed_undershoot();
- void calculate_altitude_error();
-
- /**
- * Shim for calling task_main from task_create.
- */
- static void task_main_trampoline(int argc, char *argv[]);
-
- /**
- * Main sensor collection task.
- */
- void task_main() __attribute__((noreturn));
-};
namespace navigator
{
-/* oddly, ERROR is not defined for c++ */
-#ifdef ERROR
-# undef ERROR
-#endif
-static const int ERROR = -1;
-
Navigator *g_navigator;
}
Navigator::Navigator() :
-
+ SuperBlock(NULL, "NAV"),
_task_should_exit(false),
_navigator_task(-1),
-
-/* subscriptions */
+ _mavlink_fd(-1),
_global_pos_sub(-1),
- _att_sub(-1),
- _airspeed_sub(-1),
+ _home_pos_sub(-1),
_vstatus_sub(-1),
- _params_sub(-1),
- _manual_control_sub(-1),
-
-/* publications */
- _triplet_pub(-1),
-
-/* performance counters */
+ _capabilities_sub(-1),
+ _control_mode_sub(-1),
+ _onboard_mission_sub(-1),
+ _offboard_mission_sub(-1),
+ _pos_sp_triplet_pub(-1),
+ _vstatus({}),
+ _control_mode({}),
+ _global_pos({}),
+ _home_pos({}),
+ _mission_item({}),
+ _nav_caps({}),
+ _pos_sp_triplet({}),
+ _mission_item_valid(false),
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
-/* states */
- _mission_items_maxcount(20),
- _mission_valid(false),
- _loiter_hold(false)
+ _geofence({}),
+ _geofence_violation_warning_sent(false),
+ _fence_valid(false),
+ _inside_fence(true),
+ _navigation_mode(nullptr),
+ _mission(this, "MIS"),
+ _loiter(this, "LOI"),
+ _rtl(this, "RTL"),
+ _update_triplet(false),
+ _param_loiter_radius(this, "LOITER_RAD"),
+ _param_acceptance_radius(this, "ACC_RAD")
{
- _mission_items = (mission_item_s*)malloc(sizeof(mission_item_s) * _mission_items_maxcount);
- if (!_mission_items) {
- _mission_items_maxcount = 0;
- warnx("no free RAM to allocate mission, rejecting any waypoints");
- }
-
- _parameter_handles.throttle_cruise = param_find("NAV_DUMMY");
+ /* Create a list of our possible navigation types */
+ _navigation_mode_array[0] = &_mission;
+ _navigation_mode_array[1] = &_loiter;
+ _navigation_mode_array[2] = &_rtl;
- /* fetch initial parameter values */
- parameters_update();
+ updateParams();
}
Navigator::~Navigator()
@@ -266,70 +158,48 @@ Navigator::~Navigator()
navigator::g_navigator = nullptr;
}
-int
-Navigator::parameters_update()
+void
+Navigator::global_position_update()
{
-
- //param_get(_parameter_handles.throttle_cruise, &(_parameters.throttle_cruise));
-
- return OK;
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
}
void
-Navigator::vehicle_status_poll()
+Navigator::home_position_update()
{
- bool vstatus_updated;
-
- /* Check HIL state if vehicle status has changed */
- orb_check(_vstatus_sub, &vstatus_updated);
+ orb_copy(ORB_ID(home_position), _home_pos_sub, &_home_pos);
+}
- if (vstatus_updated) {
+void
+Navigator::navigation_capabilities_update()
+{
+ orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
+}
- orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
+void
+Navigator::vehicle_status_update()
+{
+ if (orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus) != OK) {
+ /* in case the commander is not be running */
+ _vstatus.arming_state = ARMING_STATE_STANDBY;
}
}
void
-Navigator::vehicle_attitude_poll()
+Navigator::vehicle_control_mode_update()
{
- /* check if there is a new position */
- bool att_updated;
- orb_check(_att_sub, &att_updated);
-
- if (att_updated) {
- orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
+ if (orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode) != OK) {
+ /* in case the commander is not be running */
+ _control_mode.flag_control_auto_enabled = false;
+ _control_mode.flag_armed = false;
}
}
void
-Navigator::mission_poll()
+Navigator::params_update()
{
- /* check if there is a new setpoint */
- bool mission_updated;
- orb_check(_mission_sub, &mission_updated);
-
- if (mission_updated) {
-
- struct mission_s mission;
- orb_copy(ORB_ID(mission), _mission_sub, &mission);
-
- // XXX this is not optimal yet, but a first prototype /
- // test implementation
-
- if (mission.count <= _mission_items_maxcount) {
- /*
- * Perform an atomic copy & state update
- */
- irqstate_t flags = irqsave();
-
- memcpy(_mission_items, mission.items, mission.count * sizeof(struct mission_item_s));
- _mission_valid = true;
-
- irqrestore(flags);
- } else {
- warnx("mission larger than storage space");
- }
- }
+ parameter_update_s param_update;
+ orb_copy(ORB_ID(parameter_update), _param_update_sub, &param_update);
}
void
@@ -341,196 +211,189 @@ Navigator::task_main_trampoline(int argc, char *argv[])
void
Navigator::task_main()
{
-
/* inform about start */
warnx("Initializing..");
- fflush(stdout);
- /*
- * do subscriptions
- */
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+
+ /* Try to load the geofence:
+ * if /fs/microsd/etc/geofence.txt load from this file
+ * else clear geofence data in datamanager */
+ struct stat buffer;
+
+ if (stat(GEOFENCE_FILENAME, &buffer) == 0) {
+ warnx("Try to load geofence.txt");
+ _geofence.loadFromFile(GEOFENCE_FILENAME);
+
+ } else {
+ if (_geofence.clearDm() > 0)
+ warnx("Geofence cleared");
+ else
+ warnx("Could not clear geofence");
+ }
+
+ /* do subscriptions */
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- _mission_sub = orb_subscribe(ORB_ID(mission));
- _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- _airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ _capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
- _params_sub = orb_subscribe(ORB_ID(parameter_update));
- _manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ _control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ _home_pos_sub = orb_subscribe(ORB_ID(home_position));
+ _onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission));
+ _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
+ _param_update_sub = orb_subscribe(ORB_ID(parameter_update));
+
+ /* copy all topics first time */
+ vehicle_status_update();
+ vehicle_control_mode_update();
+ global_position_update();
+ home_position_update();
+ navigation_capabilities_update();
+ params_update();
- /* rate limit vehicle status updates to 5Hz */
- orb_set_interval(_vstatus_sub, 200);
/* rate limit position updates to 50 Hz */
orb_set_interval(_global_pos_sub, 20);
- parameters_update();
+ hrt_abstime mavlink_open_time = 0;
+ const hrt_abstime mavlink_open_interval = 500000;
/* wakeup source(s) */
- struct pollfd fds[2];
+ struct pollfd fds[6];
/* Setup of loop */
- fds[0].fd = _params_sub;
+ fds[0].fd = _global_pos_sub;
fds[0].events = POLLIN;
- fds[1].fd = _global_pos_sub;
+ fds[1].fd = _home_pos_sub;
fds[1].events = POLLIN;
+ fds[2].fd = _capabilities_sub;
+ fds[2].events = POLLIN;
+ fds[3].fd = _vstatus_sub;
+ fds[3].events = POLLIN;
+ fds[4].fd = _control_mode_sub;
+ fds[4].events = POLLIN;
+ fds[5].fd = _param_update_sub;
+ fds[5].events = POLLIN;
while (!_task_should_exit) {
- /* wait for up to 500ms for data */
+ /* wait for up to 100ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
- /* timed out - periodic check for _task_should_exit, etc. */
- if (pret == 0)
+ if (pret == 0) {
+ /* timed out - periodic check for _task_should_exit, etc. */
continue;
- /* this is undesirable but not much we can do - might want to flag unhappy status */
- if (pret < 0) {
+ } else if (pret < 0) {
+ /* this is undesirable but not much we can do - might want to flag unhappy status */
warn("poll error %d, %d", pret, errno);
continue;
}
perf_begin(_loop_perf);
- /* check vehicle status for changes to publication state */
- vehicle_status_poll();
-
- /* only update parameters if they changed */
- if (fds[0].revents & POLLIN) {
- /* read from param to clear updated flag */
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), _params_sub, &update);
-
- /* update parameters from storage */
- parameters_update();
+ if (_mavlink_fd < 0 && hrt_absolute_time() > mavlink_open_time) {
+ /* try to reopen the mavlink log device with specified interval */
+ mavlink_open_time = hrt_abstime() + mavlink_open_interval;
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
}
- /* only run controller if position changed */
- if (fds[1].revents & POLLIN) {
-
-
- static uint64_t last_run = 0;
- float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
- last_run = hrt_absolute_time();
-
- /* guard against too large deltaT's */
- if (deltaT > 1.0f)
- deltaT = 0.01f;
-
- /* load local copies */
- orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
-
- vehicle_attitude_poll();
-
- mission_poll();
-
- math::Vector2f ground_speed(_global_pos.vx, _global_pos.vy);
- // Current waypoint
- math::Vector2f next_wp(_global_triplet.current.lat / 1e7f, _global_triplet.current.lon / 1e7f);
- // Global position
- math::Vector2f current_position(_global_pos.lat / 1e7f, _global_pos.lon / 1e7f);
-
- /* AUTONOMOUS FLIGHT */
-
- if (1 /* autonomous flight */) {
-
- /* execute navigation once we have a setpoint */
- if (_mission_valid) {
-
- // Next waypoint
- math::Vector2f prev_wp;
-
- if (_global_triplet.previous_valid) {
- prev_wp.setX(_global_triplet.previous.lat / 1e7f);
- prev_wp.setY(_global_triplet.previous.lon / 1e7f);
-
- } else {
- /*
- * No valid next waypoint, go for heading hold.
- * This is automatically handled by the L1 library.
- */
- prev_wp.setX(_global_triplet.current.lat / 1e7f);
- prev_wp.setY(_global_triplet.current.lon / 1e7f);
-
- }
-
-
-
- /******** MAIN NAVIGATION STATE MACHINE ********/
-
- // XXX to be put in its own class
+ /* parameters updated */
+ if (fds[5].revents & POLLIN) {
+ params_update();
+ updateParams();
+ }
- if (_global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
- /* waypoint is a plain navigation waypoint */
-
+ /* vehicle control mode updated */
+ if (fds[4].revents & POLLIN) {
+ vehicle_control_mode_update();
+ }
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
- _global_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
- _global_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+ /* vehicle status updated */
+ if (fds[3].revents & POLLIN) {
+ vehicle_status_update();
+ }
- /* waypoint is a loiter waypoint */
-
- }
+ /* navigation capabilities updated */
+ if (fds[2].revents & POLLIN) {
+ navigation_capabilities_update();
+ }
- // XXX at this point we always want no loiter hold if a
- // mission is active
- _loiter_hold = false;
+ /* home position updated */
+ if (fds[1].revents & POLLIN) {
+ home_position_update();
+ }
- } else {
+ /* global position updated */
+ if (fds[0].revents & POLLIN) {
+ global_position_update();
- if (!_loiter_hold) {
- _loiter_hold_lat = _global_pos.lat / 1e7f;
- _loiter_hold_lon = _global_pos.lon / 1e7f;
- _loiter_hold_alt = _global_pos.alt;
- _loiter_hold = true;
- }
+ /* Check geofence violation */
+ if (!_geofence.inside(&_global_pos)) {
- //_parameters.loiter_hold_radius
+ /* Issue a warning about the geofence violation once */
+ if (!_geofence_violation_warning_sent) {
+ mavlink_log_critical(_mavlink_fd, "#audio: Geofence violation");
+ _geofence_violation_warning_sent = true;
}
-
- } else if (0/* seatbelt mode enabled */) {
-
- /** SEATBELT FLIGHT **/
- continue;
-
} else {
-
- /** MANUAL FLIGHT **/
-
- /* no flight mode applies, do not publish an attitude setpoint */
- continue;
- }
-
- /******** MAIN NAVIGATION STATE MACHINE ********/
-
- if (_global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
- // XXX define launch position and return
-
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_LAND) {
- // XXX flared descent on final approach
-
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
-
- /* apply minimum pitch if altitude has not yet been reached */
- if (_global_pos.alt < _global_triplet.current.altitude) {
- _att_sp.pitch_body = math::max(_att_sp.pitch_body, _global_triplet.current.param1);
- }
+ /* Reset the _geofence_violation_warning_sent field */
+ _geofence_violation_warning_sent = false;
}
+ }
- /* lazily publish the setpoint only once available */
- if (_triplet_pub > 0) {
- /* publish the attitude setpoint */
- orb_publish(ORB_ID(vehicle_global_position_set_triplet), _triplet_pub, &_global_triplet);
+ /* Do stuff according to navigation state set by commander */
+ switch (_vstatus.nav_state) {
+ case NAVIGATION_STATE_MANUAL:
+ case NAVIGATION_STATE_ACRO:
+ case NAVIGATION_STATE_ALTCTL:
+ case NAVIGATION_STATE_POSCTL:
+ _navigation_mode = nullptr;
+ _can_loiter_at_sp = false;
+ break;
+ case NAVIGATION_STATE_AUTO_MISSION:
+ _navigation_mode = &_mission;
+ break;
+ case NAVIGATION_STATE_AUTO_LOITER:
+ _navigation_mode = &_loiter;
+ break;
+ case NAVIGATION_STATE_AUTO_RTL:
+ _navigation_mode = &_rtl;
+ break;
+ case NAVIGATION_STATE_AUTO_RTGS:
+ _navigation_mode = &_rtl; /* TODO: change this to something else */
+ break;
+ case NAVIGATION_STATE_LAND:
+ case NAVIGATION_STATE_TERMINATION:
+ default:
+ _navigation_mode = nullptr;
+ _can_loiter_at_sp = false;
+ break;
+ }
+ /* iterate through navigation modes and set active/inactive for each */
+ for(unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) {
+ if (_navigation_mode == _navigation_mode_array[i]) {
+ _update_triplet = _navigation_mode_array[i]->on_active(&_pos_sp_triplet);
} else {
- /* advertise and publish */
- _triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &_global_triplet);
+ _navigation_mode_array[i]->on_inactive();
}
+ }
+
+ /* if nothing is running, set position setpoint triplet invalid */
+ if (_navigation_mode == nullptr) {
+ _pos_sp_triplet.previous.valid = false;
+ _pos_sp_triplet.current.valid = false;
+ _pos_sp_triplet.next.valid = false;
+ _update_triplet = true;
+ }
+ if (_update_triplet) {
+ publish_position_setpoint_triplet();
+ _update_triplet = false;
}
perf_end(_loop_perf);
}
-
- warnx("exiting.\n");
+ warnx("exiting.");
_navigator_task = -1;
_exit(0);
@@ -543,11 +406,11 @@ Navigator::start()
/* start the task */
_navigator_task = task_spawn_cmd("navigator",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 5,
- 2048,
- (main_t)&Navigator::task_main_trampoline,
- nullptr);
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2000,
+ (main_t)&Navigator::task_main_trampoline,
+ nullptr);
if (_navigator_task < 0) {
warn("task start failed");
@@ -557,20 +420,81 @@ Navigator::start()
return OK;
}
+void
+Navigator::status()
+{
+ /* TODO: add this again */
+ // warnx("Global position is %svalid", _global_pos_valid ? "" : "in");
+
+ // if (_global_pos.global_valid) {
+ // warnx("Longitude %5.5f degrees, latitude %5.5f degrees", _global_pos.lon, _global_pos.lat);
+ // warnx("Altitude %5.5f meters, altitude above home %5.5f meters",
+ // (double)_global_pos.alt, (double)(_global_pos.alt - _home_pos.alt));
+ // warnx("Ground velocity in m/s, N %5.5f, E %5.5f, D %5.5f",
+ // (double)_global_pos.vel_n, (double)_global_pos.vel_e, (double)_global_pos.vel_d);
+ // warnx("Compass heading in degrees %5.5f", (double)(_global_pos.yaw * M_RAD_TO_DEG_F));
+ // }
+
+ if (_fence_valid) {
+ warnx("Geofence is valid");
+ /* TODO: needed? */
+// warnx("Vertex longitude latitude");
+// for (unsigned i = 0; i < _fence.count; i++)
+// warnx("%6u %9.5f %8.5f", i, (double)_fence.vertices[i].lon, (double)_fence.vertices[i].lat);
+
+ } else {
+ warnx("Geofence not set");
+ }
+}
+
+void
+Navigator::publish_position_setpoint_triplet()
+{
+ /* update navigation state */
+ /* TODO: set nav_state */
+
+ /* lazily publish the position setpoint triplet only once available */
+ if (_pos_sp_triplet_pub > 0) {
+ orb_publish(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_pub, &_pos_sp_triplet);
+
+ } else {
+ _pos_sp_triplet_pub = orb_advertise(ORB_ID(position_setpoint_triplet), &_pos_sp_triplet);
+ }
+}
+
+void Navigator::add_fence_point(int argc, char *argv[])
+{
+ _geofence.addPoint(argc, argv);
+}
+
+void Navigator::load_fence_from_file(const char *filename)
+{
+ _geofence.loadFromFile(filename);
+}
+
+
+static void usage()
+{
+ errx(1, "usage: navigator {start|stop|status|fence|fencefile}");
+}
+
int navigator_main(int argc, char *argv[])
{
- if (argc < 1)
- errx(1, "usage: navigator {start|stop|status}");
+ if (argc < 2) {
+ usage();
+ }
if (!strcmp(argv[1], "start")) {
- if (navigator::g_navigator != nullptr)
+ if (navigator::g_navigator != nullptr) {
errx(1, "already running");
+ }
navigator::g_navigator = new Navigator;
- if (navigator::g_navigator == nullptr)
+ if (navigator::g_navigator == nullptr) {
errx(1, "alloc failed");
+ }
if (OK != navigator::g_navigator->start()) {
delete navigator::g_navigator;
@@ -578,27 +502,28 @@ int navigator_main(int argc, char *argv[])
err(1, "start failed");
}
- exit(0);
+ return 0;
}
- if (!strcmp(argv[1], "stop")) {
- if (navigator::g_navigator == nullptr)
- errx(1, "not running");
+ if (navigator::g_navigator == nullptr)
+ errx(1, "not running");
+ if (!strcmp(argv[1], "stop")) {
delete navigator::g_navigator;
navigator::g_navigator = nullptr;
- exit(0);
- }
- if (!strcmp(argv[1], "status")) {
- if (navigator::g_navigator) {
- errx(0, "running");
+ } else if (!strcmp(argv[1], "status")) {
+ navigator::g_navigator->status();
- } else {
- errx(1, "not running");
- }
+ } else if (!strcmp(argv[1], "fence")) {
+ navigator::g_navigator->add_fence_point(argc - 2, argv + 2);
+
+ } else if (!strcmp(argv[1], "fencefile")) {
+ navigator::g_navigator->load_fence_from_file(GEOFENCE_FILENAME);
+
+ } else {
+ usage();
}
- warnx("unrecognized command");
- return 1;
+ return 0;
}
diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp
new file mode 100644
index 000000000..25e767c2b
--- /dev/null
+++ b/src/modules/navigator/navigator_mode.cpp
@@ -0,0 +1,70 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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 navigator_mode.cpp
+ *
+ * Helper class for different modes in navigator
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#include "navigator_mode.h"
+
+NavigatorMode::NavigatorMode(Navigator *navigator, const char *name) :
+ SuperBlock(NULL, name),
+ _navigator(navigator),
+ _first_run(true)
+{
+ /* load initial params */
+ updateParams();
+ /* set initial mission items */
+ on_inactive();
+}
+
+NavigatorMode::~NavigatorMode()
+{
+}
+
+void
+NavigatorMode::on_inactive()
+{
+ _first_run = true;
+}
+
+bool
+NavigatorMode::on_active(struct position_setpoint_triplet_s *pos_sp_triplet)
+{
+ pos_sp_triplet->current.valid = false;
+ _first_run = false;
+ return false;
+}
diff --git a/src/modules/navigator/navigator_mode.h b/src/modules/navigator/navigator_mode.h
new file mode 100644
index 000000000..cbb53d91b
--- /dev/null
+++ b/src/modules/navigator/navigator_mode.h
@@ -0,0 +1,86 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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 navigator_mode.h
+ *
+ * Helper class for different modes in navigator
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#ifndef NAVIGATOR_MODE_H
+#define NAVIGATOR_MODE_H
+
+#include <drivers/drv_hrt.h>
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <dataman/dataman.h>
+
+#include <uORB/topics/position_setpoint_triplet.h>
+
+class Navigator;
+
+class NavigatorMode : public control::SuperBlock
+{
+public:
+ /**
+ * Constructor
+ */
+ NavigatorMode(Navigator *navigator, const char *name);
+
+ /**
+ * Destructor
+ */
+ virtual ~NavigatorMode();
+
+ /**
+ * This function is called while the mode is inactive
+ */
+ virtual void on_inactive();
+
+ /**
+ * This function is called while the mode is active
+ *
+ * @param position setpoint triplet to set
+ * @return true if position setpoint triplet has been changed
+ */
+ virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet);
+
+protected:
+ Navigator *_navigator;
+ bool _first_run;
+};
+
+#endif
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 06df9a452..084afe340 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2014 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
@@ -18,7 +17,7 @@
* 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
+ * 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,
@@ -35,19 +34,33 @@
/**
* @file navigator_params.c
*
- * Parameters defined by the navigator task.
+ * Parameters for navigator in general
*
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
*/
#include <nuttx/config.h>
#include <systemlib/param/param.h>
-/*
- * Navigator parameters, accessible via MAVLink
+/**
+ * Loiter radius (FW only)
+ *
+ * Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only).
*
+ * @unit meters
+ * @min 0.0
+ * @group Mission
*/
+PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
-PARAM_DEFINE_FLOAT(NAV_DUMMY, 0.0f);
-
+/**
+ * Acceptance Radius
+ *
+ * Default acceptance radius, overridden by acceptance radius of waypoint if set.
+ *
+ * @unit meters
+ * @min 1.0
+ * @group Mission
+ */
+PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 25.0f);
diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp
new file mode 100644
index 000000000..597a2c0ec
--- /dev/null
+++ b/src/modules/navigator/rtl.cpp
@@ -0,0 +1,320 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 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 navigator_rtl.cpp
+ * Helper class to access RTL
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/home_position.h>
+
+#include "navigator.h"
+#include "rtl.h"
+
+#define DELAY_SIGMA 0.01f
+
+RTL::RTL(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name),
+ _rtl_state(RTL_STATE_NONE),
+ _param_return_alt(this, "RETURN_ALT"),
+ _param_descend_alt(this, "DESCEND_ALT"),
+ _param_land_delay(this, "LAND_DELAY")
+{
+ /* load initial params */
+ updateParams();
+ /* initial reset */
+ on_inactive();
+}
+
+RTL::~RTL()
+{
+}
+
+void
+RTL::on_inactive()
+{
+ _first_run = true;
+
+ /* reset RTL state only if setpoint moved */
+ if (!_navigator->get_can_loiter_at_sp()) {
+ _rtl_state = RTL_STATE_NONE;
+ }
+}
+
+bool
+RTL::on_active(struct position_setpoint_triplet_s *pos_sp_triplet)
+{
+ bool updated = false;
+
+ if (_first_run) {
+ _first_run = false;
+
+ /* decide where to enter the RTL procedure when we switch into it */
+ if (_rtl_state == RTL_STATE_NONE) {
+ /* for safety reasons don't go into RTL if landed */
+ if (_navigator->get_vstatus()->condition_landed) {
+ _rtl_state = RTL_STATE_LANDED;
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no RTL when landed");
+
+ /* if lower than return altitude, climb up first */
+ } else if (_navigator->get_global_position()->alt < _navigator->get_home_position()->alt
+ + _param_return_alt.get()) {
+ _rtl_state = RTL_STATE_CLIMB;
+
+ /* otherwise go straight to return */
+ } else {
+ /* set altitude setpoint to current altitude */
+ _rtl_state = RTL_STATE_RETURN;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_global_position()->alt;
+ }
+ }
+
+ set_rtl_item(pos_sp_triplet);
+ updated = true;
+
+ } else if (_rtl_state != RTL_STATE_LANDED && is_mission_item_reached()) {
+ advance_rtl();
+ set_rtl_item(pos_sp_triplet);
+ updated = true;
+ }
+
+ return updated;
+}
+
+void
+RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet)
+{
+ /* make sure we have the latest params */
+ updateParams();
+
+ set_previous_pos_setpoint(pos_sp_triplet);
+ _navigator->set_can_loiter_at_sp(false);
+
+ switch (_rtl_state) {
+ case RTL_STATE_CLIMB: {
+ float climb_alt = _navigator->get_home_position()->alt + _param_return_alt.get();
+
+ _mission_item.lat = _navigator->get_global_position()->lat;
+ _mission_item.lon = _navigator->get_global_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = climb_alt;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_WAYPOINT;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: climb to %d meters above home",
+ (int)(climb_alt - _navigator->get_home_position()->alt));
+ break;
+ }
+
+ case RTL_STATE_RETURN: {
+ _mission_item.lat = _navigator->get_home_position()->lat;
+ _mission_item.lon = _navigator->get_home_position()->lon;
+ // don't change altitude
+
+ if (pos_sp_triplet->previous.valid) {
+ /* if previous setpoint is valid then use it to calculate heading to home */
+ _mission_item.yaw = get_bearing_to_next_waypoint(
+ pos_sp_triplet->previous.lat, pos_sp_triplet->previous.lon,
+ _mission_item.lat, _mission_item.lon);
+
+ } else {
+ /* else use current position */
+ _mission_item.yaw = get_bearing_to_next_waypoint(
+ _navigator->get_global_position()->lat, _navigator->get_global_position()->lon,
+ _mission_item.lat, _mission_item.lon);
+ }
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_WAYPOINT;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: return at %d meters above home",
+ (int)(_mission_item.altitude - _navigator->get_home_position()->alt));
+ break;
+ }
+
+ case RTL_STATE_DESCEND: {
+ _mission_item.lat = _navigator->get_home_position()->lat;
+ _mission_item.lon = _navigator->get_home_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_home_position()->alt + _param_descend_alt.get();
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = false;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: descend to %d meters above home",
+ (int)(_mission_item.altitude - _navigator->get_home_position()->alt));
+ break;
+ }
+
+ case RTL_STATE_LOITER: {
+ bool autoland = _param_land_delay.get() > -DELAY_SIGMA;
+
+ _mission_item.lat = _navigator->get_home_position()->lat;
+ _mission_item.lon = _navigator->get_home_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_home_position()->alt + _param_descend_alt.get();
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = autoland ? NAV_CMD_LOITER_TIME_LIMIT : NAV_CMD_LOITER_UNLIMITED;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = _param_land_delay.get() < 0.0f ? 0.0f : _param_land_delay.get();
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = autoland;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ _navigator->set_can_loiter_at_sp(true);
+
+ if (autoland) {
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: loiter %.1fs", (double)_mission_item.time_inside);
+
+ } else {
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: completed, loiter");
+ }
+ break;
+ }
+
+ case RTL_STATE_LAND: {
+ _mission_item.lat = _navigator->get_home_position()->lat;
+ _mission_item.lon = _navigator->get_home_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_home_position()->alt;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_LAND;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: land at home");
+ break;
+ }
+
+ case RTL_STATE_LANDED: {
+ _mission_item.lat = _navigator->get_home_position()->lat;
+ _mission_item.lon = _navigator->get_home_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_home_position()->alt;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_IDLE;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: completed, landed");
+ break;
+ }
+
+ default:
+ break;
+ }
+
+ /* convert mission item to current position setpoint and make it valid */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ reset_mission_item_reached();
+ pos_sp_triplet->current.valid = true;
+ pos_sp_triplet->next.valid = false;
+}
+
+void
+RTL::advance_rtl()
+{
+ switch (_rtl_state) {
+ case RTL_STATE_CLIMB:
+ _rtl_state = RTL_STATE_RETURN;
+ break;
+
+ case RTL_STATE_RETURN:
+ _rtl_state = RTL_STATE_DESCEND;
+ break;
+
+ case RTL_STATE_DESCEND:
+ /* only go to land if autoland is enabled */
+ if (_param_land_delay.get() < -DELAY_SIGMA || _param_land_delay.get() > DELAY_SIGMA) {
+ _rtl_state = RTL_STATE_LOITER;
+
+ } else {
+ _rtl_state = RTL_STATE_LAND;
+ }
+ break;
+
+ case RTL_STATE_LOITER:
+ _rtl_state = RTL_STATE_LAND;
+ break;
+
+ case RTL_STATE_LAND:
+ _rtl_state = RTL_STATE_LANDED;
+ break;
+
+ default:
+ break;
+ }
+}
diff --git a/src/modules/navigator/rtl.h b/src/modules/navigator/rtl.h
new file mode 100644
index 000000000..b4b729e89
--- /dev/null
+++ b/src/modules/navigator/rtl.h
@@ -0,0 +1,110 @@
+/***************************************************************************
+ *
+ * Copyright (c) 2013-2014 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 navigator_rtl.h
+ * Helper class for RTL
+ *
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#ifndef NAVIGATOR_RTL_H
+#define NAVIGATOR_RTL_H
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <uORB/topics/mission.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/home_position.h>
+#include <uORB/topics/vehicle_global_position.h>
+
+#include "navigator_mode.h"
+#include "mission_block.h"
+
+class Navigator;
+
+class RTL : public MissionBlock
+{
+public:
+ /**
+ * Constructor
+ */
+ RTL(Navigator *navigator, const char *name);
+
+ /**
+ * Destructor
+ */
+ ~RTL();
+
+ /**
+ * This function is called while the mode is inactive
+ */
+ void on_inactive();
+
+ /**
+ * This function is called while the mode is active
+ *
+ * @param position setpoint triplet that needs to be set
+ * @return true if updated
+ */
+ bool on_active(position_setpoint_triplet_s *pos_sp_triplet);
+
+
+private:
+ /**
+ * Set the RTL item
+ */
+ void set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet);
+
+ /**
+ * Move to next RTL item
+ */
+ void advance_rtl();
+
+ enum RTLState {
+ RTL_STATE_NONE = 0,
+ RTL_STATE_CLIMB,
+ RTL_STATE_RETURN,
+ RTL_STATE_DESCEND,
+ RTL_STATE_LOITER,
+ RTL_STATE_LAND,
+ RTL_STATE_LANDED,
+ } _rtl_state;
+
+ control::BlockParamFloat _param_return_alt;
+ control::BlockParamFloat _param_descend_alt;
+ control::BlockParamFloat _param_land_delay;
+};
+
+#endif
diff --git a/src/modules/navigator/rtl_params.c b/src/modules/navigator/rtl_params.c
new file mode 100644
index 000000000..bfe6ce7e1
--- /dev/null
+++ b/src/modules/navigator/rtl_params.c
@@ -0,0 +1,98 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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 rtl_params.c
+ *
+ * Parameters for RTL
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * RTL parameters, accessible via MAVLink
+ */
+
+/**
+ * Loiter radius after RTL (FW only)
+ *
+ * Default value of loiter radius after RTL (fixedwing only).
+ *
+ * @unit meters
+ * @min 0.0
+ * @group RTL
+ */
+PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 50.0f);
+
+/**
+ * RTL altitude
+ *
+ * Altitude to fly back in RTL in meters
+ *
+ * @unit meters
+ * @min 0
+ * @max 1
+ * @group RTL
+ */
+PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 100);
+
+
+/**
+ * RTL loiter altitude
+ *
+ * Stay at this altitude above home position after RTL descending.
+ * Land (i.e. slowly descend) from this altitude if autolanding allowed.
+ *
+ * @unit meters
+ * @min 0
+ * @max 100
+ * @group RTL
+ */
+PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 20);
+
+/**
+ * RTL delay
+ *
+ * Delay after descend before landing in RTL mode.
+ * If set to -1 the system will not land but loiter at NAV_LAND_ALT.
+ *
+ * @unit seconds
+ * @min -1
+ * @max
+ * @group RTL
+ */
+PARAM_DEFINE_FLOAT(RTL_LAND_DELAY, -1.0f);