aboutsummaryrefslogtreecommitdiff
path: root/src/modules/navigator/navigator_main.cpp
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-04-21 17:36:59 +0200
committerJulian Oes <julian@oes.ch>2014-04-21 17:36:59 +0200
commitc3c0328e8bb9211580dbe5a52ecb23e0452cb402 (patch)
tree0c449cb2733f3c6cbfc5593e38929fea34152c11 /src/modules/navigator/navigator_main.cpp
parent488785250f4f1fa3c2f6d1e3283fd8eabb6b3144 (diff)
downloadpx4-firmware-c3c0328e8bb9211580dbe5a52ecb23e0452cb402.tar.gz
px4-firmware-c3c0328e8bb9211580dbe5a52ecb23e0452cb402.tar.bz2
px4-firmware-c3c0328e8bb9211580dbe5a52ecb23e0452cb402.zip
navigator: lot's of cleanup (WIP)
Diffstat (limited to 'src/modules/navigator/navigator_main.cpp')
-rw-r--r--src/modules/navigator/navigator_main.cpp934
1 files changed, 307 insertions, 627 deletions
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index 494266dd3..34a28aec3 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -1,10 +1,6 @@
/****************************************************************************
*
- * 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>
+ * 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
@@ -35,19 +31,20 @@
*
****************************************************************************/
/**
- * @file navigator_main.c
+ * @file navigator_main.cpp
* Implementation of the main navigation state machine.
*
- * Handles missions, geo fencing and failsafe navigation behavior.
- * Published the mission item triplet for the position controller.
+ * Handles mission items, geo fencing and failsafe navigation behavior.
+ * Published the position setpoint 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 Julian Oes <julian@oes.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <nuttx/config.h>
+
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -58,9 +55,13 @@
#include <poll.h>
#include <time.h>
#include <sys/ioctl.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+
#include <drivers/device/device.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
+
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/home_position.h>
@@ -71,20 +72,19 @@
#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 <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 <mathlib/mathlib.h>
#include <mavlink/mavlink_log.h>
-#include <sys/types.h>
-#include <sys/stat.h>
-#include "navigator_state.h"
-#include "navigator_mission.h"
+#include "mission.h"
+#include "rtl.h"
#include "mission_feasibility_checker.h"
#include "geofence.h"
@@ -130,12 +130,12 @@ public:
/**
* Add point to geofence
*/
- void add_fence_point(int argc, char *argv[]);
+ void add_fence_point(int argc, char *argv[]);
/**
* Load fence from file
*/
- void load_fence_from_file(const char *filename);
+ void load_fence_from_file(const char *filename);
private:
@@ -154,15 +154,15 @@ private:
int _control_mode_sub; /**< vehicle control mode subscription */
orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */
- orb_advert_t _mission_result_pub; /**< publish mission result topic */
- 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 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 */
+ vehicle_status_s _vstatus; /**< vehicle status */
+ vehicle_control_mode_s _control_mode; /**< vehicle control mode */
+ vehicle_global_position_s _global_pos; /**< global vehicle position */
+ home_position_s _home_pos; /**< home position for RTL */
+ position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */
+ mission_item_s _mission_item; /**< current mission item */
+
+ bool _mission_item_valid;
perf_counter_t _loop_perf; /**< loop performance counter */
@@ -174,56 +174,41 @@ private:
struct navigation_capabilities_s _nav_caps;
- class Mission _mission;
+ Mission _mission;
+
+ RTL _rtl;
- bool _mission_item_valid; /**< current mission item valid */
- 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;
- uint64_t _set_nav_state_timestamp; /**< timestamp of last handled navigation state request */
-
- bool _pos_sp_triplet_updated;
-
- const char *nav_states_str[NAV_STATE_MAX];
+ bool _update_triplet;
struct {
- 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 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_TAKEN_OFF,
+ EVENT_LANDED,
EVENT_MISSION_CHANGED,
EVENT_HOME_POSITION_CHANGED,
+ EVENT_MISSION_ITEM_REACHED,
MAX_EVENT
};
@@ -232,15 +217,6 @@ private:
*/
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.
*/
@@ -264,7 +240,7 @@ private:
/**
* Retrieve offboard mission.
*/
- void offboard_mission_update(bool isrotaryWing);
+ void offboard_mission_update();
/**
* Retrieve onboard mission.
@@ -296,19 +272,20 @@ private:
/**
* 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();
+ bool start_none_on_ground();
+ bool start_none_in_air();
+ bool start_auto_on_ground();
+ bool start_loiter();
+ bool start_mission();
+ bool advance_mission();
+ bool start_rtl();
+ bool advance_rtl();
+ bool start_land();
/**
* Fork for state transitions
*/
- void request_loiter_or_ready();
- void request_mission_if_available();
+ // void request_loiter_or_ready();
/**
* Guards offboard mission
@@ -333,12 +310,12 @@ private:
/**
* Perform actions when current mission item reached.
*/
- void on_mission_item_reached();
+ // void on_mission_item_reached();
/**
* Move to next waypoint
*/
- void set_mission_item();
+ bool set_mission_items();
/**
* Switch to next RTL state
@@ -348,7 +325,7 @@ private:
/**
* Set position setpoint for mission item
*/
- void position_setpoint_from_mission_item(position_setpoint_s *sp, mission_item_s *item);
+ void mission_item_to_position_setpoint(const mission_item_s *item, position_setpoint_s *sp);
/**
* Helper function to get a takeoff item
@@ -377,12 +354,9 @@ 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),
_home_pos_sub(-1),
_vstatus_sub(-1),
@@ -391,53 +365,29 @@ Navigator::Navigator() :
_onboard_mission_sub(-1),
_capabilities_sub(-1),
_control_mode_sub(-1),
-
-/* publications */
_pos_sp_triplet_pub(-1),
-
-/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
-
_geofence_violation_warning_sent(false),
_fence_valid(false),
_inside_fence(true),
_mission(),
+ _pos_sp_triplet({}),
+ _mission_item({}),
_mission_item_valid(false),
- _global_pos_valid(false),
- _reset_loiter_pos(true),
_waypoint_position_reached(false),
_waypoint_yaw_reached(false),
_time_first_inside_orbit(0),
- _need_takeoff(true),
- _do_takeoff(false),
- _set_nav_state_timestamp(0),
- _pos_sp_triplet_updated(false),
-/* states */
- _rtl_state(RTL_STATE_NONE)
+ _update_triplet(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_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();
+ myState = NAV_STATE_NONE_ON_GROUND;
+
+ start_none_on_ground();
}
Navigator::~Navigator()
@@ -472,16 +422,12 @@ Navigator::parameters_update()
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));
+ param_get(_parameter_handles.takeoff_alt, &(_parameters.takeoff_alt));
- _mission.set_onboard_mission_allowed((bool)_parameter_handles.onboard_mission_enabled);
+ _mission.set_onboard_mission_allowed((bool)_parameters.onboard_mission_enabled);
_geofence.updateParams();
}
@@ -496,6 +442,8 @@ void
Navigator::home_position_update()
{
orb_copy(ORB_ID(home_position), _home_pos_sub, &_home_pos);
+
+ _rtl.set_home_position(&_home_pos);
}
void
@@ -506,7 +454,7 @@ Navigator::navigation_capabilities_update()
void
-Navigator::offboard_mission_update(bool isrotaryWing)
+Navigator::offboard_mission_update()
{
struct mission_s offboard_mission;
@@ -523,19 +471,17 @@ Navigator::offboard_mission_update(bool isrotaryWing)
dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
}
- missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence);
+ missionFeasiblityChecker.checkMissionFeasible(_vstatus.is_rotary_wing, dm_current, (size_t)offboard_mission.count, _geofence);
_mission.set_offboard_dataman_id(offboard_mission.dataman_id);
_mission.set_offboard_mission_count(offboard_mission.count);
- _mission.set_current_offboard_mission_index(offboard_mission.current_index);
+ _mission.command_current_offboard_mission_index(offboard_mission.current_index);
} else {
_mission.set_offboard_mission_count(0);
- _mission.set_current_offboard_mission_index(0);
+ _mission.command_current_offboard_mission_index(0);
}
-
- _mission.publish_mission_result();
}
void
@@ -546,11 +492,11 @@ Navigator::onboard_mission_update()
if (orb_copy(ORB_ID(onboard_mission), _onboard_mission_sub, &onboard_mission) == OK) {
_mission.set_onboard_mission_count(onboard_mission.count);
- _mission.set_current_onboard_mission_index(onboard_mission.current_index);
+ _mission.command_current_onboard_mission_index(onboard_mission.current_index);
} else {
_mission.set_onboard_mission_count(0);
- _mission.set_current_onboard_mission_index(0);
+ _mission.command_current_onboard_mission_index(0);
}
}
@@ -626,13 +572,13 @@ Navigator::task_main()
global_position_update();
home_position_update();
navigation_capabilities_update();
- offboard_mission_update(_vstatus.is_rotary_wing);
+ offboard_mission_update();
onboard_mission_update();
/* rate limit position updates to 50 Hz */
orb_set_interval(_global_pos_sub, 20);
- unsigned prevState = NAV_STATE_NONE;
+ unsigned prevState = NAV_STATE_NONE_ON_GROUND;
hrt_abstime mavlink_open_time = 0;
const hrt_abstime mavlink_open_interval = 500000;
@@ -690,55 +636,45 @@ Navigator::task_main()
if (fds[6].revents & POLLIN) {
vehicle_status_update();
- /* evaluate state requested by commander */
- if (_control_mode.flag_armed && _control_mode.flag_control_auto_enabled) {
- if (_vstatus.set_nav_state_timestamp != _set_nav_state_timestamp) {
- /* commander requested new navigation mode, try to set it */
- switch (_vstatus.set_nav_state) {
- case NAV_STATE_NONE:
- /* nothing to do */
- break;
-
- case NAV_STATE_LOITER:
- request_loiter_or_ready();
- break;
-
- case NAV_STATE_MISSION:
- request_mission_if_available();
- break;
-
- case NAV_STATE_RTL:
- if (!(_rtl_state == RTL_STATE_DESCEND &&
- (myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) &&
- _vstatus.condition_home_position_valid) {
- dispatch(EVENT_RTL_REQUESTED);
- }
-
- break;
-
- case NAV_STATE_LAND:
- 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) {
- request_mission_if_available();
- }
- }
-
- } else {
- /* navigator shouldn't act */
+ /* commander requested new navigation mode, forward it to state machine */
+ switch (_vstatus.set_nav_state) {
+ case NAVIGATION_STATE_NONE:
dispatch(EVENT_NONE_REQUESTED);
+ break;
+
+ case NAVIGATION_STATE_LOITER:
+ dispatch(EVENT_LOITER_REQUESTED);
+ break;
+
+ case NAVIGATION_STATE_MISSION:
+ dispatch(EVENT_MISSION_REQUESTED);
+ break;
+
+ case NAVIGATION_STATE_RTL:
+ /* TODO: what is this for? */
+ // if (!(_rtl_state == RTL_STATE_DESCEND &&
+ // (myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) &&
+ // _vstatus.condition_home_position_valid) {
+ dispatch(EVENT_RTL_REQUESTED);
+ // }
+ break;
+
+ case NAVIGATION_STATE_LAND:
+ /* TODO: add this */
+ // dispatch(EVENT_LAND_REQUESTED);
+ break;
+
+ default:
+ warnx("ERROR: Requested navigation state not supported");
+ break;
}
- _set_nav_state_timestamp = _vstatus.set_nav_state_timestamp;
+ /* commander sets in-air/on-ground flag as well */
+ if (_vstatus.condition_landed) {
+ dispatch(EVENT_LANDED);
+ } else {
+ dispatch(EVENT_TAKEN_OFF);
+ }
}
/* parameters updated */
@@ -754,74 +690,49 @@ Navigator::task_main()
/* offboard mission updated */
if (fds[4].revents & POLLIN) {
- offboard_mission_update(_vstatus.is_rotary_wing);
- // XXX check if mission really changed
+ offboard_mission_update();
+ /* TODO: 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
+ /* TODO: 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
+ /* TODO check if home position really changed */
dispatch(EVENT_HOME_POSITION_CHANGED);
}
/* global position updated */
if (fds[1].revents & POLLIN) {
global_position_update();
-
- /* 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;
-
- if (myState == NAV_STATE_LAND && _global_pos.global_valid && !_global_pos_valid) {
- /* got global position when landing, update setpoint */
- start_land();
- }
-
- _global_pos_valid = _global_pos.global_valid;
-
- /* 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();
- }
- }
+ if (check_mission_item_reached()) {
+ dispatch(EVENT_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)
/* 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;
}
}
- /* publish position setpoint triplet if updated */
- if (_pos_sp_triplet_updated) {
- _pos_sp_triplet_updated = false;
+ if (_update_triplet ) {
publish_position_setpoint_triplet();
- }
-
- /* notify user about state changes */
- if (myState != prevState) {
- mavlink_log_info(_mavlink_fd, "#audio: navigation state: %s", nav_states_str[myState]);
- prevState = myState;
+ _update_triplet = false;
}
perf_end(_loop_perf);
@@ -879,8 +790,12 @@ Navigator::status()
}
switch (myState) {
- case NAV_STATE_NONE:
- warnx("State: None");
+ case NAV_STATE_NONE_ON_GROUND:
+ warnx("State: None on ground");
+ break;
+
+ case NAV_STATE_NONE_IN_AIR:
+ warnx("State: None in air");
break;
case NAV_STATE_LOITER:
@@ -895,6 +810,10 @@ Navigator::status()
warnx("State: RTL");
break;
+ case NAV_STATE_LAND:
+ warnx("State: LAND");
+ break;
+
default:
warnx("State: Unknown");
break;
@@ -903,92 +822,119 @@ Navigator::status()
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},
+ /* NAV_STATE_NONE_ON_GROUND */
+ /* EVENT_NONE_REQUESTED */ {NO_ACTION, NAV_STATE_NONE_ON_GROUND},
+ /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_NONE_ON_GROUND},
+ /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_auto_on_ground), NAV_STATE_AUTO_ON_GROUND},
+ /* EVENT_RTL_REQUESTED */ {NO_ACTION, NAV_STATE_NONE_ON_GROUND},
+ /* EVENT_TAKEN_OFF */ {ACTION(&Navigator::start_none_in_air), NAV_STATE_NONE_IN_AIR},
+ /* EVENT_LANDED */ {NO_ACTION, NAV_STATE_NONE_ON_GROUND},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_NONE_ON_GROUND},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_NONE_ON_GROUND},
+ /* EVENT_MISSION_ITEM_REACHED */ {NO_ACTION, NAV_STATE_NONE_ON_GROUND},
+ },
+ {
+ /* NAV_STATE_NONE_IN_AIR */
+ /* EVENT_NONE_REQUESTED */ {NO_ACTION, NAV_STATE_NONE_IN_AIR},
/* 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},
+ /* EVENT_TAKEN_OFF */ {NO_ACTION, NAV_STATE_NONE_IN_AIR},
+ /* EVENT_LANDED */ {ACTION(&Navigator::start_none_on_ground), NAV_STATE_NONE_ON_GROUND},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_NONE_IN_AIR},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_NONE_IN_AIR},
+ /* EVENT_MISSION_ITEM_REACHED */ {NO_ACTION, NAV_STATE_NONE_IN_AIR},
},
{
- /* 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 */ {NO_ACTION, NAV_STATE_READY},
- /* 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_AUTO_ON_GROUND */
+ /* EVENT_NONE_REQUESTED */ {NO_ACTION, NAV_STATE_AUTO_ON_GROUND},
+ /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_AUTO_ON_GROUND},
+ /* EVENT_MISSION_REQUESTED */ {NO_ACTION, NAV_STATE_AUTO_ON_GROUND},
+ /* EVENT_RTL_REQUESTED */ {NO_ACTION, NAV_STATE_AUTO_ON_GROUND},
+ /* EVENT_TAKEN_OFF */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
+ /* EVENT_LANDED */ {NO_ACTION, NAV_STATE_AUTO_ON_GROUND},
+ /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_AUTO_ON_GROUND},
+ /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_AUTO_ON_GROUND},
+ /* EVENT_MISSION_ITEM_REACHED */ {NO_ACTION, NAV_STATE_AUTO_ON_GROUND},
},
{
/* NAV_STATE_LOITER */
- /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
- /* EVENT_READY_REQUESTED */ {NO_ACTION, NAV_STATE_LOITER},
+ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none_in_air), NAV_STATE_NONE_IN_AIR},
/* 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_TAKEN_OFF */ {NO_ACTION, NAV_STATE_LOITER},
+ /* EVENT_LANDED */ {NO_ACTION, NAV_STATE_LOITER},
/* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER},
/* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER},
+ /* EVENT_MISSION_ITEM_REACHED */ {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_NONE_REQUESTED */ {ACTION(&Navigator::start_none_in_air), NAV_STATE_NONE_IN_AIR},
/* 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_TAKEN_OFF */ {NO_ACTION, NAV_STATE_MISSION},
+ /* EVENT_LANDED */ {NO_ACTION, NAV_STATE_MISSION},
/* EVENT_MISSION_CHANGED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
/* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_MISSION},
+ /* EVENT_MISSION_ITEM_REACHED */ {ACTION(&Navigator::advance_mission), 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_NONE_REQUESTED */ {ACTION(&Navigator::start_none_in_air), NAV_STATE_NONE_IN_AIR},
/* 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_TAKEN_OFF */ {NO_ACTION, NAV_STATE_RTL},
+ /* EVENT_LANDED */ {NO_ACTION, NAV_STATE_RTL},
/* 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
+ /* EVENT_HOME_POSITION_CHANGED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
+ /* EVENT_MISSION_ITEM_REACHED */ {ACTION(&Navigator::advance_rtl), NAV_STATE_RTL},
},
{
/* NAV_STATE_LAND */
- /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
- /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
+ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none_in_air), NAV_STATE_NONE_IN_AIR},
/* 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_TAKEN_OFF */ {NO_ACTION, NAV_STATE_LAND},
+ /* EVENT_LANDED */ {ACTION(&Navigator::start_auto_on_ground), NAV_STATE_AUTO_ON_GROUND},
/* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_LAND},
/* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_LAND},
+ /* EVENT_MISSION_ITEM_REACHED */ {NO_ACTION, NAV_STATE_LAND},
},
};
-void
-Navigator::start_none()
+bool
+Navigator::start_none_on_ground()
{
reset_reached();
_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;
+ _update_triplet = true;
+ return true;
+}
+
+bool
+Navigator::start_none_in_air()
+{
+ reset_reached();
+
+ _pos_sp_triplet.previous.valid = false;
+ _pos_sp_triplet.current.valid = false;
+ _pos_sp_triplet.next.valid = false;
- _pos_sp_triplet_updated = true;
+ _update_triplet = true;
+ return true;
}
-void
-Navigator::start_ready()
+bool
+Navigator::start_auto_on_ground()
{
reset_reached();
@@ -998,46 +944,26 @@ Navigator::start_ready()
_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;
- }
+ // if (_rtl_state != RTL_STATE_DESCEND) {
+ // reset RTL state if landed not at home
+ // _rtl_state = RTL_STATE_NONE;
+ // }
- _pos_sp_triplet_updated = true;
+ _update_triplet = true;
+ return true;
}
-void
+bool
Navigator::start_loiter()
{
- reset_reached();
-
- _do_takeoff = false;
-
- /* set loiter position if needed */
- if (_reset_loiter_pos || !_pos_sp_triplet.current.valid) {
- _reset_loiter_pos = false;
+ /* if no existing item available, use current position */
+ if (!(_pos_sp_triplet.current.valid && _waypoint_position_reached)) {
_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 && !_vstatus.is_rotary_wing) {
- _pos_sp_triplet.current.alt = min_alt_amsl;
- mavlink_log_info(_mavlink_fd, "#audio: loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt));
-
- } else {
- _pos_sp_triplet.current.alt = _global_pos.alt;
- mavlink_log_info(_mavlink_fd, "#audio: loiter at current altitude");
- }
-
+ _pos_sp_triplet.current.alt = _global_pos.alt;
}
_pos_sp_triplet.current.type = SETPOINT_TYPE_LOITER;
_pos_sp_triplet.current.loiter_radius = _parameters.loiter_radius;
@@ -1045,167 +971,146 @@ Navigator::start_loiter()
_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;
+ mavlink_log_info(_mavlink_fd, "#audio: loiter at current altitude");
+
+ _update_triplet = true;
+ return true;
}
-void
+bool
Navigator::start_mission()
{
- _need_takeoff = true;
+ /* start fresh */
+ _pos_sp_triplet.previous.valid = false;
+ _pos_sp_triplet.current.valid = false;
+ _pos_sp_triplet.next.valid = false;
- set_mission_item();
+ return set_mission_items();
}
-void
-Navigator::set_mission_item()
+bool
+Navigator::advance_mission()
{
- reset_reached();
+ /* tell mission to move by one */
+ _mission.move_to_next();
- /* copy current mission to previous item */
- memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
+ /* now try to set the new mission items, if it fails, it will dispatch loiter */
+ return set_mission_items();
+}
- _reset_loiter_pos = true;
- _do_takeoff = false;
+bool
+Navigator::set_mission_items()
+{
+ if (_pos_sp_triplet.current.valid) {
+ memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
+ _pos_sp_triplet.previous.valid = true;
+ }
- int ret;
bool onboard;
- unsigned index;
+ int index;
- ret = _mission.get_current_mission_item(&_mission_item, &onboard, &index);
+ /* if we fail to set the current mission, continue to loiter */
+ if (!_mission.get_current_mission_item(&_mission_item, &onboard, &index)) {
- if (ret == OK) {
- _mission.report_current_offboard_mission_item();
+ dispatch(EVENT_LOITER_REQUESTED);
+ return false;
+ }
- _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 we got an RTL mission item, switch to RTL mode and give up */
+ if (_mission_item.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
+ dispatch(EVENT_RTL_REQUESTED);
+ return false;
+ }
- 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);
- }
+ _mission_item_valid = true;
- /* 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;
+ /* convert the current mission item and set it valid */
+ mission_item_to_position_setpoint(&_mission_item, &_pos_sp_triplet.current);
+ _pos_sp_triplet.current.valid = true;
+
- /* move current position setpoint to next */
- memcpy(&_pos_sp_triplet.next, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
+ mission_item_s next_mission_item;
- /* set current setpoint to takeoff */
+ bool last_wp = false;
+ /* now try to set the next mission item as well, if there is no more next
+ * this means we're heading to the last waypoint */
+ if (_mission.get_next_mission_item(&next_mission_item)) {
+ /* convert the next mission item and set it valid */
+ mission_item_to_position_setpoint(&next_mission_item, &_pos_sp_triplet.next);
+ _pos_sp_triplet.next.valid = true;
+ } else {
+ last_wp = true;
+ }
- _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;
- }
+ /* notify user about what happened */
+ mavlink_log_info(_mavlink_fd, "#audio: heading to %s%swaypoint %d",
+ (last_wp ? "last " : "" ), (onboard ? "onboard " : ""), index);
- } else if (_mission_item.nav_cmd == NAV_CMD_LAND) {
- /* will need takeoff after landing */
- _need_takeoff = true;
- }
- }
+ _update_triplet = true;
- if (_do_takeoff) {
- mavlink_log_info(_mavlink_fd, "#audio: takeoff to %.1fm above home", (double)(_pos_sp_triplet.current.alt - _home_pos.alt));
+ reset_reached();
- } else {
- if (onboard) {
- mavlink_log_info(_mavlink_fd, "#audio: heading to onboard WP %d", index);
+ return true;
+}
- } else {
- mavlink_log_info(_mavlink_fd, "#audio: heading to offboard WP %d", index);
- }
- }
+bool
+Navigator::start_rtl()
+{
+ /* TODO check if RTL was successfull, if not we have a problem and need to dispatch something */
+ if (_rtl.get_current_rtl_item(&_global_pos, &_mission_item)) {
- } 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");
- }
+ _mission_item_valid = true;
- if (!_do_takeoff) {
- mission_item_s item_next;
- ret = _mission.get_next_mission_item(&item_next);
+ mission_item_to_position_setpoint(&_mission_item, &_pos_sp_triplet.current);
+ _pos_sp_triplet.current.valid = true;
- if (ret == OK) {
- position_setpoint_from_mission_item(&_pos_sp_triplet.next, &item_next);
+ reset_reached();
- } else {
- /* this will fail for the last WP */
- _pos_sp_triplet.next.valid = false;
- }
+ _update_triplet = true;
+ return true;
}
+ dispatch(EVENT_LOITER_REQUESTED);
- _pos_sp_triplet_updated = true;
+ return false;
}
-void
-Navigator::start_rtl()
+bool
+Navigator::advance_rtl()
{
- _do_takeoff = false;
+ /* tell mission to move by one */
+ _rtl.move_to_next();
- /* 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;
+ /* now try to set the new mission items, if it fails, it will dispatch loiter */
+ if (_rtl.get_current_rtl_item(&_global_pos, &_mission_item)) {
- } else {
- _rtl_state = RTL_STATE_RETURN;
- }
- }
+ _mission_item_valid = true;
- /* 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;
+ mission_item_to_position_setpoint(&_mission_item, &_pos_sp_triplet.current);
+ _pos_sp_triplet.current.valid = true;
+
+ reset_reached();
+
+ _update_triplet = true;
+ return true;
}
- _reset_loiter_pos = true;
- set_rtl_item();
+ dispatch(EVENT_LOITER_REQUESTED);
+ return false;
}
-void
+bool
Navigator::start_land()
{
+ /* TODO: verify/test */
+
reset_reached();
/* 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;
@@ -1220,185 +1125,22 @@ Navigator::start_land()
_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()
-{
- reset_reached();
-
- /* 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);
+ mission_item_to_position_setpoint(&_mission_item, &_pos_sp_triplet.current);
_pos_sp_triplet.next.valid = false;
-}
-
-void
-Navigator::set_rtl_item()
-{
- reset_reached();
-
- 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, "#audio: RTL: climb to %.1fm above home", (double)(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
- if (_pos_sp_triplet.previous.valid) {
- /* if previous setpoint is valid then use it to calculate heading to home */
- _mission_item.yaw = get_bearing_to_next_waypoint(_pos_sp_triplet.previous.lat, _pos_sp_triplet.previous.lon, _mission_item.lat, _mission_item.lon);
-
- } else {
- /* else use current position */
- _mission_item.yaw = get_bearing_to_next_waypoint(_global_pos.lat, _global_pos.lon, _mission_item.lat, _mission_item.lon);
- }
- _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, "#audio: RTL: return at %.1fm above home", (double)(_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.0f ? 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, "#audio: RTL: descend to %.1fm above home", (double)(_mission_item.altitude - _home_pos.alt));
- break;
- }
-
- default: {
- mavlink_log_critical(_mavlink_fd, "#audio: [navigator] error: unknown RTL state: %d", _rtl_state);
- start_loiter();
- break;
- }
- }
-
- _pos_sp_triplet_updated = true;
-}
-
-void
-Navigator::request_loiter_or_ready()
-{
- /* XXX workaround: no landing detector for fixedwing yet */
- if (_vstatus.condition_landed && _vstatus.is_rotary_wing) {
- dispatch(EVENT_READY_REQUESTED);
-
- } else {
- dispatch(EVENT_LOITER_REQUESTED);
- }
-}
-
-void
-Navigator::request_mission_if_available()
-{
- if (_mission.current_mission_available()) {
- dispatch(EVENT_MISSION_REQUESTED);
- } else {
- request_loiter_or_ready();
- }
+ _update_triplet = true;
+ return true;
}
void
-Navigator::position_setpoint_from_mission_item(position_setpoint_s *sp, mission_item_s *item)
+Navigator::mission_item_to_position_setpoint(const mission_item_s *item, position_setpoint_s *sp)
{
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;
if (_pos_sp_triplet.previous.valid) {
/* if previous setpoint is valid then use it to calculate heading to home */
@@ -1408,9 +1150,6 @@ Navigator::position_setpoint_from_mission_item(position_setpoint_s *sp, mission_
/* else use current position */
sp->yaw = get_bearing_to_next_waypoint(_global_pos.lat, _global_pos.lon, sp->lat, sp->lon);
}
- sp->loiter_radius = _parameters.loiter_radius;
- sp->loiter_direction = 1;
- sp->pitch_min = 0.0f;
} else {
sp->lat = item->lat;
@@ -1450,14 +1189,14 @@ Navigator::check_mission_item_reached()
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) {
+ /* 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;
- }
+ // return false;
+ // }
uint64_t now = hrt_absolute_time();
@@ -1475,22 +1214,19 @@ Navigator::check_mission_item_reached()
float dist_xy = -1.0f;
float dist_z = -1.0f;
- /* calculate AMSL altitude for this waypoint */
- float wp_alt_amsl = _mission_item.altitude;
+ float altitude_amsl = _mission_item.altitude_is_relative
+ ? _mission_item.altitude + _home_pos.alt : _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 = get_distance_to_point_global_wgs84(_mission_item.lat, _mission_item.lon, altitude_amsl,
+ _global_pos.lat, _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 */
+ if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF) {
+
+ /* require only altitude for takeoff */
+ if (_global_pos.alt > altitude_amsl - acceptance_radius) {
_waypoint_position_reached = true;
}
-
} else {
if (dist >= 0.0f && dist <= acceptance_radius) {
_waypoint_position_reached = true;
@@ -1499,7 +1235,10 @@ Navigator::check_mission_item_reached()
}
if (_waypoint_position_reached && !_waypoint_yaw_reached) {
- if (_vstatus.is_rotary_wing && !_do_takeoff && isfinite(_mission_item.yaw)) {
+
+ /* TODO: removed takeoff, why? */
+ if (_vstatus.is_rotary_wing && 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);
@@ -1514,24 +1253,23 @@ Navigator::check_mission_item_reached()
/* 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, "#audio: waypoint reached, wait for %.1fs", (double)_mission_item.time_inside);
+ mavlink_log_info(_mavlink_fd, "#audio: waypoint reached, wait for %.1fs",
+ (double)_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) {
- reset_reached();
return true;
}
}
-
return false;
-
}
void
@@ -1544,62 +1282,6 @@ Navigator::reset_reached()
}
void
-Navigator::on_mission_item_reached()
-{
- if (myState == NAV_STATE_MISSION) {
-
- _mission.report_mission_item_reached();
-
- if (_do_takeoff) {
- /* takeoff completed */
- _do_takeoff = false;
- mavlink_log_info(_mavlink_fd, "#audio: 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");
- request_loiter_or_ready();
- }
-
- } 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);
- }
- _mission.publish_mission_result();
-}
-
-void
Navigator::publish_position_setpoint_triplet()
{
/* update navigation state */
@@ -1607,11 +1289,9 @@ Navigator::publish_position_setpoint_triplet()
/* 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);
}
}