diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 4365100b37..7321a77b61 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1075,7 +1075,7 @@ static void medium_loop() medium_loopCounter++; // log compass information - if (motors.armed() && g.log_bitmask & MASK_LOG_COMPASS) { + if (motors.armed() && (g.log_bitmask & MASK_LOG_COMPASS)) { Log_Write_Compass(); } @@ -1097,7 +1097,7 @@ static void medium_loop() // perform next command // -------------------- if(control_mode == AUTO) { - if(ap.home_is_set && g.command_total > 1) { + if(ap.home_is_set && (g.command_total > 1)) { update_commands(); } } diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index c5635fe84f..d799e7003a 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -50,7 +50,7 @@ static struct Location get_cmd_with_index(int i) } // Add on home altitude if we are a nav command (or other command with altitude) and stored alt is relative - //if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options & MASK_OPTIONS_RELATIVE_ALT){ + //if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && (temp.options & MASK_OPTIONS_RELATIVE_ALT)){ //temp.alt += home.alt; //} diff --git a/ArduCopter/inertia.pde b/ArduCopter/inertia.pde index ce951fbb0a..7b65532082 100644 --- a/ArduCopter/inertia.pde +++ b/ArduCopter/inertia.pde @@ -8,7 +8,7 @@ static void read_inertia() // inertial altitude estimates inertial_nav.update(G_Dt); - if( motors.armed() && g.log_bitmask & MASK_LOG_INAV ) { + if( motors.armed() && (g.log_bitmask & MASK_LOG_INAV) ) { log_counter_inav++; if( log_counter_inav >= 10 ) { log_counter_inav = 0; @@ -23,4 +23,4 @@ static void read_inertial_altitude() // with inertial nav we can update the altitude and climb rate at 50hz current_loc.alt = inertial_nav.get_altitude(); climb_rate = inertial_nav.get_velocity_z(); -} \ No newline at end of file +} diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index 1c7d560aa5..3cc4c43b3e 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -20,7 +20,7 @@ static void update_navigation() update_nav_mode(); // update log - if (g.log_bitmask & MASK_LOG_NTUN && motors.armed()) { + if ((g.log_bitmask & MASK_LOG_NTUN) && motors.armed()) { Log_Write_Nav_Tuning(); } }