aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander
diff options
context:
space:
mode:
authorTickTock- <TjckTock@gmail.com>2014-04-28 21:47:45 -0700
committerTickTock- <TjckTock@gmail.com>2014-04-28 21:47:45 -0700
commit31089a290ba089b2b5cbcc76ed677e3f401ffa36 (patch)
treedfa7cc73cfa9b4d1b52f801aa05f66429c0ffa41 /src/modules/commander
parent269800b48c31d78fec900b4beaf3f655a8c18730 (diff)
downloadpx4-firmware-31089a290ba089b2b5cbcc76ed677e3f401ffa36.tar.gz
px4-firmware-31089a290ba089b2b5cbcc76ed677e3f401ffa36.tar.bz2
px4-firmware-31089a290ba089b2b5cbcc76ed677e3f401ffa36.zip
Replaces poshold/althold with posctrl/altctrl
Diffstat (limited to 'src/modules/commander')
-rw-r--r--src/modules/commander/commander.cpp46
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp24
-rw-r--r--src/modules/commander/px4_custom_mode.h4
-rw-r--r--src/modules/commander/state_machine_helper.cpp4
4 files changed, 39 insertions, 39 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index a99456370..be3e6d269 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -434,13 +434,13 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
/* MANUAL */
main_res = main_state_transition(status, MAIN_STATE_MANUAL);
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTHOLD) {
- /* ALTHOLD */
- main_res = main_state_transition(status, MAIN_STATE_ALTHOLD);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTRL) {
+ /* ALTCTRL */
+ main_res = main_state_transition(status, MAIN_STATE_ALTCTRL);
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSHOLD) {
- /* POSHOLD */
- main_res = main_state_transition(status, MAIN_STATE_POSHOLD);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSCTRL) {
+ /* POSCTRL */
+ main_res = main_state_transition(status, MAIN_STATE_POSCTRL);
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
/* AUTO */
@@ -455,8 +455,8 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
} else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
- /* POSHOLD */
- main_res = main_state_transition(status, MAIN_STATE_POSHOLD);
+ /* POSCTRL */
+ main_res = main_state_transition(status, MAIN_STATE_POSCTRL);
} else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
/* MANUAL */
@@ -628,8 +628,8 @@ int commander_thread_main(int argc, char *argv[])
char *main_states_str[MAIN_STATE_MAX];
main_states_str[0] = "MANUAL";
- main_states_str[1] = "ALTHOLD";
- main_states_str[2] = "POSHOLD";
+ main_states_str[1] = "ALTCTRL";
+ main_states_str[2] = "POSCTRL";
main_states_str[3] = "AUTO";
char *arming_states_str[ARMING_STATE_MAX];
@@ -1299,8 +1299,8 @@ int commander_thread_main(int argc, char *argv[])
}
// TODO remove this hack
- /* flight termination in manual mode if assisted switch is on poshold position */
- if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.poshold_switch == SWITCH_POS_ON) {
+ /* flight termination in manual mode if assisted switch is on posctrl position */
+ if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.posctrl_switch == SWITCH_POS_ON) {
if (TRANSITION_CHANGED == failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION)) {
tune_positive(armed.armed);
}
@@ -1557,25 +1557,25 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
break;
case SWITCH_POS_MIDDLE: // ASSISTED
- if (sp_man->poshold_switch == SWITCH_POS_ON) {
- res = main_state_transition(status, MAIN_STATE_POSHOLD);
+ if (sp_man->posctrl_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status, MAIN_STATE_POSCTRL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
}
- // else fallback to ALTHOLD
- print_reject_mode(status, "POSHOLD");
+ // else fallback to ALTCTRL
+ print_reject_mode(status, "POSCTRL");
}
- res = main_state_transition(status, MAIN_STATE_ALTHOLD);
+ res = main_state_transition(status, MAIN_STATE_ALTCTRL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this mode
}
- if (sp_man->poshold_switch != SWITCH_POS_ON) {
- print_reject_mode(status, "ALTHOLD");
+ if (sp_man->posctrl_switch != SWITCH_POS_ON) {
+ print_reject_mode(status, "ALTCTRL");
}
// else fallback to MANUAL
@@ -1590,9 +1590,9 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
break; // changed successfully or already in this state
}
- // else fallback to ALTHOLD (POSHOLD likely will not work too)
+ // else fallback to ALTCTRL (POSCTRL likely will not work too)
print_reject_mode(status, "AUTO");
- res = main_state_transition(status, MAIN_STATE_ALTHOLD);
+ res = main_state_transition(status, MAIN_STATE_ALTCTRL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
@@ -1638,7 +1638,7 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;
- case MAIN_STATE_ALTHOLD:
+ case MAIN_STATE_ALTCTRL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
control_mode.flag_control_rates_enabled = true;
@@ -1649,7 +1649,7 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;
- case MAIN_STATE_POSHOLD:
+ case MAIN_STATE_POSCTRL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
control_mode.flag_control_rates_enabled = true;
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
index b440e561b..18586053b 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -317,34 +317,34 @@ bool StateMachineHelperTest::mainStateTransitionTest(void)
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
ut_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state);
- // MANUAL to ALTHOLD.
+ // MANUAL to ALTCTRL.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = true;
- new_main_state = MAIN_STATE_ALTHOLD;
- ut_assert("tranisition: manual to althold",
+ new_main_state = MAIN_STATE_ALTCTRL;
+ ut_assert("tranisition: manual to altctrl",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("new state: althold", MAIN_STATE_ALTHOLD == current_state.main_state);
+ ut_assert("new state: altctrl", MAIN_STATE_ALTCTRL == current_state.main_state);
- // MANUAL to ALTHOLD, invalid local altitude.
+ // MANUAL to ALTCTRL, invalid local altitude.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = false;
- new_main_state = MAIN_STATE_ALTHOLD;
+ new_main_state = MAIN_STATE_ALTCTRL;
ut_assert("no transition: invalid local altitude",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
- // MANUAL to POSHOLD.
+ // MANUAL to POSCTRL.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = true;
- new_main_state = MAIN_STATE_POSHOLD;
- ut_assert("transition: manual to poshold",
+ new_main_state = MAIN_STATE_POSCTRL;
+ ut_assert("transition: manual to posctrl",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: poshold", MAIN_STATE_POSHOLD == current_state.main_state);
+ ut_assert("current state: posctrl", MAIN_STATE_POSCTRL == current_state.main_state);
- // MANUAL to POSHOLD, invalid local position.
+ // MANUAL to POSCTRL, invalid local position.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = false;
- new_main_state = MAIN_STATE_POSHOLD;
+ new_main_state = MAIN_STATE_POSCTRL;
ut_assert("no transition: invalid position",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
index 962d2804c..e6274fb89 100644
--- a/src/modules/commander/px4_custom_mode.h
+++ b/src/modules/commander/px4_custom_mode.h
@@ -12,8 +12,8 @@
enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
- PX4_CUSTOM_MAIN_MODE_ALTHOLD,
- PX4_CUSTOM_MAIN_MODE_POSHOLD,
+ PX4_CUSTOM_MAIN_MODE_ALTCTRL,
+ PX4_CUSTOM_MAIN_MODE_POSCTRL,
PX4_CUSTOM_MAIN_MODE_AUTO,
};
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 21e36a87d..3b6d95135 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -215,7 +215,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
ret = TRANSITION_CHANGED;
break;
- case MAIN_STATE_ALTHOLD:
+ case MAIN_STATE_ALTCTRL:
/* need at minimum altitude estimate */
if (!status->is_rotary_wing ||
@@ -226,7 +226,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
break;
- case MAIN_STATE_POSHOLD:
+ case MAIN_STATE_POSCTRL:
/* need at minimum local position estimate */
if (status->condition_local_position_valid ||