mirror of https://github.com/ArduPilot/ardupilot
Rover: use EKF velocity for high rate ground_speed updates
this may give smoother throttle response when the EKF is enabled
This commit is contained in:
parent
85ebe81ed3
commit
48919b6253
|
@ -623,6 +623,12 @@ static void ahrs_update()
|
||||||
|
|
||||||
ahrs.update();
|
ahrs.update();
|
||||||
|
|
||||||
|
// if using the EKF get a speed update now (from accelerometers)
|
||||||
|
Vector3f velocity;
|
||||||
|
if (ahrs.get_velocity_NED(velocity)) {
|
||||||
|
ground_speed = pythagorous2(velocity.x, velocity.y);
|
||||||
|
}
|
||||||
|
|
||||||
if (should_log(MASK_LOG_ATTITUDE_FAST))
|
if (should_log(MASK_LOG_ATTITUDE_FAST))
|
||||||
Log_Write_Attitude();
|
Log_Write_Attitude();
|
||||||
|
|
||||||
|
@ -824,7 +830,12 @@ static void update_GPS_10Hz(void)
|
||||||
ground_start_count = 0;
|
ground_start_count = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
ground_speed = gps.ground_speed();
|
Vector3f velocity;
|
||||||
|
if (ahrs.get_velocity_NED(velocity)) {
|
||||||
|
ground_speed = pythagorous2(velocity.x, velocity.y);
|
||||||
|
} else {
|
||||||
|
ground_speed = gps.ground_speed();
|
||||||
|
}
|
||||||
|
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
if (camera.update_location(current_loc) == true) {
|
if (camera.update_location(current_loc) == true) {
|
||||||
|
|
Loading…
Reference in New Issue