Rover: changed to auto deltat in Rover code as well

This commit is contained in:
Andrew Tridgell 2012-07-06 19:57:11 +10:00
parent ec70e87495
commit f4b71ff8c9
2 changed files with 2 additions and 8 deletions

View File

@ -733,10 +733,6 @@ static byte superslow_loopCounter;
// Counter to trigger execution of 1 Hz processes
static byte counter_one_herz;
// used to track the elapsed time for navigation PID integral terms
static unsigned long nav_loopTimer;
// Elapsed time since last call to navigation pid functions
static unsigned long dTnav;
// % MCU cycles used
static float load;
@ -922,8 +918,6 @@ Serial.println(tempaccel.z, DEC);
if(g_gps->new_data){
g_gps->new_data = false;
dTnav = millis() - nav_loopTimer;
nav_loopTimer = millis();
// calculate the plane's desired bearing
// -------------------------------------

View File

@ -38,7 +38,7 @@ static void calc_throttle()
groundspeed_error = rov_speed - (float)ground_speed;
int throttle_req = (throttle_target + g.pidTeThrottle.get_pid(groundspeed_error, dTnav)) * 10;
int throttle_req = (throttle_target + g.pidTeThrottle.get_pid(groundspeed_error)) * 10;
if(g.throttle_slewrate > 0)
{ if (throttle_req > throttle_last)
@ -71,7 +71,7 @@ static void calc_nav_roll()
// negative error = left turn
// positive error = right turn
nav_roll = g.pidNavRoll.get_pid(bearing_error, dTnav, nav_gain_scaler); //returns desired bank angle in degrees*100
nav_roll = g.pidNavRoll.get_pid(bearing_error, nav_gain_scaler); //returns desired bank angle in degrees*100
if(obstacle) { // obstacle avoidance
nav_roll += 9000; // if obstacle in front turn 90° right