aboutsummaryrefslogtreecommitdiff
path: root/src/modules/navigator/navigator_main.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/navigator/navigator_main.cpp')
-rw-r--r--src/modules/navigator/navigator_main.cpp85
1 files changed, 80 insertions, 5 deletions
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index 042c46afd..bc9951bf2 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -40,6 +40,7 @@
* @author Jean Cyr <jean.m.cyr@gmail.com>
* @author Julian Oes <julian@oes.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <nuttx/config.h>
@@ -68,6 +69,7 @@
#include <uORB/topics/fence.h>
#include <uORB/topics/navigation_capabilities.h>
#include <uORB/topics/offboard_control_setpoint.h>
+#include <drivers/drv_baro.h>
#include <systemlib/err.h>
#include <systemlib/systemlib.h>
@@ -107,13 +109,16 @@ Navigator::Navigator() :
_offboard_mission_sub(-1),
_param_update_sub(-1),
_pos_sp_triplet_pub(-1),
+ _mission_result_pub(-1),
_vstatus{},
_control_mode{},
_global_pos{},
+ _sensor_combined{},
_home_pos{},
_mission_item{},
_nav_caps{},
_pos_sp_triplet{},
+ _mission_result{},
_mission_item_valid(false),
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
_geofence{},
@@ -125,16 +130,23 @@ Navigator::Navigator() :
_loiter(this, "LOI"),
_rtl(this, "RTL"),
_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"),
- _param_acceptance_radius(this, "ACC_RAD")
+ _param_acceptance_radius(this, "ACC_RAD"),
+ _param_datalinkloss_obc(this, "DLL_OBC")
{
/* Create a list of our possible navigation types */
_navigation_mode_array[0] = &_mission;
_navigation_mode_array[1] = &_loiter;
_navigation_mode_array[2] = &_rtl;
_navigation_mode_array[3] = &_offboard;
+ _navigation_mode_array[4] = &_dataLinkLoss;
+ _navigation_mode_array[5] = &_engineFailure;
+ _navigation_mode_array[6] = &_gpsFailure;
updateParams();
}
@@ -171,6 +183,12 @@ Navigator::global_position_update()
}
void
+Navigator::sensor_combined_update()
+{
+ orb_copy(ORB_ID(sensor_combined), _sensor_combined_sub, &_sensor_combined);
+}
+
+void
Navigator::home_position_update()
{
orb_copy(ORB_ID(home_position), _home_pos_sub, &_home_pos);
@@ -240,6 +258,7 @@ Navigator::task_main()
/* do subscriptions */
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ _sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
_capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
@@ -253,6 +272,7 @@ Navigator::task_main()
vehicle_status_update();
vehicle_control_mode_update();
global_position_update();
+ sensor_combined_update();
home_position_update();
navigation_capabilities_update();
params_update();
@@ -264,7 +284,7 @@ Navigator::task_main()
const hrt_abstime mavlink_open_interval = 500000;
/* wakeup source(s) */
- struct pollfd fds[6];
+ struct pollfd fds[7];
/* Setup of loop */
fds[0].fd = _global_pos_sub;
@@ -279,6 +299,8 @@ Navigator::task_main()
fds[4].events = POLLIN;
fds[5].fd = _param_update_sub;
fds[5].events = POLLIN;
+ fds[6].fd = _sensor_combined_sub;
+ fds[6].events = POLLIN;
while (!_task_should_exit) {
@@ -303,6 +325,11 @@ Navigator::task_main()
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
}
+ /* sensors combined updated */
+ if (fds[6].revents & POLLIN) {
+ sensor_combined_update();
+ }
+
/* parameters updated */
if (fds[5].revents & POLLIN) {
params_update();
@@ -334,7 +361,18 @@ Navigator::task_main()
global_position_update();
/* Check geofence violation */
- if (!_geofence.inside(&_global_pos)) {
+ bool inside = false;
+ if (_geofence.getAltitudeMode() == Geofence::GF_ALT_MODE_GPS) {
+ inside = _geofence.inside(_global_pos);
+ } else {
+ inside = _geofence.inside(_global_pos, _sensor_combined.baro_alt_meter);
+ }
+ if (!inside) {
+ /* inform other apps via the sp triplet */
+ _pos_sp_triplet.geofence_violated = true;
+ if (_pos_sp_triplet.geofence_violated != true) {
+ _pos_sp_triplet_updated = true;
+ }
/* Issue a warning about the geofence violation once */
if (!_geofence_violation_warning_sent) {
@@ -342,6 +380,11 @@ Navigator::task_main()
_geofence_violation_warning_sent = true;
}
} else {
+ /* inform other apps via the sp triplet */
+ _pos_sp_triplet.geofence_violated = false;
+ if (_pos_sp_triplet.geofence_violated != false) {
+ _pos_sp_triplet_updated = true;
+ }
/* Reset the _geofence_violation_warning_sent field */
_geofence_violation_warning_sent = false;
}
@@ -359,6 +402,9 @@ Navigator::task_main()
_can_loiter_at_sp = false;
break;
case NAVIGATION_STATE_AUTO_MISSION:
+ /* Some failsafe modes prohibit the fallback to mission
+ * usually this is done after some time to make sure
+ * that the full failsafe operation is performed */
_navigation_mode = &_mission;
break;
case NAVIGATION_STATE_AUTO_LOITER:
@@ -367,8 +413,20 @@ Navigator::task_main()
case NAVIGATION_STATE_AUTO_RTL:
_navigation_mode = &_rtl;
break;
- case NAVIGATION_STATE_AUTO_RTGS:
- _navigation_mode = &_rtl; /* TODO: change this to something else */
+ case NAVIGATION_STATE_AUTO_RTGS: //XXX OBC: differentiate between rc loss and dl loss here
+ /* Use complex data link loss mode only when enabled via param
+ * otherwise use rtl */
+ if (_param_datalinkloss_obc.get() != 0) {
+ _navigation_mode = &_dataLinkLoss;
+ } else {
+ _navigation_mode = &_rtl; /* TODO: change this to something else */
+ }
+ break;
+ case NAVIGATION_STATE_AUTO_LANDENGFAIL:
+ _navigation_mode = &_engineFailure;
+ break;
+ case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
+ _navigation_mode = &_gpsFailure;
break;
case NAVIGATION_STATE_OFFBOARD:
_navigation_mode = &_offboard;
@@ -534,3 +592,20 @@ int navigator_main(int argc, char *argv[])
return 0;
}
+
+void
+Navigator::publish_mission_result()
+{
+ /* lazily publish the mission result only once available */
+ if (_mission_result_pub > 0) {
+ /* publish mission result */
+ orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);
+
+ } else {
+ /* advertise and publish */
+ _mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
+ }
+ /* reset reached bool */
+ _mission_result.reached = false;
+ _mission_result.finished = false;
+}