mirror of https://github.com/ArduPilot/ardupilot
Rover: cleanup some old code
This commit is contained in:
parent
3aeb836bc0
commit
0873f8d00d
|
@ -442,10 +442,6 @@ static float current_amps1;
|
||||||
// Totalized current (Amp-hours) from battery 1
|
// Totalized current (Amp-hours) from battery 1
|
||||||
static float current_total1;
|
static float current_total1;
|
||||||
|
|
||||||
// To Do - Add support for second battery pack
|
|
||||||
//static float battery_voltage2 = LOW_VOLTAGE * 1.05; // Battery 2 Voltage, initialized above threshold for filter
|
|
||||||
//static float current_amps2; // Current (Amperes) draw from battery 2
|
|
||||||
//static float current_total2; // Totalized current (Amp-hours) from battery 2
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Navigation control variables
|
// Navigation control variables
|
||||||
|
@ -662,7 +658,10 @@ static void fast_loop()
|
||||||
} else {
|
} else {
|
||||||
obstacle = false;
|
obstacle = false;
|
||||||
}
|
}
|
||||||
}
|
} else {
|
||||||
|
// this makes it possible to disable sonar at runtime
|
||||||
|
obstacle = false;
|
||||||
|
}
|
||||||
|
|
||||||
// uses the yaw from the DCM to give more accurate turns
|
// uses the yaw from the DCM to give more accurate turns
|
||||||
calc_bearing_error();
|
calc_bearing_error();
|
||||||
|
@ -675,13 +674,6 @@ static void fast_loop()
|
||||||
Log_Write_IMU();
|
Log_Write_IMU();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// inertial navigation
|
|
||||||
// ------------------
|
|
||||||
#if INERTIAL_NAVIGATION == ENABLED
|
|
||||||
// TODO: implement inertial nav function
|
|
||||||
inertialNavigation();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// custom code/exceptions for flight modes
|
// custom code/exceptions for flight modes
|
||||||
// ---------------------------------------
|
// ---------------------------------------
|
||||||
update_current_mode();
|
update_current_mode();
|
||||||
|
@ -695,9 +687,6 @@ static void fast_loop()
|
||||||
// ------------------------------
|
// ------------------------------
|
||||||
set_servos();
|
set_servos();
|
||||||
|
|
||||||
|
|
||||||
// XXX is it appropriate to be doing the comms below on the fast loop?
|
|
||||||
|
|
||||||
gcs_update();
|
gcs_update();
|
||||||
gcs_data_stream_send();
|
gcs_data_stream_send();
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue