aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-05-11 13:35:05 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-05-11 13:35:05 +0200
commit88b18bbad1be31cf31ff964c6cf6f3123948488d (patch)
tree90e402ea54cc6c7d6d0cd35435fcef8f75a1904d /src/modules
parent808badb34d3b88ad40aac60f817960c51cb499c5 (diff)
downloadpx4-firmware-88b18bbad1be31cf31ff964c6cf6f3123948488d.tar.gz
px4-firmware-88b18bbad1be31cf31ff964c6cf6f3123948488d.tar.bz2
px4-firmware-88b18bbad1be31cf31ff964c6cf6f3123948488d.zip
ALTCTRL/POSCTRL renamed to ALTCTL/POSCTL
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.cpp46
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp12
-rw-r--r--src/modules/commander/px4_custom_mode.h4
-rw-r--r--src/modules/commander/state_machine_helper.cpp4
-rw-r--r--src/modules/fixedwing_backside/fixedwing.cpp4
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp8
-rw-r--r--src/modules/segway/BlockSegwayController.cpp4
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h4
-rw-r--r--src/modules/uORB/topics/vehicle_status.h4
9 files changed, 45 insertions, 45 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index e5124a31f..8c7f6270d 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -435,13 +435,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_ALTCTRL) {
- /* ALTCTRL */
- main_res = main_state_transition(status, MAIN_STATE_ALTCTRL);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) {
+ /* ALTCTL */
+ main_res = main_state_transition(status, MAIN_STATE_ALTCTL);
- } 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_POSCTL) {
+ /* POSCTL */
+ main_res = main_state_transition(status, MAIN_STATE_POSCTL);
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
/* AUTO */
@@ -456,8 +456,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) {
- /* POSCTRL */
- main_res = main_state_transition(status, MAIN_STATE_POSCTRL);
+ /* POSCTL */
+ main_res = main_state_transition(status, MAIN_STATE_POSCTL);
} else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
/* MANUAL */
@@ -634,8 +634,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] = "ALTCTRL";
- main_states_str[2] = "POSCTRL";
+ main_states_str[1] = "ALTCTL";
+ main_states_str[2] = "POSCTL";
main_states_str[3] = "AUTO";
char *arming_states_str[ARMING_STATE_MAX];
@@ -1335,8 +1335,8 @@ int commander_thread_main(int argc, char *argv[])
}
// TODO remove this hack
- /* flight termination in manual mode if assist 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) {
+ /* flight termination in manual mode if assist switch is on POSCTL position */
+ if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.posctl_switch == SWITCH_POS_ON) {
if (TRANSITION_CHANGED == failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION)) {
tune_positive(armed.armed);
}
@@ -1593,25 +1593,25 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
break;
case SWITCH_POS_MIDDLE: // ASSIST
- if (sp_man->posctrl_switch == SWITCH_POS_ON) {
- res = main_state_transition(status, MAIN_STATE_POSCTRL);
+ if (sp_man->posctl_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status, MAIN_STATE_POSCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
}
- // else fallback to ALTCTRL
- print_reject_mode(status, "POSCTRL");
+ // else fallback to ALTCTL
+ print_reject_mode(status, "POSCTL");
}
- res = main_state_transition(status, MAIN_STATE_ALTCTRL);
+ res = main_state_transition(status, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this mode
}
- if (sp_man->posctrl_switch != SWITCH_POS_ON) {
- print_reject_mode(status, "ALTCTRL");
+ if (sp_man->posctl_switch != SWITCH_POS_ON) {
+ print_reject_mode(status, "ALTCTL");
}
// else fallback to MANUAL
@@ -1626,9 +1626,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 ALTCTRL (POSCTRL likely will not work too)
+ // else fallback to ALTCTL (POSCTL likely will not work too)
print_reject_mode(status, "AUTO");
- res = main_state_transition(status, MAIN_STATE_ALTCTRL);
+ res = main_state_transition(status, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
@@ -1674,7 +1674,7 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;
- case MAIN_STATE_ALTCTRL:
+ case MAIN_STATE_ALTCTL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
control_mode.flag_control_rates_enabled = true;
@@ -1685,7 +1685,7 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;
- case MAIN_STATE_POSCTRL:
+ case MAIN_STATE_POSCTL:
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 18586053b..ee0d08391 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -320,15 +320,15 @@ bool StateMachineHelperTest::mainStateTransitionTest(void)
// MANUAL to ALTCTRL.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = true;
- new_main_state = MAIN_STATE_ALTCTRL;
+ new_main_state = MAIN_STATE_ALTCTL;
ut_assert("tranisition: manual to altctrl",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("new state: altctrl", MAIN_STATE_ALTCTRL == current_state.main_state);
+ ut_assert("new state: altctrl", MAIN_STATE_ALTCTL == current_state.main_state);
// 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_ALTCTRL;
+ new_main_state = MAIN_STATE_ALTCTL;
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);
@@ -336,15 +336,15 @@ bool StateMachineHelperTest::mainStateTransitionTest(void)
// MANUAL to POSCTRL.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = true;
- new_main_state = MAIN_STATE_POSCTRL;
+ new_main_state = MAIN_STATE_POSCTL;
ut_assert("transition: manual to posctrl",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: posctrl", MAIN_STATE_POSCTRL == current_state.main_state);
+ ut_assert("current state: posctrl", MAIN_STATE_POSCTL == current_state.main_state);
// 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_POSCTRL;
+ new_main_state = MAIN_STATE_POSCTL;
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 e6274fb89..a83c81850 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_ALTCTRL,
- PX4_CUSTOM_MAIN_MODE_POSCTRL,
+ PX4_CUSTOM_MAIN_MODE_ALTCTL,
+ PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
};
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 3b6d95135..97a214c33 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_ALTCTRL:
+ case MAIN_STATE_ALTCTL:
/* 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_POSCTRL:
+ case MAIN_STATE_POSCTL:
/* need at minimum local position estimate */
if (status->condition_local_position_valid ||
diff --git a/src/modules/fixedwing_backside/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp
index 596e286a4..bbb39f20f 100644
--- a/src/modules/fixedwing_backside/fixedwing.cpp
+++ b/src/modules/fixedwing_backside/fixedwing.cpp
@@ -229,8 +229,8 @@ void BlockMultiModeBacksideAutopilot::update()
_actuators.control[CH_RDR] = _manual.yaw;
_actuators.control[CH_THR] = _manual.throttle;
- } else if (_status.main_state == MAIN_STATE_ALTCTRL ||
- _status.main_state == MAIN_STATE_POSCTRL /* TODO, implement pos control */) {
+ } else if (_status.main_state == MAIN_STATE_ALTCTL ||
+ _status.main_state == MAIN_STATE_POSCTL /* TODO, implement pos control */) {
// calculate velocity, XXX should be airspeed, but using ground speed for now
// for the purpose of control we will limit the velocity feedback between
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 9a7e636c3..b8879157e 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -124,13 +124,13 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (status->is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
- } else if (status->main_state == MAIN_STATE_ALTCTRL) {
+ } else if (status->main_state == MAIN_STATE_ALTCTL) {
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTRL;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL;
- } else if (status->main_state == MAIN_STATE_POSCTRL) {
+ } else if (status->main_state == MAIN_STATE_POSCTL) {
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTRL;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
} else if (status->main_state == MAIN_STATE_AUTO) {
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp
index 6d46db9bd..91230a37c 100644
--- a/src/modules/segway/BlockSegwayController.cpp
+++ b/src/modules/segway/BlockSegwayController.cpp
@@ -35,8 +35,8 @@ void BlockSegwayController::update() {
// handle autopilot modes
if (_status.main_state == MAIN_STATE_AUTO ||
- _status.main_state == MAIN_STATE_ALTCTRL ||
- _status.main_state == MAIN_STATE_POSCTRL) {
+ _status.main_state == MAIN_STATE_ALTCTL ||
+ _status.main_state == MAIN_STATE_POSCTL) {
_actuators.control[0] = spdCmd;
_actuators.control[1] = spdCmd;
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index 727be9492..ac394786d 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -77,8 +77,8 @@ struct manual_control_setpoint_s {
float aux5; /**< default function: payload drop */
switch_pos_t mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
- switch_pos_t return_switch; /**< rturn to launch 2 position switch (mandatory): no effect, return */
- switch_pos_t posctrl_switch; /**< posctrl 2 position switch (optional): altctrl, posctrl */
+ switch_pos_t return_switch; /**< rturn to launch 2 position switch (mandatory): normal, return */
+ switch_pos_t posctl_switch; /**< posctrl 2 position switch (optional): altctl, posctl */
switch_pos_t loiter_switch; /**< mission 2 position switch (optional): mission, loiter */
}; /**< manual control inputs */
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index f401140ae..f56355246 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -63,8 +63,8 @@
/* main state machine */
typedef enum {
MAIN_STATE_MANUAL = 0,
- MAIN_STATE_ALTCTRL,
- MAIN_STATE_POSCTRL,
+ MAIN_STATE_ALTCTL,
+ MAIN_STATE_POSCTL,
MAIN_STATE_AUTO,
MAIN_STATE_MAX
} main_state_t;