Skip to content

Commit 39b2ca8

Browse files
committed
AP_AHRS: remove groundspeed method from AHRS backend
if we want backends to be able to return this number as determined by a separate calculation (wheel odometry?) we can put it in the results object. For now, just derive it from the groundspeed vector
1 parent 04cf648 commit 39b2ca8

File tree

2 files changed

+0
-27
lines changed

2 files changed

+0
-27
lines changed

libraries/AP_AHRS/AP_AHRS.cpp

Lines changed: 0 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -1420,28 +1420,6 @@ Vector2f AP_AHRS::_groundspeed_vector(void)
14201420

14211421
float AP_AHRS::_groundspeed(void)
14221422
{
1423-
switch (active_EKF_type()) {
1424-
#if AP_AHRS_DCM_ENABLED
1425-
case EKFType::DCM:
1426-
return dcm.groundspeed();
1427-
#endif
1428-
#if HAL_NAVEKF2_AVAILABLE
1429-
case EKFType::TWO:
1430-
#endif
1431-
1432-
#if HAL_NAVEKF3_AVAILABLE
1433-
case EKFType::THREE:
1434-
#endif
1435-
1436-
#if AP_AHRS_EXTERNAL_ENABLED
1437-
case EKFType::EXTERNAL:
1438-
#endif
1439-
1440-
#if AP_AHRS_SIM_ENABLED
1441-
case EKFType::SIM:
1442-
#endif
1443-
break;
1444-
}
14451423
return groundspeed_vector().length();
14461424
}
14471425

libraries/AP_AHRS/AP_AHRS_Backend.h

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -206,11 +206,6 @@ class AP_AHRS_Backend
206206
return false;
207207
}
208208

209-
// return ground speed estimate in meters/second. Used by ground vehicles.
210-
float groundspeed(void) {
211-
return groundspeed_vector().length();
212-
}
213-
214209
// return true if we will use compass for yaw
215210
virtual bool use_compass(void) = 0;
216211

0 commit comments

Comments
 (0)