aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/state_machine_helper.cpp
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-06-19 10:26:56 +0200
committerJulian Oes <julian@oes.ch>2014-06-19 10:26:56 +0200
commit62faa2ee5155253779d3b93c5a280e8918585f6e (patch)
tree1e9dfd8678df95098333ded38484fb509ecddeb4 /src/modules/commander/state_machine_helper.cpp
parent94e004955df3f467b7e67b3fac0d968b9a68e091 (diff)
downloadpx4-firmware-62faa2ee5155253779d3b93c5a280e8918585f6e.tar.gz
px4-firmware-62faa2ee5155253779d3b93c5a280e8918585f6e.tar.bz2
px4-firmware-62faa2ee5155253779d3b93c5a280e8918585f6e.zip
commander/navigator: renamed FS modes to RTL and RTGS (return to ground station)
Diffstat (limited to 'src/modules/commander/state_machine_helper.cpp')
-rw-r--r--src/modules/commander/state_machine_helper.cpp12
1 files changed, 6 insertions, 6 deletions
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index f0fe13921..74885abf6 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -384,7 +384,7 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
status->failsafe = true;
if (status->condition_global_position_valid && status->condition_home_position_valid) {
- status->nav_state = NAVIGATION_STATE_AUTO_FS_RC_LOSS;
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
} else if (status->condition_local_position_valid) {
status->nav_state = NAVIGATION_STATE_LAND;
} else if (status->condition_local_altitude_valid) {
@@ -427,7 +427,7 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
status->failsafe = true;
if (status->condition_global_position_valid && status->condition_home_position_valid) {
- status->nav_state = NAVIGATION_STATE_AUTO_FS_RC_LOSS;
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
} else if (status->condition_local_position_valid) {
status->nav_state = NAVIGATION_STATE_LAND;
} else if (status->condition_local_altitude_valid) {
@@ -441,7 +441,7 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
status->failsafe = true;
if (status->condition_global_position_valid && status->condition_home_position_valid) {
- status->nav_state = NAVIGATION_STATE_AUTO_FS_DL_LOSS;
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
} else if (status->condition_local_position_valid) {
status->nav_state = NAVIGATION_STATE_LAND;
} else if (status->condition_local_altitude_valid) {
@@ -467,7 +467,7 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
status->failsafe = true;
if (status->condition_global_position_valid && status->condition_home_position_valid) {
- status->nav_state = NAVIGATION_STATE_AUTO_FS_RC_LOSS;
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
} else if (status->condition_local_position_valid) {
status->nav_state = NAVIGATION_STATE_LAND;
} else if (status->condition_local_altitude_valid) {
@@ -481,7 +481,7 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
status->failsafe = true;
if (status->condition_global_position_valid && status->condition_home_position_valid) {
- status->nav_state = NAVIGATION_STATE_AUTO_FS_DL_LOSS;
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
} else if (status->condition_local_position_valid) {
status->nav_state = NAVIGATION_STATE_LAND;
} else if (status->condition_local_altitude_valid) {
@@ -495,7 +495,7 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
status->failsafe = true;
if (status->condition_global_position_valid && status->condition_home_position_valid) {
- status->nav_state = NAVIGATION_STATE_AUTO_FS_DL_LOSS;
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
} else if (status->condition_local_position_valid) {
status->nav_state = NAVIGATION_STATE_LAND;
} else if (status->condition_local_altitude_valid) {