aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/state_machine_helper.cpp7
-rw-r--r--src/modules/navigator/datalinkloss.cpp2
-rw-r--r--src/modules/navigator/gpsfailure.cpp170
-rw-r--r--src/modules/navigator/gpsfailure.h86
-rw-r--r--src/modules/navigator/module.mk3
-rw-r--r--src/modules/navigator/navigator.h4
-rw-r--r--src/modules/navigator/navigator_main.cpp5
7 files changed, 272 insertions, 5 deletions
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 3f4bfaa1c..404bafb04 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -499,12 +499,15 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL;
} else if (status->data_link_lost_cmd) {
status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
- //} else if (status->gps_failure_cmd) {
- //status->nav_state = NAVIGATION_STATE_AUTO_***;
+ } else if (status->gps_failure_cmd) {
+ status->nav_state = NAVIGATION_STATE_AUTO_LANDGPSFAIL;
} else if (status->rc_signal_lost_cmd) {
status->nav_state = NAVIGATION_STATE_AUTO_RTGS; //XXX
+ /* Finished handling commands which have priority , now handle failures */
} else if (status->engine_failure) {
status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL;
+ } else if (status->gps_failure) {
+ status->nav_state = NAVIGATION_STATE_AUTO_LANDGPSFAIL;
} else if (((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) ||
(!data_link_loss_enabled && status->rc_signal_lost && mission_finished)) {
status->failsafe = true;
diff --git a/src/modules/navigator/datalinkloss.cpp b/src/modules/navigator/datalinkloss.cpp
index b914fdb34..d8a1de229 100644
--- a/src/modules/navigator/datalinkloss.cpp
+++ b/src/modules/navigator/datalinkloss.cpp
@@ -32,7 +32,7 @@
****************************************************************************/
/**
* @file datalinkloss.cpp
- * Helper class for Data Link Loss Mode acording to the OBC rules
+ * Helper class for Data Link Loss Mode according to the OBC rules
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
diff --git a/src/modules/navigator/gpsfailure.cpp b/src/modules/navigator/gpsfailure.cpp
new file mode 100644
index 000000000..4c526b76e
--- /dev/null
+++ b/src/modules/navigator/gpsfailure.cpp
@@ -0,0 +1,170 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file gpsfailure.cpp
+ * Helper class for gpsfailure mode according to the OBC rules
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/home_position.h>
+
+#include "navigator.h"
+#include "gpsfailure.h"
+
+#define DELAY_SIGMA 0.01f
+
+GpsFailure::GpsFailure(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name),
+ _gpsf_state(GPSF_STATE_NONE)
+{
+ /* load initial params */
+ updateParams();
+ /* initial reset */
+ on_inactive();
+}
+
+GpsFailure::~GpsFailure()
+{
+}
+
+void
+GpsFailure::on_inactive()
+{
+ /* reset GPSF state only if setpoint moved */
+ if (!_navigator->get_can_loiter_at_sp()) {
+ _gpsf_state = GPSF_STATE_NONE;
+ }
+}
+
+void
+GpsFailure::on_activation()
+{
+ _gpsf_state = GPSF_STATE_NONE;
+ updateParams();
+ advance_gpsf();
+ set_gpsf_item();
+}
+
+void
+GpsFailure::on_active()
+{
+ if (is_mission_item_reached()) {
+ updateParams();
+ advance_gpsf();
+ set_gpsf_item();
+ }
+}
+
+void
+GpsFailure::set_gpsf_item()
+{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ set_previous_pos_setpoint();
+ _navigator->set_can_loiter_at_sp(false);
+
+ switch (_gpsf_state) {
+ case GPSF_STATE_LOITER: {
+ //_mission_item.lat = (double)(_param_commsholdlat.get()) * 1.0e-7;
+ //_mission_item.lon = (double)(_param_commsholdlon.get()) * 1.0e-7;
+ //_mission_item.altitude_is_relative = false;
+ //_mission_item.altitude = _param_commsholdalt.get();
+ //_mission_item.yaw = NAN;
+ //_mission_item.loiter_radius = _navigator->get_loiter_radius();
+ //_mission_item.loiter_direction = 1;
+ //_mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
+ //_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ //_mission_item.time_inside = _param_commsholdwaittime.get() < 0.0f ? 0.0f : _param_commsholdwaittime.get();
+ //_mission_item.pitch_min = 0.0f;
+ //_mission_item.autocontinue = true;
+ //_mission_item.origin = ORIGIN_ONBOARD;
+
+ //_navigator->set_can_loiter_at_sp(true);
+ break;
+ }
+ case GPSF_STATE_TERMINATE: {
+ //_mission_item.lat = (double)(_param_airfieldhomelat.get()) * 1.0e-7;
+ //_mission_item.lon = (double)(_param_airfieldhomelon.get()) * 1.0e-7;
+ //_mission_item.altitude_is_relative = false;
+ //_mission_item.altitude = _param_airfieldhomealt.get();
+ //_mission_item.yaw = NAN;
+ //_mission_item.loiter_radius = _navigator->get_loiter_radius();
+ //_mission_item.loiter_direction = 1;
+ //_mission_item.nav_cmd = NAV_CMD_LOITER_UNLIMITED;
+ //_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ //_mission_item.pitch_min = 0.0f;
+ //_mission_item.autocontinue = true;
+ //_mission_item.origin = ORIGIN_ONBOARD;
+
+ //_navigator->set_can_loiter_at_sp(true);
+ break;
+ }
+ default:
+ break;
+ }
+
+ reset_mission_item_reached();
+
+ /* convert mission item to current position setpoint and make it valid */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ pos_sp_triplet->next.valid = false;
+
+ _navigator->set_position_setpoint_triplet_updated();
+}
+
+void
+GpsFailure::advance_gpsf()
+{
+ switch (_gpsf_state) {
+ case GPSF_STATE_NONE:
+ _gpsf_state = GPSF_STATE_LOITER;
+ break;
+ case GPSF_STATE_LOITER:
+ _gpsf_state = GPSF_STATE_TERMINATE;
+ break;
+ default:
+ break;
+ }
+}
diff --git a/src/modules/navigator/gpsfailure.h b/src/modules/navigator/gpsfailure.h
new file mode 100644
index 000000000..88d386ec4
--- /dev/null
+++ b/src/modules/navigator/gpsfailure.h
@@ -0,0 +1,86 @@
+/***************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file gpsfailure.h
+ * Helper class for Data Link Loss Mode according to the OBC rules
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#ifndef NAVIGATOR_GPSFAILURE_H
+#define NAVIGATOR_GPSFAILURE_H
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <uORB/Subscription.hpp>
+
+#include "navigator_mode.h"
+#include "mission_block.h"
+
+class Navigator;
+
+class GpsFailure : public MissionBlock
+{
+public:
+ GpsFailure(Navigator *navigator, const char *name);
+
+ ~GpsFailure();
+
+ virtual void on_inactive();
+
+ virtual void on_activation();
+
+ virtual void on_active();
+
+private:
+ /* Params */
+
+ enum GPSFState {
+ GPSF_STATE_NONE = 0,
+ GPSF_STATE_LOITER = 1,
+ GPSF_STATE_TERMINATE = 2,
+ } _gpsf_state;
+
+ /**
+ * Set the GPSF item
+ */
+ void set_gpsf_item();
+
+ /**
+ * Move to next GPSF item
+ */
+ void advance_gpsf();
+
+};
+#endif
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index 0539087df..f6590605b 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -52,7 +52,8 @@ SRCS = navigator_main.cpp \
geofence_params.c \
datalinkloss.cpp \
enginefailure.cpp \
- datalinkloss_params.c
+ datalinkloss_params.c \
+ gpsfailure.cpp
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h
index 59a6752a9..b161c2984 100644
--- a/src/modules/navigator/navigator.h
+++ b/src/modules/navigator/navigator.h
@@ -61,12 +61,13 @@
#include "offboard.h"
#include "datalinkloss.h"
#include "enginefailure.h"
+#include "gpsfailure.h"
#include "geofence.h"
/**
* Number of navigation modes that need on_active/on_inactive calls
*/
-#define NAVIGATOR_MODE_ARRAY_SIZE 6
+#define NAVIGATOR_MODE_ARRAY_SIZE 7
class Navigator : public control::SuperBlock
{
@@ -184,6 +185,7 @@ private:
DataLinkLoss _dataLinkLoss; /**< class that handles the OBC datalink loss mode */
EngineFailure _engineFailure; /**< class that handles the engine failure mode
(FW only!) */
+ GpsFailure _gpsFailure; /**< class that handles the OBC gpsfailure loss mode */
NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE]; /**< array of navigation modes */
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index d77acf74e..d77825715 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -132,6 +132,7 @@ Navigator::Navigator() :
_offboard(this, "OFF"),
_dataLinkLoss(this, "DLL"),
_engineFailure(this, "EF"),
+ _gpsFailure(this, "GPSF"),
_can_loiter_at_sp(false),
_pos_sp_triplet_updated(false),
_param_loiter_radius(this, "LOITER_RAD"),
@@ -145,6 +146,7 @@ Navigator::Navigator() :
_navigation_mode_array[3] = &_offboard;
_navigation_mode_array[4] = &_dataLinkLoss;
_navigation_mode_array[5] = &_engineFailure;
+ _navigation_mode_array[6] = &_gpsFailure;
updateParams();
}
@@ -421,6 +423,9 @@ Navigator::task_main()
case NAVIGATION_STATE_AUTO_LANDENGFAIL:
_navigation_mode = &_engineFailure;
break;
+ case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
+ _navigation_mode = &_gpsFailure;
+ break;
case NAVIGATION_STATE_LAND:
case NAVIGATION_STATE_TERMINATION:
case NAVIGATION_STATE_OFFBOARD: