aboutsummaryrefslogtreecommitdiff
path: root/src/modules/navigator
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/navigator')
-rw-r--r--src/modules/navigator/geofence.cpp299
-rw-r--r--src/modules/navigator/geofence.h93
-rw-r--r--src/modules/navigator/geofence_params.c55
-rw-r--r--src/modules/navigator/mission_feasibility_checker.cpp202
-rw-r--r--src/modules/navigator/mission_feasibility_checker.h83
-rw-r--r--src/modules/navigator/module.mk8
-rw-r--r--src/modules/navigator/navigator_main.cpp1476
-rw-r--r--src/modules/navigator/navigator_mission.cpp257
-rw-r--r--src/modules/navigator/navigator_mission.h97
-rw-r--r--src/modules/navigator/navigator_params.c13
10 files changed, 2332 insertions, 251 deletions
diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp
new file mode 100644
index 000000000..9bbaf167a
--- /dev/null
+++ b/src/modules/navigator/geofence.cpp
@@ -0,0 +1,299 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ *
+ * 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
+ */
+#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() : _fence_pub(-1),
+ _altitude_min(0),
+ _altitude_max(0),
+ _verticesCount(0),
+ param_geofence_on(NULL, "GF_ON", false)
+{
+ /* 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 (((temp_vertex_i.lon) >= lon != (temp_vertex_j.lon >= lon)) &&
+ (lat <= (temp_vertex_j.lat - temp_vertex_i.lat) * (lon - temp_vertex_i.lon) /
+ (temp_vertex_j.lon - temp_vertex_i.lon) + 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);
+}
+
+void Geofence::updateParams()
+{
+ param_geofence_on.update();
+}
diff --git a/src/modules/navigator/geofence.h b/src/modules/navigator/geofence.h
new file mode 100644
index 000000000..5b56ebc7a
--- /dev/null
+++ b/src/modules/navigator/geofence.h
@@ -0,0 +1,93 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ *
+ * 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
+ */
+
+#ifndef GEOFENCE_H_
+#define GEOFENCE_H_
+
+#include <uORB/topics/fence.h>
+#include <controllib/block/BlockParam.hpp>
+
+#define GEOFENCE_FILENAME "/fs/microsd/etc/geofence.txt"
+
+class Geofence {
+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;}
+
+ void updateParams();
+};
+
+
+#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..20dd1fe2f
--- /dev/null
+++ b/src/modules/navigator/geofence_params.c
@@ -0,0 +1,55 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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
+ *
+ */
+
+// @DisplayName Switch to enable geofence
+// @Description if set to 1 geofence is enabled, defaults to 1 because geofence is only enabled when the geofence.txt file is present
+// @Range 0 or 1
+PARAM_DEFINE_INT32(GF_ON, 1);
diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp
new file mode 100644
index 000000000..eaafa217d
--- /dev/null
+++ b/src/modules/navigator/mission_feasibility_checker.cpp
@@ -0,0 +1,202 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ * 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
+ */
+
+#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)
+{
+ /* 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);
+ else
+ return checkMissionFeasibleFixedwing(dm_current, nMissionItems, geofence);
+}
+
+bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+{
+
+ return checkGeofence(dm_current, nMissionItems, geofence);
+}
+
+bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+{
+ /* 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));
+}
+
+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++) {
+ 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. */
+ return false;
+ }
+
+ if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) { //xxx: handle relative altitude
+ mavlink_log_info(_mavlink_fd, "#audio: Geofence violation waypoint %d", i);
+ return false;
+ }
+ }
+ }
+
+ 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++) {
+ 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. */
+ 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;
+}
+
+void MissionFeasibilityChecker::updateNavigationCapabilities()
+{
+ int res = 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..7a0b2a296
--- /dev/null
+++ b/src/modules/navigator/mission_feasibility_checker.h
@@ -0,0 +1,83 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
+ * 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
+ */
+#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);
+
+ /* Checks specific to fixedwing airframes */
+ bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ 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);
+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);
+
+};
+
+
+#endif /* MISSION_FEASIBILITY_CHECKER_H_ */
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index 0404b06c7..55f8a4caa 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -38,4 +38,10 @@
MODULE_COMMAND = navigator
SRCS = navigator_main.cpp \
- navigator_params.c
+ navigator_params.c \
+ navigator_mission.cpp \
+ mission_feasibility_checker.cpp \
+ geofence.cpp \
+ geofence_params.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index f6c44444a..bb7520a03 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -1,7 +1,9 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,6 +38,7 @@
* Implementation of the main navigation state machine.
*
* Handles missions, geo fencing and failsafe navigation behavior.
+ * Published the mission item triplet for the position controller.
*/
#include <nuttx/config.h>
@@ -48,26 +51,43 @@
#include <math.h>
#include <poll.h>
#include <time.h>
+#include <sys/ioctl.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/mission_item_triplet.h>
+#include <uORB/topics/mission_result.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/mission.h>
+#include <uORB/topics/fence.h>
+#include <uORB/topics/navigation_capabilities.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
-#include <geo/geo.h>
+#include <systemlib/state_table.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
+#include <geo/geo.h>
#include <mathlib/mathlib.h>
+#include <dataman/dataman.h>
+#include <mavlink/mavlink_log.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+
+#include "navigator_mission.h"
+#include "mission_feasibility_checker.h"
+#include "geofence.h"
+
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
/**
* navigator app start / stop handling function
@@ -76,7 +96,7 @@
*/
extern "C" __EXPORT int navigator_main(int argc, char *argv[]);
-class Navigator
+class Navigator : public StateTable
{
public:
/**
@@ -85,103 +105,162 @@ public:
Navigator();
/**
- * Destructor, also kills the sensors task.
+ * Destructor, also kills the navigators task.
*/
~Navigator();
/**
- * Start the sensors task.
+ * 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);
+
private:
bool _task_should_exit; /**< if true, sensor task should exit */
- int _navigator_task; /**< task handle for sensor task */
+ 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 _mavlink_fd;
+
+ int _global_pos_sub; /**< global position subscription */
+ int _home_pos_sub; /**< home position 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;
+ int _params_sub; /**< notification of parameter updates */
+ int _offboard_mission_sub; /**< notification of offboard mission updates */
+ int _onboard_mission_sub; /**< notification of onboard mission updates */
+ int _capabilities_sub; /**< notification of vehicle capabilities updates */
- orb_advert_t _triplet_pub; /**< position setpoint */
+ orb_advert_t _triplet_pub; /**< publish position setpoint triplet */
+ orb_advert_t _mission_result_pub; /**< publish mission result topic */
+ orb_advert_t _control_mode_pub; /**< publish vehicle control mode topic */
- 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_control_mode_s _control_mode; /**< vehicle control mode */
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
- struct vehicle_global_position_set_triplet_s _global_triplet; /**< triplet of global setpoints */
+ struct home_position_s _home_pos; /**< home position for RTL */
+ struct mission_item_triplet_s _mission_item_triplet; /**< triplet of mission items */
+ struct mission_result_s _mission_result; /**< mission result for commander/mavlink */
perf_counter_t _loop_perf; /**< loop performance counter */
+
+ Geofence _geofence;
+ bool _geofence_violation_warning_sent;
+
+ bool _fence_valid; /**< flag if fence is valid */
+ bool _inside_fence; /**< vehicle is inside fence */
- 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 */
+ struct navigation_capabilities_s _nav_caps;
- /** 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;
+ class Mission _mission;
+
+ bool _reset_loiter_pos; /**< if true then loiter position should be set to current position */
+ bool _waypoint_position_reached;
+ bool _waypoint_yaw_reached;
+ uint64_t _time_first_inside_orbit;
+ bool _need_takeoff; /**< if need to perform vertical takeoff before going to waypoint (only for MISSION mode and VTOL vehicles) */
+ bool _do_takeoff; /**< vertical takeoff state, current mission item is generated by navigator (only for MISSION mode and VTOL vehicles) */
+
+ MissionFeasibilityChecker missionFeasiblityChecker;
+
+ uint64_t _set_nav_state_timestamp; /**< timestamp of last handled navigation state request */
struct {
- float throttle_cruise;
- } _parameters; /**< local copies of interesting parameters */
+ float min_altitude;
+ float acceptance_radius;
+ float loiter_radius;
+ int onboard_mission_enabled;
+ float takeoff_alt;
+ float land_alt;
+ float rtl_alt;
+ } _parameters; /**< local copies of parameters */
struct {
- param_t throttle_cruise;
+ param_t min_altitude;
+ param_t acceptance_radius;
+ param_t loiter_radius;
+ param_t onboard_mission_enabled;
+ param_t takeoff_alt;
+ param_t land_alt;
+ param_t rtl_alt;
+ } _parameter_handles; /**< handles for parameters */
+
+ enum Event {
+ EVENT_NONE_REQUESTED,
+ EVENT_READY_REQUESTED,
+ EVENT_LOITER_REQUESTED,
+ EVENT_MISSION_REQUESTED,
+ EVENT_RTL_REQUESTED,
+ EVENT_MISSION_CHANGED,
+ EVENT_HOME_POSITION_CHANGED,
+ MAX_EVENT
+ };
+
+ /**
+ * State machine transition table
+ */
+ static StateTable::Tran const myTable[NAV_STATE_MAX][MAX_EVENT];
- } _parameter_handles; /**< handles for interesting parameters */
+ enum RTLState {
+ RTL_STATE_NONE = 0,
+ RTL_STATE_CLIMB,
+ RTL_STATE_RETURN,
+ RTL_STATE_DESCEND,
+ RTL_STATE_LAND
+ };
+ enum RTLState _rtl_state;
/**
* Update our local parameter cache.
*/
- int parameters_update();
+ void parameters_update();
/**
- * Update control outputs
- *
+ * Retrieve global position
*/
- void control_update();
+ void global_position_update();
/**
- * Check for changes in vehicle status.
+ * Retrieve home position
*/
- void vehicle_status_poll();
+ void home_position_update();
/**
- * Check for position updates.
+ * Retreive navigation capabilities
*/
- void vehicle_attitude_poll();
+ void navigation_capabilities_update();
/**
- * Check for set triplet updates.
+ * Retrieve offboard mission.
*/
- void mission_poll();
+ void offboard_mission_update(bool isrotaryWing);
/**
- * Control throttle.
+ * Retrieve onboard mission.
*/
- float control_throttle(float energy_error);
+ void onboard_mission_update();
/**
- * Control pitch.
+ * Retrieve vehicle status
*/
- float control_pitch(float altitude_error);
+ void vehicle_status_update();
- void calculate_airspeed_errors();
- void calculate_gndspeed_undershoot();
- void calculate_altitude_error();
/**
* Shim for calling task_main from task_create.
@@ -192,6 +271,79 @@ private:
* Main sensor collection task.
*/
void task_main() __attribute__((noreturn));
+
+ void publish_safepoints(unsigned points);
+
+ /**
+ * Functions that are triggered when a new state is entered.
+ */
+ void start_none();
+ void start_ready();
+ void start_loiter();
+ void start_mission();
+ void start_rtl();
+ void finish_rtl();
+
+ /**
+ * Guards offboard mission
+ */
+ bool offboard_mission_available(unsigned relative_index);
+
+ /**
+ * Guards onboard mission
+ */
+ bool onboard_mission_available(unsigned relative_index);
+
+ /**
+ * Check if current mission item has been reached.
+ */
+ bool check_mission_item_reached();
+
+ /**
+ * Perform actions when current mission item reached.
+ */
+ void on_mission_item_reached();
+
+ /**
+ * Move to next waypoint
+ */
+ void advance_mission();
+
+ /**
+ * Switch to next RTL state
+ */
+ void set_rtl_item();
+
+ /**
+ * Helper function to get a loiter item
+ */
+ void get_loiter_item(mission_item_s *item);
+
+ /**
+ * Helper function to get a takeoff item
+ */
+ void get_takeoff_item(mission_item_s *item);
+
+ /**
+ * Publish a new mission item triplet for position controller
+ */
+ void publish_mission_item_triplet();
+
+ /**
+ * Publish vehicle_control_mode topic for controllers
+ */
+ void publish_control_mode();
+
+
+ /**
+ * Compare two mission items if they are equivalent
+ * Two mission items can be considered equivalent for the purpose of the navigator even if some fields differ.
+ *
+ * @return true if equivalent, false otherwise
+ */
+ bool cmp_mission_item_equivalent(const struct mission_item_s a, const struct mission_item_s b);
+
+ void add_home_pos_to_rtl(struct mission_item_s *new_mission_item);
};
namespace navigator
@@ -206,39 +358,66 @@ static const int ERROR = -1;
Navigator *g_navigator;
}
-Navigator::Navigator() :
+Navigator::Navigator() :
+
+/* state machine transition table */
+ StateTable(&myTable[0][0], NAV_STATE_MAX, MAX_EVENT),
_task_should_exit(false),
_navigator_task(-1),
+ _mavlink_fd(-1),
/* subscriptions */
_global_pos_sub(-1),
- _att_sub(-1),
- _airspeed_sub(-1),
+ _home_pos_sub(-1),
_vstatus_sub(-1),
_params_sub(-1),
- _manual_control_sub(-1),
+ _offboard_mission_sub(-1),
+ _onboard_mission_sub(-1),
+ _capabilities_sub(-1),
/* publications */
_triplet_pub(-1),
+ _mission_result_pub(-1),
+ _control_mode_pub(-1),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
+
/* states */
- _mission_items_maxcount(20),
- _mission_valid(false),
- _loiter_hold(false)
+ _rtl_state(RTL_STATE_NONE),
+ _fence_valid(false),
+ _inside_fence(true),
+ _mission(),
+ _reset_loiter_pos(true),
+ _waypoint_position_reached(false),
+ _waypoint_yaw_reached(false),
+ _time_first_inside_orbit(0),
+ _set_nav_state_timestamp(0),
+ _need_takeoff(true),
+ _do_takeoff(false),
+ _geofence_violation_warning_sent(false)
{
- _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");
-
- /* fetch initial parameter values */
- parameters_update();
+ _parameter_handles.min_altitude = param_find("NAV_MIN_ALT");
+ _parameter_handles.acceptance_radius = param_find("NAV_ACCEPT_RAD");
+ _parameter_handles.loiter_radius = param_find("NAV_LOITER_RAD");
+ _parameter_handles.onboard_mission_enabled = param_find("NAV_ONB_MIS_EN");
+ _parameter_handles.takeoff_alt = param_find("NAV_TAKEOFF_ALT");
+ _parameter_handles.land_alt = param_find("NAV_LAND_ALT");
+ _parameter_handles.rtl_alt = param_find("NAV_RTL_ALT");
+
+ _mission_item_triplet.previous_valid = false;
+ _mission_item_triplet.current_valid = false;
+ _mission_item_triplet.next_valid = false;
+ memset(&_mission_item_triplet.previous, 0, sizeof(struct mission_item_s));
+ memset(&_mission_item_triplet.current, 0, sizeof(struct mission_item_s));
+ memset(&_mission_item_triplet.next, 0, sizeof(struct mission_item_s));
+
+ memset(&_mission_result, 0, sizeof(struct mission_result_s));
+
+ /* Initialize state machine */
+ myState = NAV_STATE_NONE;
+ start_none();
}
Navigator::~Navigator()
@@ -266,69 +445,93 @@ Navigator::~Navigator()
navigator::g_navigator = nullptr;
}
-int
+void
Navigator::parameters_update()
{
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), _params_sub, &update);
- //param_get(_parameter_handles.throttle_cruise, &(_parameters.throttle_cruise));
+ param_get(_parameter_handles.min_altitude, &(_parameters.min_altitude));
+ param_get(_parameter_handles.acceptance_radius, &(_parameters.acceptance_radius));
+ param_get(_parameter_handles.loiter_radius, &(_parameters.loiter_radius));
+ param_get(_parameter_handles.onboard_mission_enabled, &(_parameters.onboard_mission_enabled));
+ param_get(_parameter_handles.takeoff_alt, &(_parameters.takeoff_alt));
+ param_get(_parameter_handles.land_alt, &(_parameters.land_alt));
+ param_get(_parameter_handles.rtl_alt, &(_parameters.rtl_alt));
- return OK;
+ _mission.set_onboard_mission_allowed((bool)_parameter_handles.onboard_mission_enabled);
+
+ _geofence.updateParams();
}
void
-Navigator::vehicle_status_poll()
+Navigator::global_position_update()
{
- bool vstatus_updated;
-
- /* Check HIL state if vehicle status has changed */
- orb_check(_vstatus_sub, &vstatus_updated);
-
- if (vstatus_updated) {
-
- orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
- }
+ /* load local copies */
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
}
void
-Navigator::vehicle_attitude_poll()
+Navigator::home_position_update()
{
- /* check if there is a new position */
- bool att_updated;
- orb_check(_att_sub, &att_updated);
+ orb_copy(ORB_ID(home_position), _home_pos_sub, &_home_pos);
+}
- if (att_updated) {
- orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
- }
+void
+Navigator::navigation_capabilities_update()
+{
+ orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
}
+
void
-Navigator::mission_poll()
+Navigator::offboard_mission_update(bool isrotaryWing)
{
- /* check if there is a new setpoint */
- bool mission_updated;
- orb_check(_mission_sub, &mission_updated);
+ struct mission_s offboard_mission;
+ if (orb_copy(ORB_ID(mission), _offboard_mission_sub, &offboard_mission) == OK) {
+
+ /* 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(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence);
- if (mission_updated) {
+ _mission.set_offboard_dataman_id(offboard_mission.dataman_id);
+ _mission.set_current_offboard_mission_index(offboard_mission.current_index);
+ _mission.set_offboard_mission_count(offboard_mission.count);
- struct mission_s mission;
- orb_copy(ORB_ID(mission), _mission_sub, &mission);
+ } else {
+ _mission.set_current_offboard_mission_index(0);
+ _mission.set_offboard_mission_count(0);
+ }
+}
- // XXX this is not optimal yet, but a first prototype /
- // test implementation
+void
+Navigator::onboard_mission_update()
+{
+ struct mission_s onboard_mission;
+ if (orb_copy(ORB_ID(mission), _onboard_mission_sub, &onboard_mission) == OK) {
- if (mission.count <= _mission_items_maxcount) {
- /*
- * Perform an atomic copy & state update
- */
- irqstate_t flags = irqsave();
+ _mission.set_current_onboard_mission_index(onboard_mission.current_index);
+ _mission.set_onboard_mission_count(onboard_mission.count);
- memcpy(_mission_items, mission.items, mission.count * sizeof(struct mission_item_s));
- _mission_valid = true;
+ } else {
+ _mission.set_current_onboard_mission_index(0);
+ _mission.set_onboard_mission_count(0);
+ }
+}
- irqrestore(flags);
- } else {
- warnx("mission larger than storage space");
- }
+void
+Navigator::vehicle_status_update()
+{
+ /* try to load initial states */
+ if (orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus) != OK) {
+ _vstatus.arming_state = ARMING_STATE_STANDBY; /* in case the commander is not be running */
}
}
@@ -341,46 +544,85 @@ Navigator::task_main_trampoline(int argc, char *argv[])
void
Navigator::task_main()
{
-
/* inform about start */
warnx("Initializing..");
fflush(stdout);
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+
+ mavlink_log_info(_mavlink_fd, "[navigator] started");
+
+ /* 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));
+ _offboard_mission_sub = orb_subscribe(ORB_ID(mission));
+ _onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission));
+ _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));
+ _home_pos_sub = orb_subscribe(ORB_ID(home_position));
+
+ /* copy all topics first time */
+ vehicle_status_update();
+ parameters_update();
+ global_position_update();
+ home_position_update();
+ navigation_capabilities_update();
+ offboard_mission_update(_vstatus.is_rotary_wing);
+ onboard_mission_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();
+ unsigned prevState = NAV_STATE_NONE;
+ bool pub_control_mode = true;
+ hrt_abstime mavlink_open_time = 0;
+ const hrt_abstime mavlink_open_interval = 500000;
/* wakeup source(s) */
- struct pollfd fds[2];
+ struct pollfd fds[7];
/* Setup of loop */
fds[0].fd = _params_sub;
fds[0].events = POLLIN;
fds[1].fd = _global_pos_sub;
fds[1].events = POLLIN;
+ fds[2].fd = _home_pos_sub;
+ fds[2].events = POLLIN;
+ fds[3].fd = _capabilities_sub;
+ fds[3].events = POLLIN;
+ fds[4].fd = _offboard_mission_sub;
+ fds[4].events = POLLIN;
+ fds[5].fd = _onboard_mission_sub;
+ fds[5].events = POLLIN;
+ fds[6].fd = _vstatus_sub;
+ fds[6].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) {
continue;
+ }
/* this is undesirable but not much we can do - might want to flag unhappy status */
if (pret < 0) {
@@ -390,187 +632,927 @@ Navigator::task_main()
perf_begin(_loop_perf);
- /* check vehicle status for changes to publication state */
- vehicle_status_poll();
+ 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 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);
+ /* vehicle status updated */
+ if (fds[6].revents & POLLIN) {
+ vehicle_status_update();
+ pub_control_mode = true;
+
+ /* Evaluate state machine from commander and set the navigator mode accordingly */
+ if (_vstatus.main_state == MAIN_STATE_AUTO &&
+ (_vstatus.arming_state == ARMING_STATE_ARMED || _vstatus.arming_state == ARMING_STATE_ARMED_ERROR)) {
+ bool stick_mode = false;
+ if (!_vstatus.rc_signal_lost) {
+ /* RC signal available, use control switches to set mode */
+ /* RETURN switch, overrides MISSION switch */
+ if (_vstatus.return_switch == RETURN_SWITCH_RETURN) {
+ if (myState != NAV_STATE_READY || _rtl_state != RTL_STATE_LAND) {
+ dispatch(EVENT_RTL_REQUESTED);
+ }
+ stick_mode = true;
+ } else {
+ /* MISSION switch */
+ if (_vstatus.mission_switch == MISSION_SWITCH_LOITER) {
+ dispatch(EVENT_LOITER_REQUESTED);
+ stick_mode = true;
+ } else if (_vstatus.mission_switch == MISSION_SWITCH_MISSION) {
+ /* switch to mission only if available */
+ if (_mission.current_mission_available()) {
+ dispatch(EVENT_MISSION_REQUESTED);
+ } else {
+ dispatch(EVENT_LOITER_REQUESTED);
+ }
+ stick_mode = true;
+ }
+ if (!stick_mode && _vstatus.return_switch == RETURN_SWITCH_NORMAL && myState == NAV_STATE_RTL) {
+ /* RETURN switch is in normal mode, no MISSION switch mapped, interrupt if in RTL state */
+ dispatch(EVENT_LOITER_REQUESTED);
+ stick_mode = true;
+ }
+ }
+ }
+
+ if (!stick_mode) {
+ if (_vstatus.set_nav_state_timestamp != _set_nav_state_timestamp) {
+ /* commander requested new navigation mode, try to set it */
+ _set_nav_state_timestamp = _vstatus.set_nav_state_timestamp;
+
+ switch (_vstatus.set_nav_state) {
+ case NAV_STATE_NONE:
+ /* nothing to do */
+ break;
+
+ case NAV_STATE_LOITER:
+ dispatch(EVENT_LOITER_REQUESTED);
+ break;
+
+ case NAV_STATE_MISSION:
+ if (_mission.current_mission_available()) {
+ dispatch(EVENT_MISSION_REQUESTED);
+ } else {
+ dispatch(EVENT_LOITER_REQUESTED);
+ }
+ break;
+
+ case NAV_STATE_RTL:
+ if (myState != NAV_STATE_READY || _rtl_state != RTL_STATE_LAND) {
+ dispatch(EVENT_RTL_REQUESTED);
+ }
+ break;
+
+ default:
+ warnx("ERROR: Requested navigation state not supported");
+ break;
+ }
+
+ } else {
+ /* on first switch to AUTO try mission by default, if none is available fallback to loiter */
+ if (myState == NAV_STATE_NONE) {
+ if (_mission.current_mission_available()) {
+ dispatch(EVENT_MISSION_REQUESTED);
+ } else {
+ dispatch(EVENT_LOITER_REQUESTED);
+ }
+ }
+ }
+ }
+
+ } else {
+ /* not in AUTO */
+ dispatch(EVENT_NONE_REQUESTED);
+ }
+ }
- /* update parameters from storage */
+ /* parameters updated */
+ if (fds[0].revents & POLLIN) {
parameters_update();
+ /* note that these new parameters won't be in effect until a mission triplet is published again */
+ }
+
+ /* navigation capabilities updated */
+ if (fds[3].revents & POLLIN) {
+ navigation_capabilities_update();
+ }
+
+ /* offboard mission updated */
+ if (fds[4].revents & POLLIN) {
+ offboard_mission_update(_vstatus.is_rotary_wing);
+ // XXX check if mission really changed
+ dispatch(EVENT_MISSION_CHANGED);
+ }
+
+ /* onboard mission updated */
+ if (fds[5].revents & POLLIN) {
+ onboard_mission_update();
+ // XXX check if mission really changed
+ dispatch(EVENT_MISSION_CHANGED);
+ }
+
+ /* home position updated */
+ if (fds[2].revents & POLLIN) {
+ home_position_update();
+ // XXX check if home position really changed
+ dispatch(EVENT_HOME_POSITION_CHANGED);
}
- /* only run controller if position changed */
+ /* global position updated */
if (fds[1].revents & POLLIN) {
+ global_position_update();
+ /* only check if waypoint has been reached in MISSION and RTL modes */
+ if (myState == NAV_STATE_MISSION || myState == NAV_STATE_RTL) {
+ if (check_mission_item_reached()) {
+ on_mission_item_reached();
+ }
+ }
+ /* Check geofence violation */
+ if(!_geofence.inside(&_global_pos)) {
+ //xxx: publish geofence violation here (or change local flag depending on which app handles the flight termination)
- static uint64_t last_run = 0;
- float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
- last_run = hrt_absolute_time();
+ /* 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 {
+ /* Reset the _geofence_violation_warning_sent field */
+ _geofence_violation_warning_sent = false;
+ }
+ }
- /* guard against too large deltaT's */
- if (deltaT > 1.0f)
- deltaT = 0.01f;
+ /* notify user about state changes */
+ if (myState != prevState) {
+ mavlink_log_info(_mavlink_fd, "[navigator] nav state %d -> %d", prevState, myState);
+ prevState = myState;
+ pub_control_mode = true;
+ }
- /* load local copies */
- orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+ /* publish control mode if updated */
+ if (pub_control_mode) {
+ publish_control_mode();
+ }
- vehicle_attitude_poll();
+ perf_end(_loop_perf);
+ }
- mission_poll();
+ warnx("exiting.");
- 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);
+ _navigator_task = -1;
+ _exit(0);
+}
- /* AUTONOMOUS FLIGHT */
+int
+Navigator::start()
+{
+ ASSERT(_navigator_task == -1);
- if (1 /* autonomous flight */) {
+ /* start the task */
+ _navigator_task = task_spawn_cmd("navigator",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&Navigator::task_main_trampoline,
+ nullptr);
- /* execute navigation once we have a setpoint */
- if (_mission_valid) {
+ if (_navigator_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
- // Next waypoint
- math::Vector2f prev_wp;
+ return OK;
+}
- if (_global_triplet.previous_valid) {
- prev_wp.setX(_global_triplet.previous.lat / 1e7f);
- prev_wp.setY(_global_triplet.previous.lon / 1e7f);
+void
+Navigator::status()
+{
+ warnx("Global position is %svalid", _global_pos.valid ? "" : "in");
+ if (_global_pos.valid) {
+ warnx("Longitude %5.5f degrees, latitude %5.5f degrees", _global_pos.lon / 1e7d, _global_pos.lat / 1e7d);
+ warnx("Altitude %5.5f meters, altitude above home %5.5f meters",
+ (double)_global_pos.alt, (double)_global_pos.relative_alt);
+ warnx("Ground velocity in m/s, x %5.5f, y %5.5f, z %5.5f",
+ (double)_global_pos.vx, (double)_global_pos.vy, (double)_global_pos.vz);
+ warnx("Compass heading in degrees %5.5f", (double)(_global_pos.yaw * M_RAD_TO_DEG_F));
+ }
+ if (_fence_valid) {
+ warnx("Geofence is valid");
+// 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");
+ }
- } 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);
+ switch (myState) {
+ case NAV_STATE_NONE:
+ warnx("State: None");
+ break;
+ case NAV_STATE_LOITER:
+ warnx("State: Loiter");
+ break;
+ case NAV_STATE_MISSION:
+ warnx("State: Mission");
+ break;
+ case NAV_STATE_RTL:
+ warnx("State: RTL");
+ break;
+ default:
+ warnx("State: Unknown");
+ break;
+ }
+}
- }
+StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = {
+ {
+ /* STATE_NONE */
+ /* EVENT_NONE_REQUESTED */ {NO_ACTION, NAV_STATE_NONE},
+ /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
+ /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER},
+ /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_NONE},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_NONE},
+ },
+ {
+ /* STATE_READY */
+ /* EVENT_NONE_REQUESTED */ {NO_ACTION, NAV_STATE_NONE},
+ /* EVENT_READY_REQUESTED */ {NO_ACTION, NAV_STATE_READY},
+ /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_READY},
+ /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_READY},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_READY},
+ },
+ {
+ /* STATE_LOITER */
+ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
+ /* EVENT_READY_REQUESTED */ {NO_ACTION, NAV_STATE_LOITER},
+ /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_LOITER},
+ /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER},
+ },
+ {
+ /* STATE_MISSION */
+ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
+ /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
+ /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER},
+ /* EVENT_MISSION_REQUESTED */ {NO_ACTION, NAV_STATE_MISSION},
+ /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ /* EVENT_MISSION_CHANGED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_MISSION},
+ },
+ {
+ /* STATE_RTL */
+ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
+ /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
+ /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER},
+ /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_RTL_REQUESTED */ {NO_ACTION, NAV_STATE_RTL},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_RTL},
+ /* EVENT_HOME_POSITION_CHANGED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ },
+};
+void
+Navigator::start_none()
+{
+ _mission_item_triplet.previous_valid = false;
+ _mission_item_triplet.current_valid = false;
+ _mission_item_triplet.next_valid = false;
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
+ _rtl_state = RTL_STATE_NONE;
- /******** MAIN NAVIGATION STATE MACHINE ********/
+ publish_mission_item_triplet();
+}
- // XXX to be put in its own class
+void
+Navigator::start_ready()
+{
+ _mission_item_triplet.previous_valid = false;
+ _mission_item_triplet.current_valid = false;
+ _mission_item_triplet.next_valid = false;
- if (_global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
- /* waypoint is a plain navigation waypoint */
-
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
- } 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) {
+ // TODO check
+ if (_rtl_state != RTL_STATE_LAND) {
+ _rtl_state = RTL_STATE_NONE;
+ }
- /* waypoint is a loiter waypoint */
-
- }
+ publish_mission_item_triplet();
+}
- // XXX at this point we always want no loiter hold if a
- // mission is active
- _loiter_hold = false;
+void
+Navigator::start_loiter()
+{
+ _do_takeoff = false;
- } else {
+ /* set loiter position if needed */
+ if (_reset_loiter_pos || !_mission_item_triplet.current_valid) {
+ _reset_loiter_pos = false;
- 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;
- }
+ _mission_item_triplet.current.lat = (double)_global_pos.lat / 1e7d;
+ _mission_item_triplet.current.lon = (double)_global_pos.lon / 1e7d;
+ _mission_item_triplet.current.yaw = NAN; // NAN means to use current yaw
+
+ _mission_item_triplet.current.altitude_is_relative = false;
+ float min_alt_amsl = _parameters.min_altitude + _home_pos.altitude;
+
+ /* use current altitude if above min altitude set by parameter */
+ if (_global_pos.alt < min_alt_amsl) {
+ _mission_item_triplet.current.altitude = min_alt_amsl;
+ mavlink_log_info(_mavlink_fd, "[navigator] loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt));
+ } else {
+ _mission_item_triplet.current.altitude = _global_pos.alt;
+ mavlink_log_info(_mavlink_fd, "[navigator] loiter at current altitude");
+ }
+ }
+
+ _mission_item_triplet.previous_valid = false;
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
- //_parameters.loiter_hold_radius
+ get_loiter_item(&_mission_item_triplet.current);
+
+ publish_mission_item_triplet();
+}
+
+void
+Navigator::start_mission()
+{
+ _need_takeoff = true;
+
+ mavlink_log_info(_mavlink_fd, "[navigator] mission started");
+ advance_mission();
+}
+
+void
+Navigator::advance_mission()
+{
+ /* copy current mission to previous item */
+ memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid;
+
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
+
+ int ret;
+ bool onboard;
+ unsigned index;
+
+ ret = _mission.get_current_mission_item(&_mission_item_triplet.current, &onboard, &index);
+
+ if (ret == OK) {
+ _mission_item_triplet.current_valid = true;
+ add_home_pos_to_rtl(&_mission_item_triplet.current);
+
+ if (_mission_item_triplet.current.nav_cmd != NAV_CMD_RETURN_TO_LAUNCH &&
+ _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_TIME_LIMIT &&
+ _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_TURN_COUNT &&
+ _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_UNLIMITED) {
+ /* don't reset RTL state on RTL or LOITER items */
+ _rtl_state = RTL_STATE_NONE;
+ }
+
+ if (_vstatus.is_rotary_wing) {
+ if (_need_takeoff && (
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_WAYPOINT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED
+ )) {
+ /* do special TAKEOFF handling for VTOL */
+ _need_takeoff = false;
+
+ /* calculate desired takeoff altitude AMSL */
+ float takeoff_alt_amsl = _mission_item_triplet.current.altitude;
+ if (_mission_item_triplet.current.altitude_is_relative)
+ takeoff_alt_amsl += _home_pos.altitude;
+
+ if (_vstatus.condition_landed) {
+ /* takeoff to at least NAV_TAKEOFF_ALT from ground if landed */
+ takeoff_alt_amsl = fmaxf(takeoff_alt_amsl, _global_pos.alt + _parameters.takeoff_alt);
}
- } else if (0/* seatbelt mode enabled */) {
+ /* check if we really need takeoff */
+ if (_vstatus.condition_landed || _global_pos.alt < takeoff_alt_amsl - _mission_item_triplet.current.acceptance_radius) {
+ /* force TAKEOFF if landed or waypoint altitude is more than current */
+ _do_takeoff = true;
- /** SEATBELT FLIGHT **/
- continue;
+ /* move current mission item to next */
+ memcpy(&_mission_item_triplet.next, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.next_valid = true;
- } else {
+ /* set current item to TAKEOFF */
+ get_takeoff_item(&_mission_item_triplet.current);
- /** MANUAL FLIGHT **/
+ _mission_item_triplet.current.lat = (double)_global_pos.lat / 1e7d;
+ _mission_item_triplet.current.lon = (double)_global_pos.lon / 1e7d;
+ _mission_item_triplet.current.altitude = takeoff_alt_amsl;
+ _mission_item_triplet.current.altitude_is_relative = false;
+ }
+ } else if (_mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) {
+ /* will need takeoff after landing */
+ _need_takeoff = true;
+ }
+ }
- /* no flight mode applies, do not publish an attitude setpoint */
- continue;
+ if (_do_takeoff) {
+ mavlink_log_info(_mavlink_fd, "[navigator] takeoff to %.1fm", _mission_item_triplet.current.altitude);
+ } else {
+ if (onboard) {
+ mavlink_log_info(_mavlink_fd, "[navigator] heading to onboard WP %d", index);
+ } else {
+ mavlink_log_info(_mavlink_fd, "[navigator] heading to offboard WP %d", index);
}
+ }
+ } else {
+ /* since a mission is not advanced without WPs available, this is not supposed to happen */
+ _mission_item_triplet.current_valid = false;
+ warnx("ERROR: current WP can't be set");
+ }
- /******** MAIN NAVIGATION STATE MACHINE ********/
+ if (!_do_takeoff) {
+ ret = _mission.get_next_mission_item(&_mission_item_triplet.next);
- if (_global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
- // XXX define launch position and return
+ if (ret == OK) {
+ add_home_pos_to_rtl(&_mission_item_triplet.next);
+ _mission_item_triplet.next_valid = true;
+ } else {
+ /* this will fail for the last WP */
+ _mission_item_triplet.next_valid = false;
+ }
+ }
+
+ publish_mission_item_triplet();
+}
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_LAND) {
- // XXX flared descent on final approach
+void
+Navigator::start_rtl()
+{
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
+ if (_rtl_state == RTL_STATE_NONE)
+ _rtl_state = RTL_STATE_CLIMB;
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL started");
+ set_rtl_item();
+}
- /* 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);
- }
+void
+Navigator::set_rtl_item()
+{
+ switch (_rtl_state) {
+ case RTL_STATE_CLIMB: {
+ memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid;
+
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
+
+ float climb_alt = _home_pos.altitude + _parameters.rtl_alt;
+ if (_vstatus.condition_landed)
+ climb_alt = fmaxf(climb_alt, _global_pos.alt + _parameters.rtl_alt);
+
+ _mission_item_triplet.current.altitude_is_relative = false;
+ _mission_item_triplet.current.lat = (double)_global_pos.lat / 1e7d;
+ _mission_item_triplet.current.lon = (double)_global_pos.lon / 1e7d;
+ _mission_item_triplet.current.altitude = climb_alt;
+ _mission_item_triplet.current.yaw = NAN;
+ _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius;
+ _mission_item_triplet.current.loiter_direction = 1;
+ _mission_item_triplet.current.nav_cmd = NAV_CMD_TAKEOFF;
+ _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item_triplet.current.time_inside = 0.0f;
+ _mission_item_triplet.current.pitch_min = 0.0f;
+ _mission_item_triplet.current.autocontinue = true;
+ _mission_item_triplet.current.origin = ORIGIN_ONBOARD;
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: climb to %.1fm", climb_alt - _home_pos.altitude);
+ break;
+ }
+ case RTL_STATE_RETURN: {
+ memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid;
+
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
+
+ _mission_item_triplet.current.altitude_is_relative = false;
+ _mission_item_triplet.current.lat = _home_pos.lat;
+ _mission_item_triplet.current.lon = _home_pos.lon;
+ // don't change altitude setpoint
+ _mission_item_triplet.current.yaw = NAN;
+ _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius;
+ _mission_item_triplet.current.loiter_direction = 1;
+ _mission_item_triplet.current.nav_cmd = NAV_CMD_WAYPOINT;
+ _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item_triplet.current.time_inside = 0.0f;
+ _mission_item_triplet.current.pitch_min = 0.0f;
+ _mission_item_triplet.current.autocontinue = true;
+ _mission_item_triplet.current.origin = ORIGIN_ONBOARD;
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: return");
+ break;
+ }
+ case RTL_STATE_DESCEND: {
+ memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid;
+
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
+
+ float descend_alt = _home_pos.altitude + _parameters.land_alt;
+
+ _mission_item_triplet.current.altitude_is_relative = false;
+ _mission_item_triplet.current.lat = _home_pos.lat;
+ _mission_item_triplet.current.lon = _home_pos.lon;
+ _mission_item_triplet.current.altitude = descend_alt;
+ _mission_item_triplet.current.yaw = NAN;
+ _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius;
+ _mission_item_triplet.current.loiter_direction = 1;
+ _mission_item_triplet.current.nav_cmd = NAV_CMD_WAYPOINT;
+ _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item_triplet.current.time_inside = 0.0f;
+ _mission_item_triplet.current.pitch_min = 0.0f;
+ _mission_item_triplet.current.autocontinue = true;
+ _mission_item_triplet.current.origin = ORIGIN_ONBOARD;
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: descend to %.1fm", descend_alt - _home_pos.altitude);
+ break;
+ }
+ case RTL_STATE_LAND: {
+ memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s));
+ _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid;
+
+ _mission_item_triplet.current_valid = true;
+ _mission_item_triplet.next_valid = false;
+
+ _mission_item_triplet.current.altitude_is_relative = false;
+ _mission_item_triplet.current.lat = _home_pos.lat;
+ _mission_item_triplet.current.lon = _home_pos.lon;
+ _mission_item_triplet.current.altitude = _home_pos.altitude;
+ _mission_item_triplet.current.yaw = NAN;
+ _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius;
+ _mission_item_triplet.current.loiter_direction = 1;
+ _mission_item_triplet.current.nav_cmd = NAV_CMD_LAND;
+ _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item_triplet.current.time_inside = 0.0f;
+ _mission_item_triplet.current.pitch_min = 0.0f;
+ _mission_item_triplet.current.autocontinue = true;
+ _mission_item_triplet.current.origin = ORIGIN_ONBOARD;
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: land");
+ break;
+ }
+ default: {
+ mavlink_log_critical(_mavlink_fd, "[navigator] error: unknown RTL state: %d", _rtl_state);
+ start_loiter();
+ break;
+ }
+ }
+
+ publish_mission_item_triplet();
+}
+
+bool
+Navigator::check_mission_item_reached()
+{
+ /* only check if there is actually a mission item to check */
+ if (!_mission_item_triplet.current_valid) {
+ return false;
+ }
+
+ if (_mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) {
+ return _vstatus.condition_landed;
+ }
+
+ /* XXX TODO count turns */
+ if ((_mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) &&
+ _mission_item_triplet.current.loiter_radius > 0.01f) {
+
+ return false;
+ }
+
+ uint64_t now = hrt_absolute_time();
+
+ if (!_waypoint_position_reached) {
+ float acceptance_radius;
+
+ if (_mission_item_triplet.current.nav_cmd == NAV_CMD_WAYPOINT && _mission_item_triplet.current.acceptance_radius > 0.01f) {
+ acceptance_radius = _mission_item_triplet.current.acceptance_radius;
+
+ } else {
+ acceptance_radius = _parameters.acceptance_radius;
+ }
+
+ float dist = -1.0f;
+ float dist_xy = -1.0f;
+ float dist_z = -1.0f;
+
+ /* current relative or AMSL altitude depending on mission item altitude_is_relative flag */
+ float wp_alt_amsl = _mission_item_triplet.current.altitude;
+ if (_mission_item_triplet.current.altitude_is_relative)
+ _mission_item_triplet.current.altitude += _home_pos.altitude;
+
+ dist = get_distance_to_point_global_wgs84(_mission_item_triplet.current.lat, _mission_item_triplet.current.lon, wp_alt_amsl,
+ (double)_global_pos.lat / 1e7d, (double)_global_pos.lon / 1e7d, _global_pos.alt,
+ &dist_xy, &dist_z);
+
+ if (_do_takeoff) {
+ if (_global_pos.alt > wp_alt_amsl - acceptance_radius) {
+ /* require only altitude for takeoff */
+ _waypoint_position_reached = true;
+ }
+ } else {
+ if (dist >= 0.0f && dist <= acceptance_radius) {
+ _waypoint_position_reached = true;
}
+ }
+ }
- /* 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);
+ if (!_waypoint_yaw_reached) {
+ if (_vstatus.is_rotary_wing && !_do_takeoff && isfinite(_mission_item_triplet.current.yaw)) {
+ /* check yaw if defined only for rotary wing except takeoff */
+ float yaw_err = _wrap_pi(_mission_item_triplet.current.yaw - _global_pos.yaw);
+ if (fabsf(yaw_err) < 0.05f) { /* XXX get rid of magic number */
+ _waypoint_yaw_reached = true;
+ }
+ } else {
+ _waypoint_yaw_reached = true;
+ }
+ }
- } else {
- /* advertise and publish */
- _triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &_global_triplet);
+ /* 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_triplet.current.time_inside > 0.01f) {
+ mavlink_log_info(_mavlink_fd, "[navigator] waypoint reached, wait for %.1fs", _mission_item_triplet.current.time_inside);
}
+ }
+
+ /* check if the MAV was long enough inside the waypoint orbit */
+ if ((now - _time_first_inside_orbit >= (uint64_t)_mission_item_triplet.current.time_inside * 1e6)
+ || _mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+ _time_first_inside_orbit = 0;
+ _waypoint_yaw_reached = false;
+ _waypoint_position_reached = false;
+ return true;
+ }
+ }
+ return false;
+
+}
+void
+Navigator::on_mission_item_reached()
+{
+ if (myState == NAV_STATE_MISSION) {
+ if (_do_takeoff) {
+ /* takeoff completed */
+ _do_takeoff = false;
+ mavlink_log_info(_mavlink_fd, "[navigator] takeoff completed");
+ } else {
+ /* advance by one mission item */
+ _mission.move_to_next();
}
- perf_end(_loop_perf);
+ if (_mission.current_mission_available()) {
+ advance_mission();
+ } else {
+ /* if no more mission items available then finish mission */
+ /* loiter at last waypoint */
+ _reset_loiter_pos = false;
+ mavlink_log_info(_mavlink_fd, "[navigator] mission completed");
+ if (_vstatus.condition_landed) {
+ dispatch(EVENT_READY_REQUESTED);
+ } else {
+ dispatch(EVENT_LOITER_REQUESTED);
+ }
+ }
+ } else {
+ /* RTL finished */
+ if (_rtl_state == RTL_STATE_LAND) {
+ /* landed at home position */
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL completed, landed");
+ dispatch(EVENT_READY_REQUESTED);
+ } else {
+ /* next RTL step */
+ _rtl_state = (RTLState)(_rtl_state + 1);
+ set_rtl_item();
+ }
}
+}
- warnx("exiting.\n");
+void
+Navigator::get_loiter_item(struct mission_item_s *item)
+{
+ //item->altitude_is_relative
+ //item->lat
+ //item->lon
+ //item->altitude
+ //item->yaw
+ item->loiter_radius = _parameters.loiter_radius;
+ item->loiter_direction = 1;
+ item->nav_cmd = NAV_CMD_LOITER_UNLIMITED;
+ item->acceptance_radius = _parameters.acceptance_radius;
+ item->time_inside = 0.0f;
+ item->pitch_min = 0.0f;
+ item->autocontinue = false;
+ item->origin = ORIGIN_ONBOARD;
- _navigator_task = -1;
- _exit(0);
}
-int
-Navigator::start()
+void
+Navigator::get_takeoff_item(mission_item_s *item)
{
- ASSERT(_navigator_task == -1);
+ //item->altitude_is_relative
+ //item->lat
+ //item->lon
+ //item->altitude
+ item->yaw = NAN;
+ item->loiter_radius = _parameters.loiter_radius;
+ item->loiter_direction = 1;
+ item->nav_cmd = NAV_CMD_TAKEOFF;
+ item->acceptance_radius = _parameters.acceptance_radius;
+ item->time_inside = 0.0f;
+ item->pitch_min = 0.0;
+ item->autocontinue = true;
+ item->origin = ORIGIN_ONBOARD;
+}
- /* start the task */
- _navigator_task = task_spawn_cmd("navigator",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 5,
- 2048,
- (main_t)&Navigator::task_main_trampoline,
- nullptr);
+void
+Navigator::add_home_pos_to_rtl(struct mission_item_s *new_mission_item)
+{
+ if (new_mission_item->nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
+ /* append the home position to RTL item */
+ new_mission_item->lat = _home_pos.lat;
+ new_mission_item->lon = _home_pos.lon;
+ new_mission_item->altitude = _home_pos.altitude + _parameters.rtl_alt;
+ new_mission_item->altitude_is_relative = false;
+ new_mission_item->loiter_radius = _parameters.loiter_radius;
+ new_mission_item->acceptance_radius = _parameters.acceptance_radius;
+ }
+}
- if (_navigator_task < 0) {
- warn("task start failed");
- return -errno;
+void
+Navigator::publish_mission_item_triplet()
+{
+ /* lazily publish the mission triplet only once available */
+ if (_triplet_pub > 0) {
+ /* publish the mission triplet */
+ orb_publish(ORB_ID(mission_item_triplet), _triplet_pub, &_mission_item_triplet);
+
+ } else {
+ /* advertise and publish */
+ _triplet_pub = orb_advertise(ORB_ID(mission_item_triplet), &_mission_item_triplet);
}
+}
- return OK;
+void
+Navigator::publish_control_mode()
+{
+ /* update vehicle_control_mode topic*/
+ _control_mode.main_state = _vstatus.main_state;
+ _control_mode.nav_state = static_cast<nav_state_t>(myState);
+ _control_mode.flag_armed = _vstatus.arming_state == ARMING_STATE_ARMED || _vstatus.arming_state == ARMING_STATE_ARMED_ERROR;
+ _control_mode.flag_external_manual_override_ok = !_vstatus.is_rotary_wing;
+ _control_mode.flag_system_hil_enabled = _vstatus.hil_state == HIL_STATE_ON;
+
+ _control_mode.flag_control_offboard_enabled = false;
+ _control_mode.flag_control_flighttermination_enabled = false;
+
+ switch (_vstatus.main_state) {
+ case MAIN_STATE_MANUAL:
+ _control_mode.flag_control_manual_enabled = true;
+ _control_mode.flag_control_rates_enabled = _vstatus.is_rotary_wing;
+ _control_mode.flag_control_attitude_enabled = _vstatus.is_rotary_wing;
+ _control_mode.flag_control_altitude_enabled = false;
+ _control_mode.flag_control_climb_rate_enabled = false;
+ _control_mode.flag_control_position_enabled = false;
+ _control_mode.flag_control_velocity_enabled = false;
+ break;
+
+ case MAIN_STATE_SEATBELT:
+ _control_mode.flag_control_manual_enabled = true;
+ _control_mode.flag_control_rates_enabled = true;
+ _control_mode.flag_control_attitude_enabled = true;
+ _control_mode.flag_control_altitude_enabled = true;
+ _control_mode.flag_control_climb_rate_enabled = true;
+ _control_mode.flag_control_position_enabled = false;
+ _control_mode.flag_control_velocity_enabled = false;
+ break;
+
+ case MAIN_STATE_EASY:
+ _control_mode.flag_control_manual_enabled = true;
+ _control_mode.flag_control_rates_enabled = true;
+ _control_mode.flag_control_attitude_enabled = true;
+ _control_mode.flag_control_altitude_enabled = true;
+ _control_mode.flag_control_climb_rate_enabled = true;
+ _control_mode.flag_control_position_enabled = true;
+ _control_mode.flag_control_velocity_enabled = true;
+ break;
+
+ case MAIN_STATE_AUTO:
+ _control_mode.flag_control_manual_enabled = false;
+ if (myState == NAV_STATE_READY) {
+ /* disable all controllers, armed but idle */
+ _control_mode.flag_control_rates_enabled = false;
+ _control_mode.flag_control_attitude_enabled = false;
+ _control_mode.flag_control_position_enabled = false;
+ _control_mode.flag_control_velocity_enabled = false;
+ _control_mode.flag_control_altitude_enabled = false;
+ _control_mode.flag_control_climb_rate_enabled = false;
+ } else {
+ _control_mode.flag_control_rates_enabled = true;
+ _control_mode.flag_control_attitude_enabled = true;
+ _control_mode.flag_control_position_enabled = true;
+ _control_mode.flag_control_velocity_enabled = true;
+ _control_mode.flag_control_altitude_enabled = true;
+ _control_mode.flag_control_climb_rate_enabled = true;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ _control_mode.timestamp = hrt_absolute_time();
+
+ /* lazily publish the mission triplet only once available */
+ if (_control_mode_pub > 0) {
+ /* publish the mission triplet */
+ orb_publish(ORB_ID(vehicle_control_mode), _control_mode_pub, &_control_mode);
+
+ } else {
+ /* advertise and publish */
+ _control_mode_pub = orb_advertise(ORB_ID(vehicle_control_mode), &_control_mode);
+ }
+}
+
+bool Navigator::cmp_mission_item_equivalent(const struct mission_item_s a, const struct mission_item_s b) {
+ if (a.altitude_is_relative == b.altitude_is_relative &&
+ fabs(a.lat - b.lat) < FLT_EPSILON &&
+ fabs(a.lon - b.lon) < FLT_EPSILON &&
+ fabsf(a.altitude - b.altitude) < FLT_EPSILON &&
+ fabsf(a.yaw - b.yaw) < FLT_EPSILON &&
+ fabsf(a.loiter_radius - b.loiter_radius) < FLT_EPSILON &&
+ a.loiter_direction == b.loiter_direction &&
+ a.nav_cmd == b.nav_cmd &&
+ fabsf(a.acceptance_radius - b.acceptance_radius) < FLT_EPSILON &&
+ fabsf(a.time_inside - b.time_inside) < FLT_EPSILON &&
+ a.autocontinue == b.autocontinue) {
+ return true;
+ } else {
+ return false;
+ }
+}
+
+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 +1560,27 @@ 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_mission.cpp b/src/modules/navigator/navigator_mission.cpp
new file mode 100644
index 000000000..6576aae70
--- /dev/null
+++ b/src/modules/navigator/navigator_mission.cpp
@@ -0,0 +1,257 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Julian Oes <joes@student.ethz.ch>
+ *
+ * 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
+ */
+
+// #include <stdio.h>
+// #include <stdlib.h>
+// #include <string.h>
+// #include <unistd.h>
+
+#include <stdlib.h>
+#include <dataman/dataman.h>
+#include "navigator_mission.h"
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+
+Mission::Mission() :
+
+ _offboard_dataman_id(-1),
+ _current_offboard_mission_index(0),
+ _current_onboard_mission_index(0),
+ _offboard_mission_item_count(0),
+ _onboard_mission_item_count(0),
+ _onboard_mission_allowed(false),
+ _current_mission_type(MISSION_TYPE_NONE)
+{}
+
+Mission::~Mission()
+{
+
+}
+
+void
+Mission::set_offboard_dataman_id(int new_id)
+{
+ _offboard_dataman_id = new_id;
+}
+
+void
+Mission::set_current_offboard_mission_index(int new_index)
+{
+ if (new_index != -1) {
+ _current_offboard_mission_index = (unsigned)new_index;
+ }
+}
+
+void
+Mission::set_current_onboard_mission_index(int new_index)
+{
+ if (new_index != -1) {
+ _current_onboard_mission_index = (unsigned)new_index;
+ }
+}
+
+void
+Mission::set_offboard_mission_count(unsigned new_count)
+{
+ _offboard_mission_item_count = new_count;
+}
+
+void
+Mission::set_onboard_mission_count(unsigned new_count)
+{
+ _onboard_mission_item_count = new_count;
+}
+
+void
+Mission::set_onboard_mission_allowed(bool allowed)
+{
+ _onboard_mission_allowed = allowed;
+}
+
+bool
+Mission::current_mission_available()
+{
+ return (current_onboard_mission_available() || current_offboard_mission_available());
+
+}
+
+bool
+Mission::next_mission_available()
+{
+ return (next_onboard_mission_available() || next_offboard_mission_available());
+}
+
+int
+Mission::get_current_mission_item(struct mission_item_s *new_mission_item, bool *onboard, unsigned *index)
+{
+ /* try onboard mission first */
+ if (current_onboard_mission_available()) {
+
+ const ssize_t len = sizeof(struct mission_item_s);
+ if (dm_read(DM_KEY_WAYPOINTS_ONBOARD, _current_onboard_mission_index, new_mission_item, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return ERROR;
+ }
+ _current_mission_type = MISSION_TYPE_ONBOARD;
+ *onboard = true;
+ *index = _current_onboard_mission_index;
+
+ /* otherwise fallback to offboard */
+ } else if (current_offboard_mission_available()) {
+
+ dm_item_t dm_current;
+
+ if (_offboard_dataman_id == 0) {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ } else {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ }
+
+ const ssize_t len = sizeof(struct mission_item_s);
+ if (dm_read(dm_current, _current_offboard_mission_index, new_mission_item, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ _current_mission_type = MISSION_TYPE_NONE;
+ return ERROR;
+ }
+ _current_mission_type = MISSION_TYPE_OFFBOARD;
+ *onboard = false;
+ *index = _current_offboard_mission_index;
+
+ } else {
+ /* happens when no more mission items can be added as a next item */
+ _current_mission_type = MISSION_TYPE_NONE;
+ return ERROR;
+ }
+
+ return OK;
+}
+
+int
+Mission::get_next_mission_item(struct mission_item_s *new_mission_item)
+{
+ /* try onboard mission first */
+ if (next_onboard_mission_available()) {
+
+ const ssize_t len = sizeof(struct mission_item_s);
+ if (dm_read(DM_KEY_WAYPOINTS_ONBOARD, _current_onboard_mission_index + 1, new_mission_item, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return ERROR;
+ }
+
+ /* otherwise fallback to offboard */
+ } else if (next_offboard_mission_available()) {
+
+ dm_item_t dm_current;
+
+ if (_offboard_dataman_id == 0) {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ } else {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ }
+
+ const ssize_t len = sizeof(struct mission_item_s);
+ if (dm_read(dm_current, _current_offboard_mission_index + 1, new_mission_item, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ return ERROR;
+ }
+
+ } else {
+ /* happens when no more mission items can be added as a next item */
+ return ERROR;
+ }
+
+ return OK;
+}
+
+
+bool
+Mission::current_onboard_mission_available()
+{
+ return _onboard_mission_item_count > _current_onboard_mission_index && _onboard_mission_allowed;
+}
+
+bool
+Mission::current_offboard_mission_available()
+{
+ return _offboard_mission_item_count > _current_offboard_mission_index;
+}
+
+bool
+Mission::next_onboard_mission_available()
+{
+ unsigned next = 0;
+
+ if (_current_mission_type != MISSION_TYPE_ONBOARD) {
+ next = 1;
+ }
+
+ return _onboard_mission_item_count > (_current_onboard_mission_index + next) && _onboard_mission_allowed;
+}
+
+bool
+Mission::next_offboard_mission_available()
+{
+ unsigned next = 0;
+
+ if (_current_mission_type != MISSION_TYPE_OFFBOARD) {
+ next = 1;
+ }
+
+ return _offboard_mission_item_count > (_current_offboard_mission_index + next);
+}
+
+void
+Mission::move_to_next()
+{
+ switch (_current_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;
+ }
+} \ No newline at end of file
diff --git a/src/modules/navigator/navigator_mission.h b/src/modules/navigator/navigator_mission.h
new file mode 100644
index 000000000..15d4e86bf
--- /dev/null
+++ b/src/modules/navigator/navigator_mission.h
@@ -0,0 +1,97 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Julian Oes <joes@student.ethz.ch>
+ *
+ * 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.h
+ * Helper class to access missions
+ */
+
+#ifndef NAVIGATOR_MISSION_H
+#define NAVIGATOR_MISSION_H
+
+#include <uORB/topics/mission.h>
+
+
+class __EXPORT Mission
+{
+public:
+ /**
+ * Constructor
+ */
+ Mission();
+
+ /**
+ * Destructor, also kills the sensors task.
+ */
+ ~Mission();
+
+ void set_offboard_dataman_id(int new_id);
+ void set_current_offboard_mission_index(int new_index);
+ void set_current_onboard_mission_index(int new_index);
+ void set_offboard_mission_count(unsigned new_count);
+ void set_onboard_mission_count(unsigned new_count);
+
+ void set_onboard_mission_allowed(bool allowed);
+
+ bool current_mission_available();
+ bool next_mission_available();
+
+ int get_current_mission_item(struct mission_item_s *mission_item, bool *onboard, unsigned *index);
+ int get_next_mission_item(struct mission_item_s *mission_item);
+
+ void move_to_next();
+
+ void add_home_pos(struct mission_item_s *new_mission_item);
+
+private:
+ bool current_onboard_mission_available();
+ bool current_offboard_mission_available();
+ bool next_onboard_mission_available();
+ bool next_offboard_mission_available();
+
+ int _offboard_dataman_id;
+ unsigned _current_offboard_mission_index;
+ unsigned _current_onboard_mission_index;
+ unsigned _offboard_mission_item_count; /** number of offboard mission items available */
+ unsigned _onboard_mission_item_count; /** number of onboard mission items available */
+
+ bool _onboard_mission_allowed;
+
+ enum {
+ MISSION_TYPE_NONE,
+ MISSION_TYPE_ONBOARD,
+ MISSION_TYPE_OFFBOARD,
+ } _current_mission_type;
+};
+
+#endif \ No newline at end of file
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 06df9a452..8df47fc3b 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -1,7 +1,8 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Author: @autho Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -38,6 +39,7 @@
* Parameters defined by the navigator task.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#include <nuttx/config.h>
@@ -49,5 +51,10 @@
*
*/
-PARAM_DEFINE_FLOAT(NAV_DUMMY, 0.0f);
-
+PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f);
+PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f);
+PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 100.0f);
+PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0);
+PARAM_DEFINE_FLOAT(NAV_TAAKEOFF_ALT, 10.0f); // default TAKEOFF altitude
+PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing
+PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); // min altitude for going home in RTL mode