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.cpp1563
1 files changed, 1317 insertions, 246 deletions
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index f6c44444a..260356eca 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -1,7 +1,10 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,6 +39,12 @@
* Implementation of the main navigation state machine.
*
* Handles missions, geo fencing and failsafe navigation behavior.
+ * Published the mission item triplet for the position controller.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <nuttx/config.h>
@@ -48,26 +57,44 @@
#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/position_setpoint_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_state.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 +103,7 @@
*/
extern "C" __EXPORT int navigator_main(int argc, char *argv[]);
-class Navigator
+class Navigator : public StateTable
{
public:
/**
@@ -85,103 +112,175 @@ 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 */
+ int _control_mode_sub; /**< vehicle control mode subscription */
- orb_advert_t _triplet_pub; /**< position setpoint */
+ orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */
+ orb_advert_t _mission_result_pub; /**< publish mission result 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 position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */
+ struct mission_result_s _mission_result; /**< mission result for commander/mavlink */
+ struct mission_item_s _mission_item; /**< current mission item */
+ bool _mission_item_valid; /**< current mission item valid */
perf_counter_t _loop_perf; /**< loop performance counter */
- unsigned _mission_items_maxcount; /**< maximum number of mission items supported */
- struct mission_item_s * _mission_items; /**< storage for mission items */
- bool _mission_valid; /**< flag if mission is valid */
+ Geofence _geofence;
+ bool _geofence_violation_warning_sent;
+
+ bool _fence_valid; /**< flag if fence is valid */
+ bool _inside_fence; /**< vehicle is inside fence */
+
+ struct navigation_capabilities_s _nav_caps;
+
+ class Mission _mission;
+
+ bool _global_pos_valid; /**< track changes of global_position.global_valid flag */
+ 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;
- /** 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;
+ uint64_t _set_nav_state_timestamp; /**< timestamp of last handled navigation state request */
+
+ bool _pos_sp_triplet_updated;
+
+ char *nav_states_str[NAV_STATE_MAX];
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;
+ float rtl_land_delay;
+ } _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;
+ param_t rtl_land_delay;
+ } _parameter_handles; /**< handles for parameters */
+
+ enum Event {
+ EVENT_NONE_REQUESTED,
+ EVENT_READY_REQUESTED,
+ EVENT_LOITER_REQUESTED,
+ EVENT_MISSION_REQUESTED,
+ EVENT_RTL_REQUESTED,
+ EVENT_LAND_REQUESTED,
+ EVENT_MISSION_CHANGED,
+ EVENT_HOME_POSITION_CHANGED,
+ MAX_EVENT
+ };
- } _parameter_handles; /**< handles for interesting parameters */
+ /**
+ * State machine transition table
+ */
+ static StateTable::Tran const myTable[NAV_STATE_MAX][MAX_EVENT];
+ enum RTLState {
+ RTL_STATE_NONE = 0,
+ RTL_STATE_CLIMB,
+ RTL_STATE_RETURN,
+ RTL_STATE_DESCEND
+ };
+
+ 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();
+ /**
+ * Retrieve vehicle control mode
+ */
+ void vehicle_control_mode_update();
/**
* Shim for calling task_main from task_create.
@@ -192,6 +291,64 @@ 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 start_land();
+ void start_land_home();
+
+ /**
+ * 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 set_mission_item();
+
+ /**
+ * Switch to next RTL state
+ */
+ void set_rtl_item();
+
+ /**
+ * Set position setpoint for mission item
+ */
+ void position_setpoint_from_mission_item(position_setpoint_s *sp, mission_item_s *item);
+
+ /**
+ * Helper function to get a takeoff item
+ */
+ void get_takeoff_setpoint(position_setpoint_s *pos_sp);
+
+ /**
+ * Publish a new mission item triplet for position controller
+ */
+ void publish_position_setpoint_triplet();
};
namespace navigator
@@ -208,37 +365,71 @@ Navigator *g_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),
+ _control_mode_sub(-1),
_params_sub(-1),
- _manual_control_sub(-1),
+ _offboard_mission_sub(-1),
+ _onboard_mission_sub(-1),
+ _capabilities_sub(-1),
/* publications */
- _triplet_pub(-1),
+ _pos_sp_triplet_pub(-1),
+ _mission_result_pub(-1),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
-/* states */
- _mission_items_maxcount(20),
- _mission_valid(false),
- _loiter_hold(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();
+/* states */
+ _rtl_state(RTL_STATE_NONE),
+ _fence_valid(false),
+ _inside_fence(true),
+ _mission(),
+ _global_pos_valid(false),
+ _reset_loiter_pos(true),
+ _waypoint_position_reached(false),
+ _waypoint_yaw_reached(false),
+ _time_first_inside_orbit(0),
+ _set_nav_state_timestamp(0),
+ _mission_item_valid(false),
+ _need_takeoff(true),
+ _do_takeoff(false),
+ _pos_sp_triplet_updated(false),
+ _geofence_violation_warning_sent(false)
+{
+ _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");
+ _parameter_handles.rtl_land_delay = param_find("NAV_RTL_LAND_T");
+
+ memset(&_pos_sp_triplet, 0, sizeof(struct position_setpoint_triplet_s));
+ memset(&_mission_result, 0, sizeof(struct mission_result_s));
+ memset(&_mission_item, 0, sizeof(struct mission_item_s));
+
+ memset(&nav_states_str, 0, sizeof(nav_states_str));
+ nav_states_str[0] = "NONE";
+ nav_states_str[1] = "READY";
+ nav_states_str[2] = "LOITER";
+ nav_states_str[3] = "MISSION";
+ nav_states_str[4] = "RTL";
+ nav_states_str[5] = "LAND";
+
+ /* Initialize state machine */
+ myState = NAV_STATE_NONE;
+ start_none();
}
Navigator::~Navigator()
@@ -266,69 +457,108 @@ Navigator::~Navigator()
navigator::g_navigator = nullptr;
}
-int
+void
Navigator::parameters_update()
{
-
- //param_get(_parameter_handles.throttle_cruise, &(_parameters.throttle_cruise));
-
- return OK;
+ /* 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.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));
+ param_get(_parameter_handles.rtl_land_delay, &(_parameters.rtl_land_delay));
+
+ _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);
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+}
- if (vstatus_updated) {
+void
+Navigator::home_position_update()
+{
+ orb_copy(ORB_ID(home_position), _home_pos_sub, &_home_pos);
+}
- orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
- }
+void
+Navigator::navigation_capabilities_update()
+{
+ orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
}
+
void
-Navigator::vehicle_attitude_poll()
+Navigator::offboard_mission_update(bool isrotaryWing)
{
- /* check if there is a new position */
- bool att_updated;
- orb_check(_att_sub, &att_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;
- if (att_updated) {
- orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
+ } else {
+ dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ }
+
+ missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence);
+
+ _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);
+
+ } else {
+ _mission.set_current_offboard_mission_index(0);
+ _mission.set_offboard_mission_count(0);
}
}
void
-Navigator::mission_poll()
+Navigator::onboard_mission_update()
{
- /* check if there is a new setpoint */
- bool mission_updated;
- orb_check(_mission_sub, &mission_updated);
-
- if (mission_updated) {
+ struct mission_s onboard_mission;
- struct mission_s mission;
- orb_copy(ORB_ID(mission), _mission_sub, &mission);
+ if (orb_copy(ORB_ID(mission), _onboard_mission_sub, &onboard_mission) == OK) {
- // XXX this is not optimal yet, but a first prototype /
- // test implementation
+ _mission.set_current_onboard_mission_index(onboard_mission.current_index);
+ _mission.set_onboard_mission_count(onboard_mission.count);
- if (mission.count <= _mission_items_maxcount) {
- /*
- * Perform an atomic copy & state update
- */
- irqstate_t flags = irqsave();
+ } else {
+ _mission.set_current_onboard_mission_index(0);
+ _mission.set_onboard_mission_count(0);
+ }
+}
- memcpy(_mission_items, mission.items, mission.count * sizeof(struct mission_item_s));
- _mission_valid = true;
+void
+Navigator::vehicle_status_update()
+{
+ if (orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus) != OK) {
+ /* in case the commander is not be running */
+ _vstatus.arming_state = ARMING_STATE_STANDBY;
+ }
+}
- irqrestore(flags);
- } else {
- warnx("mission larger than storage space");
- }
+void
+Navigator::vehicle_control_mode_update()
+{
+ if (orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode) != OK) {
+ /* in case the commander is not be running */
+ _control_mode.flag_control_auto_enabled = false;
+ _control_mode.flag_armed = false;
}
}
@@ -341,46 +571,90 @@ 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));
+ _control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
_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();
+ vehicle_control_mode_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;
+ hrt_abstime mavlink_open_time = 0;
+ const hrt_abstime mavlink_open_interval = 500000;
/* wakeup source(s) */
- struct pollfd fds[2];
+ struct pollfd fds[8];
/* 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;
+ fds[7].fd = _control_mode_sub;
+ fds[7].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,147 +664,218 @@ Navigator::task_main()
perf_begin(_loop_perf);
- /* check vehicle status for changes to publication state */
- vehicle_status_poll();
-
- /* only update parameters if they changed */
- if (fds[0].revents & POLLIN) {
- /* read from param to clear updated flag */
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), _params_sub, &update);
+ 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);
+ }
- /* update parameters from storage */
- parameters_update();
+ /* vehicle control mode updated */
+ if (fds[7].revents & POLLIN) {
+ vehicle_control_mode_update();
}
- /* only run controller if position changed */
- if (fds[1].revents & POLLIN) {
+ /* vehicle status updated */
+ if (fds[6].revents & POLLIN) {
+ vehicle_status_update();
+ /* evaluate state machine from commander and set the navigator mode accordingly */
+ if (_control_mode.flag_armed && _control_mode.flag_control_auto_enabled) {
+ bool stick_mode = false;
- static uint64_t last_run = 0;
- float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
- last_run = hrt_absolute_time();
+ 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) {
+ /* switch to RTL if not already landed after RTL and home position set */
+ if (!(_rtl_state == RTL_STATE_DESCEND &&
+ (myState == NAV_STATE_READY || myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) &&
+ _vstatus.condition_home_position_valid) {
+ dispatch(EVENT_RTL_REQUESTED);
+ }
- /* guard against too large deltaT's */
- if (deltaT > 1.0f)
- deltaT = 0.01f;
+ stick_mode = true;
- /* load local copies */
- orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+ } 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;
+ }
+ }
+ }
- vehicle_attitude_poll();
+ 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;
- mission_poll();
+ switch (_vstatus.set_nav_state) {
+ case NAV_STATE_NONE:
+ /* nothing to do */
+ break;
- 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);
+ case NAV_STATE_LOITER:
+ dispatch(EVENT_LOITER_REQUESTED);
+ break;
- /* AUTONOMOUS FLIGHT */
+ case NAV_STATE_MISSION:
+ if (_mission.current_mission_available()) {
+ dispatch(EVENT_MISSION_REQUESTED);
- if (1 /* autonomous flight */) {
+ } else {
+ dispatch(EVENT_LOITER_REQUESTED);
+ }
- /* execute navigation once we have a setpoint */
- if (_mission_valid) {
+ break;
- // Next waypoint
- math::Vector2f prev_wp;
+ case NAV_STATE_RTL:
+ if (!(_rtl_state == RTL_STATE_DESCEND &&
+ (myState == NAV_STATE_READY || myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) &&
+ _vstatus.condition_home_position_valid) {
+ dispatch(EVENT_RTL_REQUESTED);
+ }
- if (_global_triplet.previous_valid) {
- prev_wp.setX(_global_triplet.previous.lat / 1e7f);
- prev_wp.setY(_global_triplet.previous.lon / 1e7f);
+ break;
- } 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);
+ case NAV_STATE_LAND:
+ if (myState != NAV_STATE_READY) {
+ dispatch(EVENT_LAND_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);
+ }
+ }
+ }
+ }
- /******** MAIN NAVIGATION STATE MACHINE ********/
+ } else {
+ /* navigator shouldn't act */
+ dispatch(EVENT_NONE_REQUESTED);
+ }
+ }
- // XXX to be put in its own class
+ /* 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 */
+ }
- if (_global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
- /* waypoint is a plain navigation waypoint */
-
+ /* navigation capabilities updated */
+ if (fds[3].revents & POLLIN) {
+ navigation_capabilities_update();
+ }
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
- _global_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
- _global_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+ /* 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);
+ }
- /* waypoint is a loiter waypoint */
-
- }
+ /* onboard mission updated */
+ if (fds[5].revents & POLLIN) {
+ onboard_mission_update();
+ // XXX check if mission really changed
+ dispatch(EVENT_MISSION_CHANGED);
+ }
- // XXX at this point we always want no loiter hold if a
- // mission is active
- _loiter_hold = false;
+ /* home position updated */
+ if (fds[2].revents & POLLIN) {
+ home_position_update();
+ // XXX check if home position really changed
+ dispatch(EVENT_HOME_POSITION_CHANGED);
+ }
- } else {
+ /* global position updated */
+ if (fds[1].revents & POLLIN) {
+ global_position_update();
- if (!_loiter_hold) {
- _loiter_hold_lat = _global_pos.lat / 1e7f;
- _loiter_hold_lon = _global_pos.lon / 1e7f;
- _loiter_hold_alt = _global_pos.alt;
- _loiter_hold = true;
- }
+ /* publish position setpoint triplet on each position update if navigator active */
+ if (_control_mode.flag_armed && _control_mode.flag_control_auto_enabled) {
+ _pos_sp_triplet_updated = true;
- //_parameters.loiter_hold_radius
+ if (myState == NAV_STATE_LAND && _global_pos.global_valid && !_global_pos_valid) {
+ /* got global position when landing, update setpoint */
+ start_land();
}
- } else if (0/* seatbelt mode enabled */) {
-
- /** SEATBELT FLIGHT **/
- continue;
-
- } else {
-
- /** MANUAL FLIGHT **/
+ _global_pos_valid = _global_pos.global_valid;
- /* no flight mode applies, do not publish an attitude setpoint */
- continue;
+ /* check if waypoint has been reached in MISSION, RTL and LAND modes */
+ if (myState == NAV_STATE_MISSION || myState == NAV_STATE_RTL || myState == NAV_STATE_LAND) {
+ if (check_mission_item_reached()) {
+ on_mission_item_reached();
+ }
+ }
}
- /******** MAIN NAVIGATION STATE MACHINE ********/
-
- if (_global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
- // XXX define launch position and return
-
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_LAND) {
- // XXX flared descent on final approach
+ /* 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)
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
-
- /* apply minimum pitch if altitude has not yet been reached */
- if (_global_pos.alt < _global_triplet.current.altitude) {
- _att_sp.pitch_body = math::max(_att_sp.pitch_body, _global_triplet.current.param1);
+ /* 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;
}
- }
-
- /* 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);
} else {
- /* advertise and publish */
- _triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &_global_triplet);
+ /* Reset the _geofence_violation_warning_sent field */
+ _geofence_violation_warning_sent = false;
}
+ }
+
+ /* publish position setpoint triplet if updated */
+ if (_pos_sp_triplet_updated) {
+ _pos_sp_triplet_updated = false;
+ publish_position_setpoint_triplet();
+ }
+
+ /* notify user about state changes */
+ if (myState != prevState) {
+ mavlink_log_info(_mavlink_fd, "[navigator] nav state: %s", nav_states_str[myState]);
+ prevState = myState;
+ /* reset time counter on state changes */
+ _time_first_inside_orbit = 0;
}
perf_end(_loop_perf);
}
- warnx("exiting.\n");
+ warnx("exiting.");
_navigator_task = -1;
_exit(0);
@@ -543,11 +888,11 @@ Navigator::start()
/* start the task */
_navigator_task = task_spawn_cmd("navigator",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 5,
- 2048,
- (main_t)&Navigator::task_main_trampoline,
- nullptr);
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&Navigator::task_main_trampoline,
+ nullptr);
if (_navigator_task < 0) {
warn("task start failed");
@@ -557,20 +902,745 @@ Navigator::start()
return OK;
}
+void
+Navigator::status()
+{
+ warnx("Global position is %svalid", _global_pos.global_valid ? "" : "in");
+
+ if (_global_pos.global_valid) {
+ warnx("Longitude %5.5f degrees, latitude %5.5f degrees", _global_pos.lon, _global_pos.lat);
+ warnx("Altitude %5.5f meters, altitude above home %5.5f meters",
+ (double)_global_pos.alt, (double)(_global_pos.alt - _home_pos.alt));
+ warnx("Ground velocity in m/s, N %5.5f, E %5.5f, D %5.5f",
+ (double)_global_pos.vel_n, (double)_global_pos.vel_e, (double)_global_pos.vel_d);
+ warnx("Compass heading in degrees %5.5f", (double)(_global_pos.yaw * M_RAD_TO_DEG_F));
+ }
+
+ if (_fence_valid) {
+ warnx("Geofence is valid");
+// 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");
+ }
+
+ 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] = {
+ {
+ /* NAV_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_LAND_REQUESTED */ {ACTION(&Navigator::start_land), NAV_STATE_LAND},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_NONE},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_NONE},
+ },
+ {
+ /* NAV_STATE_READY */
+ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), 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_LAND_REQUESTED */ {NO_ACTION, NAV_STATE_READY},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_READY},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_READY},
+ },
+ {
+ /* NAV_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_LAND_REQUESTED */ {ACTION(&Navigator::start_land), NAV_STATE_LAND},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER},
+ },
+ {
+ /* NAV_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_LAND_REQUESTED */ {ACTION(&Navigator::start_land), NAV_STATE_LAND},
+ /* EVENT_MISSION_CHANGED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_MISSION},
+ },
+ {
+ /* NAV_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_LAND_REQUESTED */ {ACTION(&Navigator::start_land_home), NAV_STATE_LAND},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_RTL},
+ /* EVENT_HOME_POSITION_CHANGED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL}, // TODO need to reset rtl_state
+ },
+ {
+ /* NAV_STATE_LAND */
+ /* 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 */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ /* EVENT_LAND_REQUESTED */ {NO_ACTION, NAV_STATE_LAND},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_LAND},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_LAND},
+ },
+};
+
+void
+Navigator::start_none()
+{
+ _pos_sp_triplet.previous.valid = false;
+ _pos_sp_triplet.current.valid = false;
+ _pos_sp_triplet.next.valid = false;
+ _mission_item_valid = false;
+
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
+ _rtl_state = RTL_STATE_NONE;
+
+ _pos_sp_triplet_updated = true;
+}
+
+void
+Navigator::start_ready()
+{
+ _pos_sp_triplet.previous.valid = false;
+ _pos_sp_triplet.current.valid = true;
+ _pos_sp_triplet.next.valid = false;
+
+ _pos_sp_triplet.current.type = SETPOINT_TYPE_IDLE;
+
+ _mission_item_valid = false;
+
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
+
+ if (_rtl_state != RTL_STATE_DESCEND) {
+ /* reset RTL state if landed not at home */
+ _rtl_state = RTL_STATE_NONE;
+ }
+
+ _pos_sp_triplet_updated = true;
+}
+
+void
+Navigator::start_loiter()
+{
+ _do_takeoff = false;
+
+ /* set loiter position if needed */
+ if (_reset_loiter_pos || !_pos_sp_triplet.current.valid) {
+ _reset_loiter_pos = false;
+
+ _pos_sp_triplet.current.lat = _global_pos.lat;
+ _pos_sp_triplet.current.lon = _global_pos.lon;
+ _pos_sp_triplet.current.yaw = NAN; // NAN means to use current yaw
+
+ float min_alt_amsl = _parameters.min_altitude + _home_pos.alt;
+
+ /* use current altitude if above min altitude set by parameter */
+ if (_global_pos.alt < min_alt_amsl) {
+ _pos_sp_triplet.current.alt = min_alt_amsl;
+ mavlink_log_info(_mavlink_fd, "[navigator] loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt));
+
+ } else {
+ _pos_sp_triplet.current.alt = _global_pos.alt;
+ mavlink_log_info(_mavlink_fd, "[navigator] loiter at current altitude");
+ }
+
+ }
+ _pos_sp_triplet.current.type = SETPOINT_TYPE_LOITER;
+ _pos_sp_triplet.current.loiter_radius = _parameters.loiter_radius;
+ _pos_sp_triplet.current.loiter_direction = 1;
+ _pos_sp_triplet.previous.valid = false;
+ _pos_sp_triplet.current.valid = true;
+ _pos_sp_triplet.next.valid = false;
+ _mission_item_valid = false;
+
+ _pos_sp_triplet_updated = true;
+}
+
+void
+Navigator::start_mission()
+{
+ _need_takeoff = true;
+
+ set_mission_item();
+}
+
+void
+Navigator::set_mission_item()
+{
+ /* copy current mission to previous item */
+ memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
+
+ _reset_loiter_pos = true;
+ _do_takeoff = false;
+
+ int ret;
+ bool onboard;
+ unsigned index;
+
+ ret = _mission.get_current_mission_item(&_mission_item, &onboard, &index);
+
+ if (ret == OK) {
+ /* reset time counter for new item */
+ _time_first_inside_orbit = 0;
+
+ _mission_item_valid = true;
+ position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
+
+ if (_mission_item.nav_cmd != NAV_CMD_RETURN_TO_LAUNCH &&
+ _mission_item.nav_cmd != NAV_CMD_LOITER_TIME_LIMIT &&
+ _mission_item.nav_cmd != NAV_CMD_LOITER_TURN_COUNT &&
+ _mission_item.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.nav_cmd == NAV_CMD_TAKEOFF ||
+ _mission_item.nav_cmd == NAV_CMD_WAYPOINT ||
+ _mission_item.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED
+ )) {
+ /* do special TAKEOFF handling for VTOL */
+ _need_takeoff = false;
+
+ /* calculate desired takeoff altitude AMSL */
+ float takeoff_alt_amsl = _pos_sp_triplet.current.alt;
+
+ 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);
+ }
+
+ /* check if we really need takeoff */
+ if (_vstatus.condition_landed || _global_pos.alt < takeoff_alt_amsl - _mission_item.acceptance_radius) {
+ /* force TAKEOFF if landed or waypoint altitude is more than current */
+ _do_takeoff = true;
+
+ /* move current position setpoint to next */
+ memcpy(&_pos_sp_triplet.next, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
+
+ /* set current setpoint to takeoff */
+
+ _pos_sp_triplet.current.lat = _global_pos.lat;
+ _pos_sp_triplet.current.lon = _global_pos.lon;
+ _pos_sp_triplet.current.alt = takeoff_alt_amsl;
+ _pos_sp_triplet.current.yaw = NAN;
+ _pos_sp_triplet.current.type = SETPOINT_TYPE_TAKEOFF;
+ }
+
+ } else if (_mission_item.nav_cmd == NAV_CMD_LAND) {
+ /* will need takeoff after landing */
+ _need_takeoff = true;
+ }
+ }
+
+ if (_do_takeoff) {
+ mavlink_log_info(_mavlink_fd, "[navigator] takeoff to %.1fm above home", _pos_sp_triplet.current.alt - _home_pos.alt);
+
+ } 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_valid = false;
+ _pos_sp_triplet.current.valid = false;
+ warnx("ERROR: current WP can't be set");
+ }
+
+ if (!_do_takeoff) {
+ mission_item_s item_next;
+ ret = _mission.get_next_mission_item(&item_next);
+
+ if (ret == OK) {
+ position_setpoint_from_mission_item(&_pos_sp_triplet.next, &item_next);
+
+ } else {
+ /* this will fail for the last WP */
+ _pos_sp_triplet.next.valid = false;
+ }
+ }
+
+ _pos_sp_triplet_updated = true;
+}
+
+void
+Navigator::start_rtl()
+{
+ _do_takeoff = false;
+
+ /* decide if we need climb */
+ if (_rtl_state == RTL_STATE_NONE) {
+ if (_global_pos.alt < _home_pos.alt + _parameters.rtl_alt) {
+ _rtl_state = RTL_STATE_CLIMB;
+
+ } else {
+ _rtl_state = RTL_STATE_RETURN;
+ }
+ }
+
+ /* if switching directly to return state, reset altitude setpoint */
+ if (_rtl_state == RTL_STATE_RETURN) {
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _global_pos.alt;
+ }
+
+ _reset_loiter_pos = true;
+ set_rtl_item();
+}
+
+void
+Navigator::start_land()
+{
+ /* this state can be requested by commander even if no global position available,
+ * in his case controller must perform landing without position control */
+ _do_takeoff = false;
+ _reset_loiter_pos = true;
+
+ memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
+
+ _mission_item_valid = true;
+
+ _mission_item.lat = _global_pos.lat;
+ _mission_item.lon = _global_pos.lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _global_pos.alt;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _parameters.loiter_radius;
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_LAND;
+ _mission_item.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
+
+ _pos_sp_triplet.next.valid = false;
+}
+
+void
+Navigator::start_land_home()
+{
+ /* land to home position, should be called when hovering above home, from RTL state */
+ _do_takeoff = false;
+ _reset_loiter_pos = true;
+
+ memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
+
+ _mission_item_valid = true;
+
+ _mission_item.lat = _home_pos.lat;
+ _mission_item.lon = _home_pos.lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _home_pos.alt;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _parameters.loiter_radius;
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_LAND;
+ _mission_item.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
+
+ _pos_sp_triplet.next.valid = false;
+}
+
+void
+Navigator::set_rtl_item()
+{
+ /*reset time counter for new RTL item */
+ _time_first_inside_orbit = 0;
+
+ switch (_rtl_state) {
+ case RTL_STATE_CLIMB: {
+ memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
+
+ float climb_alt = _home_pos.alt + _parameters.rtl_alt;
+
+ if (_vstatus.condition_landed) {
+ climb_alt = fmaxf(climb_alt, _global_pos.alt + _parameters.rtl_alt);
+ }
+
+ _mission_item_valid = true;
+
+ _mission_item.lat = _global_pos.lat;
+ _mission_item.lon = _global_pos.lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = climb_alt;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _parameters.loiter_radius;
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_TAKEOFF;
+ _mission_item.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
+
+ _pos_sp_triplet.next.valid = false;
+
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: climb to %.1fm above home", climb_alt - _home_pos.alt);
+ break;
+ }
+
+ case RTL_STATE_RETURN: {
+ memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
+
+ _mission_item_valid = true;
+
+ _mission_item.lat = _home_pos.lat;
+ _mission_item.lon = _home_pos.lon;
+ // don't change altitude
+ _mission_item.yaw = NAN; // TODO set heading to home
+ _mission_item.loiter_radius = _parameters.loiter_radius;
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_WAYPOINT;
+ _mission_item.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
+
+ _pos_sp_triplet.next.valid = false;
+
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: return at %.1fm above home", _mission_item.altitude - _home_pos.alt);
+ break;
+ }
+
+ case RTL_STATE_DESCEND: {
+ memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
+
+ _mission_item_valid = true;
+
+ _mission_item.lat = _home_pos.lat;
+ _mission_item.lon = _home_pos.lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _home_pos.alt + _parameters.land_alt;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _parameters.loiter_radius;
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_WAYPOINT;
+ _mission_item.acceptance_radius = _parameters.acceptance_radius;
+ _mission_item.time_inside = _parameters.rtl_land_delay < 0.0 ? 0.0f : _parameters.rtl_land_delay;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = _parameters.rtl_land_delay > -0.001f;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
+
+ _pos_sp_triplet.next.valid = false;
+
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL: descend to %.1fm above home", _mission_item.altitude - _home_pos.alt);
+ break;
+ }
+
+ default: {
+ mavlink_log_critical(_mavlink_fd, "[navigator] error: unknown RTL state: %d", _rtl_state);
+ start_loiter();
+ break;
+ }
+ }
+
+ _pos_sp_triplet_updated = true;
+}
+
+void
+Navigator::position_setpoint_from_mission_item(position_setpoint_s *sp, mission_item_s *item)
+{
+ sp->valid = true;
+
+ if (item->nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
+ /* set home position for RTL item */
+ sp->lat = _home_pos.lat;
+ sp->lon = _home_pos.lon;
+ sp->alt = _home_pos.alt + _parameters.rtl_alt;
+
+ } else {
+ sp->lat = item->lat;
+ sp->lon = item->lon;
+ sp->alt = item->altitude_is_relative ? item->altitude + _home_pos.alt : item->altitude;
+ }
+
+ sp->yaw = item->yaw;
+ sp->loiter_radius = item->loiter_radius;
+ sp->loiter_direction = item->loiter_direction;
+ sp->pitch_min = item->pitch_min;
+
+ if (item->nav_cmd == NAV_CMD_TAKEOFF) {
+ sp->type = SETPOINT_TYPE_TAKEOFF;
+
+ } else if (item->nav_cmd == NAV_CMD_LAND) {
+ sp->type = SETPOINT_TYPE_LAND;
+
+ } else if (item->nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ item->nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ item->nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+ sp->type = SETPOINT_TYPE_LOITER;
+
+ } else {
+ sp->type = SETPOINT_TYPE_NORMAL;
+ }
+}
+
+bool
+Navigator::check_mission_item_reached()
+{
+ /* only check if there is actually a mission item to check */
+ if (!_mission_item_valid) {
+ return false;
+ }
+
+ if (_mission_item.nav_cmd == NAV_CMD_LAND) {
+ return _vstatus.condition_landed;
+ }
+
+ /* XXX TODO count turns */
+ if ((_mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED) &&
+ _mission_item.loiter_radius > 0.01f) {
+
+ return false;
+ }
+
+ uint64_t now = hrt_absolute_time();
+
+ if (!_waypoint_position_reached) {
+ float acceptance_radius;
+
+ if (_mission_item.nav_cmd == NAV_CMD_WAYPOINT && _mission_item.acceptance_radius > 0.01f) {
+ acceptance_radius = _mission_item.acceptance_radius;
+
+ } else {
+ acceptance_radius = _parameters.acceptance_radius;
+ }
+
+ float dist = -1.0f;
+ float dist_xy = -1.0f;
+ float dist_z = -1.0f;
+
+ /* calculate AMSL altitude for this waypoint */
+ float wp_alt_amsl = _mission_item.altitude;
+
+ if (_mission_item.altitude_is_relative)
+ wp_alt_amsl += _home_pos.alt;
+
+ dist = get_distance_to_point_global_wgs84(_mission_item.lat, _mission_item.lon, wp_alt_amsl,
+ (double)_global_pos.lat, (double)_global_pos.lon, _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;
+ }
+ }
+ }
+
+ if (!_waypoint_yaw_reached) {
+ if (_vstatus.is_rotary_wing && !_do_takeoff && isfinite(_mission_item.yaw)) {
+ /* check yaw if defined only for rotary wing except takeoff */
+ float yaw_err = _wrap_pi(_mission_item.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;
+ }
+ }
+
+ /* check if the current waypoint was reached */
+ if (_waypoint_position_reached && _waypoint_yaw_reached) {
+ if (_time_first_inside_orbit == 0) {
+ _time_first_inside_orbit = now;
+
+ if (_mission_item.time_inside > 0.01f) {
+ mavlink_log_info(_mavlink_fd, "[navigator] waypoint reached, wait for %.1fs", _mission_item.time_inside);
+ }
+ }
+
+ /* check if the MAV was long enough inside the waypoint orbit */
+ if ((now - _time_first_inside_orbit >= (uint64_t)_mission_item.time_inside * 1e6)
+ || _mission_item.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();
+ }
+
+ if (_mission.current_mission_available()) {
+ set_mission_item();
+
+ } 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 if (myState == NAV_STATE_RTL) {
+ /* RTL completed */
+ if (_rtl_state == RTL_STATE_DESCEND) {
+ /* hovering above home position, land if needed or loiter */
+ mavlink_log_info(_mavlink_fd, "[navigator] RTL completed");
+
+ if (_mission_item.autocontinue) {
+ dispatch(EVENT_LAND_REQUESTED);
+
+ } else {
+ _reset_loiter_pos = false;
+ dispatch(EVENT_LOITER_REQUESTED);
+ }
+
+ } else {
+ /* next RTL step */
+ _rtl_state = (RTLState)(_rtl_state + 1);
+ set_rtl_item();
+ }
+
+ } else if (myState == NAV_STATE_LAND) {
+ /* landing completed */
+ mavlink_log_info(_mavlink_fd, "[navigator] landing completed");
+ dispatch(EVENT_READY_REQUESTED);
+ }
+}
+
+void
+Navigator::publish_position_setpoint_triplet()
+{
+ /* update navigation state */
+ _pos_sp_triplet.nav_state = static_cast<nav_state_t>(myState);
+
+ /* lazily publish the position setpoint triplet only once available */
+ if (_pos_sp_triplet_pub > 0) {
+ /* publish the position setpoint triplet */
+ orb_publish(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_pub, &_pos_sp_triplet);
+
+ } else {
+ /* advertise and publish */
+ _pos_sp_triplet_pub = orb_advertise(ORB_ID(position_setpoint_triplet), &_pos_sp_triplet);
+ }
+}
+
+void Navigator::add_fence_point(int argc, char *argv[])
+{
+ _geofence.addPoint(argc, argv);
+}
+
+void Navigator::load_fence_from_file(const char *filename)
+{
+ _geofence.loadFromFile(filename);
+}
+
+
+static void usage()
+{
+ errx(1, "usage: navigator {start|stop|status|fence|fencefile}");
+}
+
int navigator_main(int argc, char *argv[])
{
- if (argc < 1)
- errx(1, "usage: navigator {start|stop|status}");
+ if (argc < 2) {
+ usage();
+ }
if (!strcmp(argv[1], "start")) {
- if (navigator::g_navigator != nullptr)
+ if (navigator::g_navigator != nullptr) {
errx(1, "already running");
+ }
navigator::g_navigator = new Navigator;
- if (navigator::g_navigator == nullptr)
+ if (navigator::g_navigator == nullptr) {
errx(1, "alloc failed");
+ }
if (OK != navigator::g_navigator->start()) {
delete navigator::g_navigator;
@@ -578,27 +1648,28 @@ int navigator_main(int argc, char *argv[])
err(1, "start failed");
}
- exit(0);
+ return 0;
}
- if (!strcmp(argv[1], "stop")) {
- if (navigator::g_navigator == nullptr)
- errx(1, "not running");
+ if (navigator::g_navigator == nullptr)
+ errx(1, "not running");
+ if (!strcmp(argv[1], "stop")) {
delete navigator::g_navigator;
navigator::g_navigator = nullptr;
- exit(0);
- }
- if (!strcmp(argv[1], "status")) {
- if (navigator::g_navigator) {
- errx(0, "running");
+ } else if (!strcmp(argv[1], "status")) {
+ navigator::g_navigator->status();
- } else {
- errx(1, "not running");
- }
+ } else if (!strcmp(argv[1], "fence")) {
+ navigator::g_navigator->add_fence_point(argc - 2, argv + 2);
+
+ } else if (!strcmp(argv[1], "fencefile")) {
+ navigator::g_navigator->load_fence_from_file(GEOFENCE_FILENAME);
+
+ } else {
+ usage();
}
- warnx("unrecognized command");
- return 1;
+ return 0;
}