mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Rover: remove duplicate setting of ground_speed
update_ahrs already does this using a slightly different method, having both likely leads to small twitches in ground speed at 10hz
This commit is contained in:
parent
e88b1572b6
commit
1e8e3609c6
@ -179,6 +179,8 @@ void Rover::ahrs_update()
|
|||||||
Vector3f velocity;
|
Vector3f velocity;
|
||||||
if (ahrs.get_velocity_NED(velocity)) {
|
if (ahrs.get_velocity_NED(velocity)) {
|
||||||
ground_speed = norm(velocity.x, velocity.y);
|
ground_speed = norm(velocity.x, velocity.y);
|
||||||
|
} else if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||||
|
ground_speed = ahrs.groundspeed();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||||
@ -391,10 +393,6 @@ void Rover::update_GPS_10Hz(void)
|
|||||||
set_system_time_from_GPS();
|
set_system_time_from_GPS();
|
||||||
|
|
||||||
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||||
|
|
||||||
// get ground speed estimate from AHRS
|
|
||||||
ground_speed = ahrs.groundspeed();
|
|
||||||
|
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
camera.update();
|
camera.update();
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user