Skip to content

Commit 9e83d63

Browse files
Fix correct usage of angular velocity in update_odometry() function (#1118) (#1153)
(cherry picked from commit d2e926b) Co-authored-by: Ferry Schoenmakers <MCFurry@users.noreply.github.com>
1 parent 11e8ad7 commit 9e83d63

File tree

2 files changed

+38
-2
lines changed

2 files changed

+38
-2
lines changed

Diff for: steering_controllers_library/src/steering_odometry.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ bool SteeringOdometry::update_odometry(
5252
const double linear_velocity, const double angular, const double dt)
5353
{
5454
/// Integrate odometry:
55-
SteeringOdometry::integrate_exact(linear_velocity * dt, angular);
55+
SteeringOdometry::integrate_exact(linear_velocity * dt, angular * dt);
5656

5757
/// We cannot estimate the speed with very small time intervals:
5858
if (dt < 0.0001)
@@ -62,7 +62,7 @@ bool SteeringOdometry::update_odometry(
6262

6363
/// Estimate speeds using a rolling mean to filter them out:
6464
linear_acc_.accumulate(linear_velocity);
65-
angular_acc_.accumulate(angular / dt);
65+
angular_acc_.accumulate(angular);
6666

6767
linear_ = linear_acc_.getRollingMean();
6868
angular_ = angular_acc_.getRollingMean();

Diff for: steering_controllers_library/test/test_steering_odometry.cpp

+36
Original file line numberDiff line numberDiff line change
@@ -108,3 +108,39 @@ TEST(TestSteeringOdometry, ackermann_back_kin_right)
108108
EXPECT_GT(std::abs(cmd1[0]), std::abs(cmd1[1])); // abs right (inner) > abs left (outer)
109109
EXPECT_LT(cmd1[0], 0);
110110
}
111+
112+
TEST(TestSteeringOdometry, bicycle_odometry)
113+
{
114+
steering_odometry::SteeringOdometry odom(1);
115+
odom.set_wheel_params(1., 1., 1.);
116+
odom.set_odometry_type(steering_odometry::BICYCLE_CONFIG);
117+
ASSERT_TRUE(odom.update_from_velocity(1., .1, .1));
118+
EXPECT_NEAR(odom.get_linear(), 1.0, 1e-3);
119+
EXPECT_NEAR(odom.get_angular(), .1, 1e-3);
120+
EXPECT_NEAR(odom.get_x(), .1, 1e-3);
121+
EXPECT_NEAR(odom.get_heading(), .01, 1e-3);
122+
}
123+
124+
TEST(TestSteeringOdometry, tricycle_odometry)
125+
{
126+
steering_odometry::SteeringOdometry odom(1);
127+
odom.set_wheel_params(1., 1., 1.);
128+
odom.set_odometry_type(steering_odometry::TRICYCLE_CONFIG);
129+
ASSERT_TRUE(odom.update_from_velocity(1., 1., .1, .1));
130+
EXPECT_NEAR(odom.get_linear(), 1.0, 1e-3);
131+
EXPECT_NEAR(odom.get_angular(), .1, 1e-3);
132+
EXPECT_NEAR(odom.get_x(), .1, 1e-3);
133+
EXPECT_NEAR(odom.get_heading(), .01, 1e-3);
134+
}
135+
136+
TEST(TestSteeringOdometry, ackermann_odometry)
137+
{
138+
steering_odometry::SteeringOdometry odom(1);
139+
odom.set_wheel_params(1., 1., 1.);
140+
odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG);
141+
ASSERT_TRUE(odom.update_from_velocity(1., 1., .1, .1, .1));
142+
EXPECT_NEAR(odom.get_linear(), 1.0, 1e-3);
143+
EXPECT_NEAR(odom.get_angular(), .1, 1e-3);
144+
EXPECT_NEAR(odom.get_x(), .1, 1e-3);
145+
EXPECT_NEAR(odom.get_heading(), .01, 1e-3);
146+
}

0 commit comments

Comments
 (0)