From fb0f5d46bac5cfd20f589dadae083d0716307ab7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 23 Apr 2013 23:05:42 +1000 Subject: [PATCH] Copter: use BIT_IF_SET() this should fix the problem with simple mode on PX4 Pair-Programmed-With: Randy Mackay --- ArduCopter/control_modes.pde | 2 +- ArduCopter/setup.pde | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 22715340f9..d31603a34a 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -20,7 +20,7 @@ static void read_control_switch() if(g.ch7_option != CH7_SIMPLE_MODE) { // set Simple mode using stored paramters from Mission planner // rather than by the control switch - set_simple_mode(g.simple_modes & (1 << switchPosition)); + set_simple_mode(BIT_IS_SET(g.simple_modes, switchPosition)); } } } diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index e2030156ad..d8b369ad05 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -334,7 +334,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv) mode = constrain_int16(mode, 0, NUM_MODES-1); // update the user - print_switch(_switchPosition, mode, (g.simple_modes & (1<<_switchPosition))); + print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition)); // Remember switch position _oldSwitchPosition = _switchPosition; @@ -350,7 +350,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv) flight_modes[_switchPosition] = mode; // print new mode - print_switch(_switchPosition, mode, (g.simple_modes & (1<<_switchPosition))); + print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition)); delay(500); } @@ -358,7 +358,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv) if (g.rc_4.control_in > 3000) { g.simple_modes |= (1<<_switchPosition); // print new mode - print_switch(_switchPosition, mode, (g.simple_modes & (1<<_switchPosition))); + print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition)); delay(500); } @@ -366,7 +366,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv) if (g.rc_4.control_in < -3000) { g.simple_modes &= ~(1<<_switchPosition); // print new mode - print_switch(_switchPosition, mode, (g.simple_modes & (1<<_switchPosition))); + print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition)); delay(500); } @@ -1163,7 +1163,7 @@ static void report_flight_modes() print_divider(); for(int16_t i = 0; i < 6; i++ ) { - print_switch(i, flight_modes[i], (g.simple_modes & (1<