forked from Archive/PX4-Autopilot
navigator: renamed the different RTL states
This commit is contained in:
parent
d9a64bb587
commit
d48a8bc073
|
@ -1300,7 +1300,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
|
|
||||||
/* if we have a global position, we can switch to RTL, if not, we can try to land */
|
/* if we have a global position, we can switch to RTL, if not, we can try to land */
|
||||||
if (status.condition_global_position_valid) {
|
if (status.condition_global_position_valid) {
|
||||||
status.failsafe_state = FAILSAFE_STATE_RTL_RC;
|
status.failsafe_state = FAILSAFE_STATE_RC_LOSS;
|
||||||
} else {
|
} else {
|
||||||
status.failsafe_state = FAILSAFE_STATE_LAND;
|
status.failsafe_state = FAILSAFE_STATE_LAND;
|
||||||
}
|
}
|
||||||
|
@ -1313,10 +1313,10 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
|
|
||||||
/* hack to detect if we finished a mission after we lost RC, so that we can trigger RTL now */
|
/* hack to detect if we finished a mission after we lost RC, so that we can trigger RTL now */
|
||||||
if (status.rc_signal_lost && status.set_nav_state == NAVIGATION_STATE_AUTO_MISSION &&
|
if (status.rc_signal_lost && status.set_nav_state == NAVIGATION_STATE_AUTO_MISSION &&
|
||||||
mission_result.mission_finished && status.failsafe_state != FAILSAFE_STATE_RTL_RC) {
|
mission_result.mission_finished && status.failsafe_state != FAILSAFE_STATE_RC_LOSS) {
|
||||||
/* if we have a global position, we can switch to RTL, if not, we can try to land */
|
/* if we have a global position, we can switch to RTL, if not, we can try to land */
|
||||||
if (status.condition_global_position_valid) {
|
if (status.condition_global_position_valid) {
|
||||||
status.failsafe_state = FAILSAFE_STATE_RTL_RC;
|
status.failsafe_state = FAILSAFE_STATE_RC_LOSS;
|
||||||
mavlink_log_info(mavlink_fd, "#audio: RTL after Mission is finished");
|
mavlink_log_info(mavlink_fd, "#audio: RTL after Mission is finished");
|
||||||
} else {
|
} else {
|
||||||
/* this probably doesn't make sense since we are in mission and have global position */
|
/* this probably doesn't make sense since we are in mission and have global position */
|
||||||
|
@ -1719,8 +1719,8 @@ set_control_mode()
|
||||||
case NAVIGATION_STATE_AUTO_MISSION:
|
case NAVIGATION_STATE_AUTO_MISSION:
|
||||||
case NAVIGATION_STATE_AUTO_LOITER:
|
case NAVIGATION_STATE_AUTO_LOITER:
|
||||||
case NAVIGATION_STATE_AUTO_RTL:
|
case NAVIGATION_STATE_AUTO_RTL:
|
||||||
case NAVIGATION_STATE_AUTO_RTL_RC:
|
case NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS:
|
||||||
case NAVIGATION_STATE_AUTO_RTL_DL:
|
case NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS:
|
||||||
control_mode.flag_control_manual_enabled = false;
|
control_mode.flag_control_manual_enabled = false;
|
||||||
control_mode.flag_control_auto_enabled = true;
|
control_mode.flag_control_auto_enabled = true;
|
||||||
control_mode.flag_control_rates_enabled = true;
|
control_mode.flag_control_rates_enabled = true;
|
||||||
|
|
|
@ -406,12 +406,12 @@ void set_nav_state(struct vehicle_status_s *status)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case FAILSAFE_STATE_RTL_RC:
|
case FAILSAFE_STATE_RC_LOSS:
|
||||||
status->set_nav_state = NAVIGATION_STATE_AUTO_RTL_RC;
|
status->set_nav_state = NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case FAILSAFE_STATE_RTL_DL:
|
case FAILSAFE_STATE_DL_LOSS:
|
||||||
status->set_nav_state = NAVIGATION_STATE_AUTO_RTL_DL;
|
status->set_nav_state = NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case FAILSAFE_STATE_LAND:
|
case FAILSAFE_STATE_LAND:
|
||||||
|
|
|
@ -161,8 +161,8 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case NAVIGATION_STATE_AUTO_RTL:
|
case NAVIGATION_STATE_AUTO_RTL:
|
||||||
case NAVIGATION_STATE_AUTO_RTL_RC:
|
case NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS:
|
||||||
case NAVIGATION_STATE_AUTO_RTL_DL:
|
case NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS:
|
||||||
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
|
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
|
||||||
| MAV_MODE_FLAG_STABILIZE_ENABLED
|
| MAV_MODE_FLAG_STABILIZE_ENABLED
|
||||||
| MAV_MODE_FLAG_GUIDED_ENABLED;
|
| MAV_MODE_FLAG_GUIDED_ENABLED;
|
||||||
|
|
|
@ -351,8 +351,8 @@ Navigator::task_main()
|
||||||
_navigation_mode = &_loiter;
|
_navigation_mode = &_loiter;
|
||||||
break;
|
break;
|
||||||
case NAVIGATION_STATE_AUTO_RTL:
|
case NAVIGATION_STATE_AUTO_RTL:
|
||||||
case NAVIGATION_STATE_AUTO_RTL_RC:
|
case NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS:
|
||||||
case NAVIGATION_STATE_AUTO_RTL_DL:
|
case NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS:
|
||||||
_navigation_mode = &_rtl;
|
_navigation_mode = &_rtl;
|
||||||
break;
|
break;
|
||||||
case NAVIGATION_STATE_LAND:
|
case NAVIGATION_STATE_LAND:
|
||||||
|
|
|
@ -1,10 +1,6 @@
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
* Copyright (C) 2012 - 2014 PX4 Development Team. All rights reserved.
|
||||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
* @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
|
|
||||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
|
||||||
* @author Julian Oes <joes@student.ethz.ch>
|
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -45,6 +41,11 @@
|
||||||
* All apps should write to subsystem_info:
|
* All apps should write to subsystem_info:
|
||||||
*
|
*
|
||||||
* (any app) --> subsystem_info (published) --> (commander app state machine) --> vehicle_status --> (mavlink app)
|
* (any app) --> subsystem_info (published) --> (commander app state machine) --> vehicle_status --> (mavlink app)
|
||||||
|
*
|
||||||
|
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||||
|
* @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
|
||||||
|
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||||
|
* @author Julian Oes <julian@oes.ch>
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef VEHICLE_STATUS_H_
|
#ifndef VEHICLE_STATUS_H_
|
||||||
|
@ -90,25 +91,25 @@ typedef enum {
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
FAILSAFE_STATE_NORMAL = 0, /**< Normal operation */
|
FAILSAFE_STATE_NORMAL = 0, /**< Normal operation */
|
||||||
FAILSAFE_STATE_RTL_RC, /**< Return To Launch on remote control loss */
|
FAILSAFE_STATE_RC_LOSS, /**< Return To Launch on remote control loss */
|
||||||
FAILSAFE_STATE_RTL_DL, /**< Return To Launch on datalink loss */
|
FAILSAFE_STATE_DL_LOSS, /**< Return To Launch on datalink loss */
|
||||||
FAILSAFE_STATE_LAND, /**< Land as safe as possible */
|
FAILSAFE_STATE_LAND, /**< Land as safe as possible */
|
||||||
FAILSAFE_STATE_TERMINATION, /**< Disable motors and use parachute, can't be recovered */
|
FAILSAFE_STATE_TERMINATION, /**< Disable motors and use parachute, can't be recovered */
|
||||||
FAILSAFE_STATE_MAX,
|
FAILSAFE_STATE_MAX,
|
||||||
} failsafe_state_t;
|
} failsafe_state_t;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
NAVIGATION_STATE_MANUAL = 0,
|
NAVIGATION_STATE_MANUAL = 0, /**< Manual mode */
|
||||||
NAVIGATION_STATE_ACRO,
|
NAVIGATION_STATE_ACRO, /**< Acro mode */
|
||||||
NAVIGATION_STATE_ALTCTL,
|
NAVIGATION_STATE_ALTCTL, /**< Altitude control mode */
|
||||||
NAVIGATION_STATE_POSCTL,
|
NAVIGATION_STATE_POSCTL, /**< Position control mode */
|
||||||
NAVIGATION_STATE_AUTO_MISSION,
|
NAVIGATION_STATE_AUTO_MISSION, /**< Auto mission mode */
|
||||||
NAVIGATION_STATE_AUTO_LOITER,
|
NAVIGATION_STATE_AUTO_LOITER, /**< Auto loiter mode */
|
||||||
NAVIGATION_STATE_AUTO_RTL,
|
NAVIGATION_STATE_AUTO_RTL, /**< Auto RTL mode */
|
||||||
NAVIGATION_STATE_AUTO_RTL_RC,
|
NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS, /**< Auto failsafe on RC loss mode */
|
||||||
NAVIGATION_STATE_AUTO_RTL_DL,
|
NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS, /**< Auto failsafe on datalink loss mode */
|
||||||
NAVIGATION_STATE_LAND,
|
NAVIGATION_STATE_LAND, /**< Land mode */
|
||||||
NAVIGATION_STATE_TERMINATION,
|
NAVIGATION_STATE_TERMINATION, /**< Termination mode */
|
||||||
} navigation_state_t;
|
} navigation_state_t;
|
||||||
|
|
||||||
enum VEHICLE_MODE_FLAG {
|
enum VEHICLE_MODE_FLAG {
|
||||||
|
|
Loading…
Reference in New Issue