aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/modules/navigator/geofence.cpp15
-rw-r--r--src/modules/navigator/geofence.h6
-rw-r--r--src/modules/navigator/geofence_params.c55
-rw-r--r--src/modules/navigator/module.mk3
-rw-r--r--src/modules/navigator/navigator_main.cpp2
5 files changed, 78 insertions, 3 deletions
diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp
index a49a71e1b..9bbaf167a 100644
--- a/src/modules/navigator/geofence.cpp
+++ b/src/modules/navigator/geofence.cpp
@@ -58,9 +58,11 @@ static const int ERROR = -1;
Geofence::Geofence() : _fence_pub(-1),
_altitude_min(0),
_altitude_max(0),
- _verticesCount(0)
+ _verticesCount(0),
+ param_geofence_on(NULL, "GF_ON", false)
{
-
+ /* Load initial params */
+ updateParams();
}
Geofence::~Geofence()
@@ -80,6 +82,10 @@ bool Geofence::inside(const struct vehicle_global_position_s *vehicle)
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()) {
@@ -286,3 +292,8 @@ 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
index 781e7a263..5b56ebc7a 100644
--- a/src/modules/navigator/geofence.h
+++ b/src/modules/navigator/geofence.h
@@ -41,6 +41,7 @@
#define GEOFENCE_H_
#include <uORB/topics/fence.h>
+#include <controllib/block/BlockParam.hpp>
#define GEOFENCE_FILENAME "/fs/microsd/etc/geofence.txt"
@@ -52,6 +53,9 @@ private:
float _altitude_max;
unsigned _verticesCount;
+
+ /* Params */
+ control::BlockParamInt param_geofence_on;
public:
Geofence();
~Geofence();
@@ -81,6 +85,8 @@ public:
int loadFromFile(const char *filename);
bool isEmpty() {return _verticesCount == 0;}
+
+ void updateParams();
};
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/module.mk b/src/modules/navigator/module.mk
index b7900e84e..55f8a4caa 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -41,6 +41,7 @@ SRCS = navigator_main.cpp \
navigator_params.c \
navigator_mission.cpp \
mission_feasibility_checker.cpp \
- geofence.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 8b5cc4576..b6059a01e 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -458,6 +458,8 @@ Navigator::parameters_update()
param_get(_parameter_handles.rtl_alt, &(_parameters.rtl_alt));
_mission.set_onboard_mission_allowed((bool)_parameter_handles.onboard_mission_enabled);
+
+ _geofence.updateParams();
}
void