aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-05-20 08:36:49 -0700
committerLorenz Meier <lm@inf.ethz.ch>2014-05-20 08:36:49 -0700
commit639d86eab22abe8850120fa07dfa58b0b4bec377 (patch)
treeac117f24f82817adce5d7407b9ab99bcd3038de0 /src/modules/commander
parent4fdc01630832f5c7d2d571c1494d4b65f1a510fc (diff)
parent559bfbb11cdac499cda8070c32e2b7e79b3b883e (diff)
downloadpx4-firmware-639d86eab22abe8850120fa07dfa58b0b4bec377.tar.gz
px4-firmware-639d86eab22abe8850120fa07dfa58b0b4bec377.tar.bz2
px4-firmware-639d86eab22abe8850120fa07dfa58b0b4bec377.zip
Merge pull request #979 from PX4/acro2
ACRO mode
Diffstat (limited to 'src/modules/commander')
-rw-r--r--src/modules/commander/commander.cpp25
-rw-r--r--src/modules/commander/px4_custom_mode.h1
-rw-r--r--src/modules/commander/state_machine_helper.cpp4
3 files changed, 28 insertions, 2 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 0b6f863ff..c26200048 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -453,6 +453,10 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
/* AUTO */
main_res = main_state_transition(status, MAIN_STATE_AUTO);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ACRO) {
+ /* ACRO */
+ main_res = main_state_transition(status, MAIN_STATE_ACRO);
}
} else {
@@ -652,6 +656,7 @@ int commander_thread_main(int argc, char *argv[])
main_states_str[1] = "ALTCTL";
main_states_str[2] = "POSCTL";
main_states_str[3] = "AUTO";
+ main_states_str[4] = "ACRO";
char *arming_states_str[ARMING_STATE_MAX];
arming_states_str[0] = "INIT";
@@ -1206,7 +1211,7 @@ int commander_thread_main(int argc, char *argv[])
* do it only for rotary wings */
if (status.is_rotary_wing &&
(status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) &&
- (status.main_state == MAIN_STATE_MANUAL || status.condition_landed) &&
+ (status.main_state == MAIN_STATE_MANUAL || status.main_state == MAIN_STATE_ACRO || status.condition_landed) &&
sp_man.r < -STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
@@ -1619,7 +1624,12 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
break;
case SWITCH_POS_OFF: // MANUAL
- res = main_state_transition(status, MAIN_STATE_MANUAL);
+ if (sp_man->acro_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status, MAIN_STATE_ACRO);
+
+ } else {
+ res = main_state_transition(status, MAIN_STATE_MANUAL);
+ }
// TRANSITION_DENIED is not possible here
break;
@@ -1731,6 +1741,17 @@ set_control_mode()
navigator_enabled = true;
break;
+ case MAIN_STATE_ACRO:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ break;
+
default:
break;
}
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
index a83c81850..e0f8dc95d 100644
--- a/src/modules/commander/px4_custom_mode.h
+++ b/src/modules/commander/px4_custom_mode.h
@@ -15,6 +15,7 @@ enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_ALTCTL,
PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
+ PX4_CUSTOM_MAIN_MODE_ACRO,
};
enum PX4_CUSTOM_SUB_MODE_AUTO {
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index abcf72717..f1a353d5b 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -222,6 +222,10 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
ret = TRANSITION_CHANGED;
break;
+ case MAIN_STATE_ACRO:
+ ret = TRANSITION_CHANGED;
+ break;
+
case MAIN_STATE_ALTCTL:
/* need at minimum altitude estimate */