Skip to content

Commit 89fd9e1

Browse files
authored
Update odometry implementation in diff_drive (#1854)
1 parent 5890ce1 commit 89fd9e1

File tree

3 files changed

+148
-44
lines changed

3 files changed

+148
-44
lines changed

diff_drive_controller/include/diff_drive_controller/odometry.hpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,10 +37,24 @@ class Odometry
3737
public:
3838
explicit Odometry(size_t velocity_rolling_window_size = 10);
3939

40+
[[deprecated]]
4041
void init(const rclcpp::Time & time);
42+
[[deprecated(
43+
"Replaced by bool update_from_pos(double left_pos, double right_pos, double "
44+
"dt).")]]
4145
bool update(double left_pos, double right_pos, const rclcpp::Time & time);
46+
[[deprecated(
47+
"Replaced by bool update_from_vel(double left_vel, double right_vel, double "
48+
"dt).")]]
4249
bool updateFromVelocity(double left_vel, double right_vel, const rclcpp::Time & time);
50+
[[deprecated(
51+
"Replaced by bool try_update_open_loop(double linear_vel, double angular_vel, double "
52+
"dt).")]]
4353
void updateOpenLoop(double linear, double angular, const rclcpp::Time & time);
54+
55+
bool update_from_pos(double left_pos, double right_pos, double dt);
56+
bool update_from_vel(double left_vel, double right_vel, double dt);
57+
bool try_update_open_loop(double linear_vel, double angular_vel, double dt);
4458
void resetOdometry();
4559

4660
double getX() const { return x_; }
@@ -60,8 +74,12 @@ class Odometry
6074
using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
6175
#endif
6276

77+
[[deprecated("Replaced by void integrate(double linear_vel, double angular_vel, double dt).")]]
6378
void integrateRungeKutta2(double linear, double angular);
79+
[[deprecated("Replaced by void integrate(double linear_vel, double angular_vel, double dt).")]]
6480
void integrateExact(double linear, double angular);
81+
82+
void integrate(double linear_vel, double angular_vel, double dt);
6583
void resetAccumulators();
6684

6785
// Current timestamp:

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 50 additions & 44 deletions
Original file line numberDiff line numberDiff line change
@@ -160,9 +160,12 @@ controller_interface::return_type DiffDriveController::update_and_write_commands
160160
const double left_wheel_radius = params_.left_wheel_radius_multiplier * params_.wheel_radius;
161161
const double right_wheel_radius = params_.right_wheel_radius_multiplier * params_.wheel_radius;
162162

163+
// Update odometry
164+
bool odometry_updated = false;
163165
if (params_.open_loop)
164166
{
165-
odometry_.updateOpenLoop(linear_command, angular_command, time);
167+
odometry_updated =
168+
odometry_.try_update_open_loop(linear_command, angular_command, period.seconds());
166169
}
167170
else
168171
{
@@ -200,62 +203,65 @@ controller_interface::return_type DiffDriveController::update_and_write_commands
200203

201204
if (params_.position_feedback)
202205
{
203-
odometry_.update(left_feedback_mean, right_feedback_mean, time);
206+
odometry_updated =
207+
odometry_.update_from_pos(left_feedback_mean, right_feedback_mean, period.seconds());
204208
}
205209
else
206210
{
207-
odometry_.updateFromVelocity(
208-
left_feedback_mean * left_wheel_radius * period.seconds(),
209-
right_feedback_mean * right_wheel_radius * period.seconds(), time);
211+
odometry_updated =
212+
odometry_.update_from_vel(left_feedback_mean, right_feedback_mean, period.seconds());
210213
}
211214
}
212215

213-
tf2::Quaternion orientation;
214-
orientation.setRPY(0.0, 0.0, odometry_.getHeading());
215-
216-
bool should_publish = false;
217-
try
216+
if (odometry_updated)
218217
{
219-
if (previous_publish_timestamp_ + publish_period_ < time)
218+
tf2::Quaternion orientation;
219+
orientation.setRPY(0.0, 0.0, odometry_.getHeading());
220+
221+
bool should_publish = false;
222+
try
220223
{
221-
previous_publish_timestamp_ += publish_period_;
222-
should_publish = true;
224+
if (previous_publish_timestamp_ + publish_period_ <= time)
225+
{
226+
previous_publish_timestamp_ += publish_period_;
227+
should_publish = true;
228+
}
223229
}
224-
}
225-
catch (const std::runtime_error &)
226-
{
227-
// Handle exceptions when the time source changes and initialize publish timestamp
228-
previous_publish_timestamp_ = time;
229-
should_publish = true;
230-
}
231-
232-
if (should_publish)
233-
{
234-
if (realtime_odometry_publisher_)
230+
catch (const std::runtime_error &)
235231
{
236-
odometry_message_.header.stamp = time;
237-
odometry_message_.pose.pose.position.x = odometry_.getX();
238-
odometry_message_.pose.pose.position.y = odometry_.getY();
239-
odometry_message_.pose.pose.orientation.x = orientation.x();
240-
odometry_message_.pose.pose.orientation.y = orientation.y();
241-
odometry_message_.pose.pose.orientation.z = orientation.z();
242-
odometry_message_.pose.pose.orientation.w = orientation.w();
243-
odometry_message_.twist.twist.linear.x = odometry_.getLinear();
244-
odometry_message_.twist.twist.angular.z = odometry_.getAngular();
245-
realtime_odometry_publisher_->try_publish(odometry_message_);
232+
// Handle exceptions when the time source changes and initialize publish timestamp
233+
previous_publish_timestamp_ = time;
234+
should_publish = true;
246235
}
247236

248-
if (params_.enable_odom_tf && realtime_odometry_transform_publisher_)
237+
if (should_publish)
249238
{
250-
auto & transform = odometry_transform_message_.transforms.front();
251-
transform.header.stamp = time;
252-
transform.transform.translation.x = odometry_.getX();
253-
transform.transform.translation.y = odometry_.getY();
254-
transform.transform.rotation.x = orientation.x();
255-
transform.transform.rotation.y = orientation.y();
256-
transform.transform.rotation.z = orientation.z();
257-
transform.transform.rotation.w = orientation.w();
258-
realtime_odometry_transform_publisher_->try_publish(odometry_transform_message_);
239+
if (realtime_odometry_publisher_)
240+
{
241+
odometry_message_.header.stamp = time;
242+
odometry_message_.pose.pose.position.x = odometry_.getX();
243+
odometry_message_.pose.pose.position.y = odometry_.getY();
244+
odometry_message_.pose.pose.orientation.x = orientation.x();
245+
odometry_message_.pose.pose.orientation.y = orientation.y();
246+
odometry_message_.pose.pose.orientation.z = orientation.z();
247+
odometry_message_.pose.pose.orientation.w = orientation.w();
248+
odometry_message_.twist.twist.linear.x = odometry_.getLinear();
249+
odometry_message_.twist.twist.angular.z = odometry_.getAngular();
250+
realtime_odometry_publisher_->try_publish(odometry_message_);
251+
}
252+
253+
if (params_.enable_odom_tf && realtime_odometry_transform_publisher_)
254+
{
255+
auto & transform = odometry_transform_message_.transforms.front();
256+
transform.header.stamp = time;
257+
transform.transform.translation.x = odometry_.getX();
258+
transform.transform.translation.y = odometry_.getY();
259+
transform.transform.rotation.x = orientation.x();
260+
transform.transform.rotation.y = orientation.y();
261+
transform.transform.rotation.z = orientation.z();
262+
transform.transform.rotation.w = orientation.w();
263+
realtime_odometry_transform_publisher_->try_publish(odometry_transform_message_);
264+
}
259265
}
260266
}
261267

diff_drive_controller/src/odometry.cpp

Lines changed: 80 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,25 @@ bool Odometry::update(double left_pos, double right_pos, const rclcpp::Time & ti
7373
return true;
7474
}
7575

76+
bool Odometry::update_from_pos(double left_pos, double right_pos, double dt)
77+
{
78+
// We cannot estimate angular velocity with very small time intervals
79+
if (std::fabs(dt) < 1e-6)
80+
{
81+
return false;
82+
}
83+
84+
// Estimate angular velocity of wheels using old and current position [rads/s]:
85+
double left_vel = (left_pos - left_wheel_old_pos_) / dt;
86+
double right_vel = (right_pos - right_wheel_old_pos_) / dt;
87+
88+
// Update old position with current:
89+
left_wheel_old_pos_ = left_pos;
90+
right_wheel_old_pos_ = right_pos;
91+
92+
return update_from_vel(left_vel, right_vel, dt);
93+
}
94+
7695
bool Odometry::updateFromVelocity(double left_vel, double right_vel, const rclcpp::Time & time)
7796
{
7897
const double dt = time.seconds() - timestamp_.seconds();
@@ -100,6 +119,30 @@ bool Odometry::updateFromVelocity(double left_vel, double right_vel, const rclcp
100119
return true;
101120
}
102121

122+
bool Odometry::update_from_vel(double left_vel, double right_vel, double dt)
123+
{
124+
if (std::fabs(dt) < 1e-6)
125+
{
126+
return false; // Interval too small to integrate with
127+
}
128+
// Compute linear and angular velocities of the robot:
129+
const double linear_vel = (left_vel * left_wheel_radius_ + right_vel * right_wheel_radius_) * 0.5;
130+
const double angular_vel =
131+
(right_vel * right_wheel_radius_ - left_vel * left_wheel_radius_) / wheel_separation_;
132+
133+
// Integrate odometry:
134+
integrate(linear_vel, angular_vel, dt);
135+
136+
// Estimate speeds using a rolling mean to filter them out:
137+
linear_accumulator_.accumulate(linear_vel);
138+
angular_accumulator_.accumulate(angular_vel);
139+
140+
linear_ = linear_accumulator_.getRollingMean();
141+
angular_ = angular_accumulator_.getRollingMean();
142+
143+
return true;
144+
}
145+
103146
void Odometry::updateOpenLoop(double linear, double angular, const rclcpp::Time & time)
104147
{
105148
/// Save last linear and angular velocity:
@@ -112,6 +155,18 @@ void Odometry::updateOpenLoop(double linear, double angular, const rclcpp::Time
112155
integrateExact(linear * dt, angular * dt);
113156
}
114157

158+
bool Odometry::try_update_open_loop(double linear_vel, double angular_vel, double dt)
159+
{
160+
// Integrate odometry:
161+
integrate(linear_vel, angular_vel, dt);
162+
163+
// Save last linear and angular velocity:
164+
linear_ = linear_vel;
165+
angular_ = angular_vel;
166+
167+
return true;
168+
}
169+
115170
void Odometry::resetOdometry()
116171
{
117172
x_ = 0.0;
@@ -161,6 +216,31 @@ void Odometry::integrateExact(double linear, double angular)
161216
}
162217
}
163218

219+
void Odometry::integrate(double linear_vel, double angular_vel, double dt)
220+
{
221+
// Skip integration for invalid time intervals
222+
if (std::fabs(dt) < 1e-6)
223+
{
224+
return;
225+
}
226+
const double dx = linear_vel * dt;
227+
const double dheading = angular_vel * dt;
228+
if (fabs(dheading) < 1e-6)
229+
{
230+
// For very small dheading, approximate to linear motion
231+
x_ += (dx * std::cos(heading_));
232+
y_ += (dx * std::sin(heading_));
233+
heading_ += dheading;
234+
}
235+
else
236+
{
237+
const double heading_old = heading_;
238+
heading_ += dheading;
239+
x_ += ((dx / dheading) * (std::sin(heading_) - std::sin(heading_old)));
240+
y_ += -(dx / dheading) * (std::cos(heading_) - std::cos(heading_old));
241+
}
242+
}
243+
164244
void Odometry::resetAccumulators()
165245
{
166246
linear_accumulator_ = RollingMeanAccumulator(velocity_rolling_window_size_);

0 commit comments

Comments
 (0)