aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/commander.c
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-07-16 13:24:02 +0200
committerJulian Oes <julian@oes.ch>2013-07-16 13:24:02 +0200
commit76edfa896b57782d7a4333bcf7a582952cb0fae4 (patch)
treec5bfe1d8c0825a7638db66c81c5c3cbc4cbf7309 /src/modules/commander/commander.c
parent6dc3fcd1ad108bc830231c1da50982e18eb7f799 (diff)
downloadpx4-firmware-76edfa896b57782d7a4333bcf7a582952cb0fae4.tar.gz
px4-firmware-76edfa896b57782d7a4333bcf7a582952cb0fae4.tar.bz2
px4-firmware-76edfa896b57782d7a4333bcf7a582952cb0fae4.zip
Fixed disarming bug, use flag instead of mode switch
Diffstat (limited to 'src/modules/commander/commander.c')
-rw-r--r--src/modules/commander/commander.c8
1 files changed, 3 insertions, 5 deletions
diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c
index b457d98a1..144fda79a 100644
--- a/src/modules/commander/commander.c
+++ b/src/modules/commander/commander.c
@@ -1387,8 +1387,7 @@ int commander_thread_main(int argc, char *argv[])
* Check if left stick is in lower left position --> switch to standby state.
* Do this only for multirotors, not for fixed wing aircraft.
*/
- // printf("checking\n");
- if ((sp_man.yaw < -STICK_ON_OFF_LIMIT) && (sp_man.throttle < STICK_THRUST_RANGE * 0.2f)) {
+ if ((sp_man.yaw < -STICK_ON_OFF_LIMIT) && (sp_man.throttle < STICK_THRUST_RANGE * 0.1f)) {
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
@@ -1396,7 +1395,7 @@ int commander_thread_main(int argc, char *argv[])
(current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
(current_status.system_type == VEHICLE_TYPE_OCTOROTOR)
) {
- if (current_status.mode_switch != MODE_SWITCH_MANUAL) {
+ if (control_mode.flag_control_position_enabled || control_mode.flag_control_velocity_enabled) {
mavlink_log_critical(mavlink_fd, "DISARM DENY, go manual mode first");
tune_negative();
} else {
@@ -1417,8 +1416,7 @@ int commander_thread_main(int argc, char *argv[])
}
/* check if left stick is in lower right position and we're in manual --> arm */
- if (!control_mode.flag_control_position_enabled && !control_mode.flag_control_velocity_enabled &&
- sp_man.yaw > STICK_ON_OFF_LIMIT &&
+ if (sp_man.yaw > STICK_ON_OFF_LIMIT &&
sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
arming_state_transition(status_pub, &current_status, ARMING_STATE_ARMED, armed_pub, &armed, mavlink_fd);