Copter: use BIT_IF_SET()

this should fix the problem with simple mode on PX4

Pair-Programmed-With: Randy Mackay <rmackay9@yahoo.com>
This commit is contained in:
Andrew Tridgell 2013-04-23 23:05:42 +10:00
parent 3659b532be
commit fb0f5d46ba
2 changed files with 6 additions and 6 deletions

View File

@ -20,7 +20,7 @@ static void read_control_switch()
if(g.ch7_option != CH7_SIMPLE_MODE) { if(g.ch7_option != CH7_SIMPLE_MODE) {
// set Simple mode using stored paramters from Mission planner // set Simple mode using stored paramters from Mission planner
// rather than by the control switch // rather than by the control switch
set_simple_mode(g.simple_modes & (1 << switchPosition)); set_simple_mode(BIT_IS_SET(g.simple_modes, switchPosition));
} }
} }
} }

View File

@ -334,7 +334,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
mode = constrain_int16(mode, 0, NUM_MODES-1); mode = constrain_int16(mode, 0, NUM_MODES-1);
// update the user // 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 // Remember switch position
_oldSwitchPosition = _switchPosition; _oldSwitchPosition = _switchPosition;
@ -350,7 +350,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
flight_modes[_switchPosition] = mode; flight_modes[_switchPosition] = mode;
// print new 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); delay(500);
} }
@ -358,7 +358,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
if (g.rc_4.control_in > 3000) { if (g.rc_4.control_in > 3000) {
g.simple_modes |= (1<<_switchPosition); g.simple_modes |= (1<<_switchPosition);
// print new 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); delay(500);
} }
@ -366,7 +366,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
if (g.rc_4.control_in < -3000) { if (g.rc_4.control_in < -3000) {
g.simple_modes &= ~(1<<_switchPosition); g.simple_modes &= ~(1<<_switchPosition);
// print new 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); delay(500);
} }
@ -1163,7 +1163,7 @@ static void report_flight_modes()
print_divider(); print_divider();
for(int16_t i = 0; i < 6; i++ ) { for(int16_t i = 0; i < 6; i++ ) {
print_switch(i, flight_modes[i], (g.simple_modes & (1<<i))); print_switch(i, flight_modes[i], BIT_IS_SET(g.simple_modes, i));
} }
print_blanks(2); print_blanks(2);
} }