mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 07:53:57 -04:00
Copter: cleanup some bit if tests to be clearer
Pair-Programmed-With: Randy Mackay <rmackay9@yahoo.com>
This commit is contained in:
parent
709a277c7f
commit
5ad9deecfb
@ -1075,7 +1075,7 @@ static void medium_loop()
|
|||||||
medium_loopCounter++;
|
medium_loopCounter++;
|
||||||
|
|
||||||
// log compass information
|
// log compass information
|
||||||
if (motors.armed() && g.log_bitmask & MASK_LOG_COMPASS) {
|
if (motors.armed() && (g.log_bitmask & MASK_LOG_COMPASS)) {
|
||||||
Log_Write_Compass();
|
Log_Write_Compass();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1097,7 +1097,7 @@ static void medium_loop()
|
|||||||
// perform next command
|
// perform next command
|
||||||
// --------------------
|
// --------------------
|
||||||
if(control_mode == AUTO) {
|
if(control_mode == AUTO) {
|
||||||
if(ap.home_is_set && g.command_total > 1) {
|
if(ap.home_is_set && (g.command_total > 1)) {
|
||||||
update_commands();
|
update_commands();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -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
|
// 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;
|
//temp.alt += home.alt;
|
||||||
//}
|
//}
|
||||||
|
|
||||||
|
@ -8,7 +8,7 @@ static void read_inertia()
|
|||||||
// inertial altitude estimates
|
// inertial altitude estimates
|
||||||
inertial_nav.update(G_Dt);
|
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++;
|
log_counter_inav++;
|
||||||
if( log_counter_inav >= 10 ) {
|
if( log_counter_inav >= 10 ) {
|
||||||
log_counter_inav = 0;
|
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
|
// with inertial nav we can update the altitude and climb rate at 50hz
|
||||||
current_loc.alt = inertial_nav.get_altitude();
|
current_loc.alt = inertial_nav.get_altitude();
|
||||||
climb_rate = inertial_nav.get_velocity_z();
|
climb_rate = inertial_nav.get_velocity_z();
|
||||||
}
|
}
|
||||||
|
@ -20,7 +20,7 @@ static void update_navigation()
|
|||||||
update_nav_mode();
|
update_nav_mode();
|
||||||
|
|
||||||
// update log
|
// update log
|
||||||
if (g.log_bitmask & MASK_LOG_NTUN && motors.armed()) {
|
if ((g.log_bitmask & MASK_LOG_NTUN) && motors.armed()) {
|
||||||
Log_Write_Nav_Tuning();
|
Log_Write_Nav_Tuning();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user