Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
fe3a568
Update odometry implementation in diff_drive
Amronos Aug 6, 2025
13edbec
Apply suggestions from code review
Amronos Aug 20, 2025
629cf5e
Fix deprecation warning
Amronos Aug 20, 2025
d387750
Multiply by wheel radius in updateFromVel
Amronos Aug 20, 2025
bd1283b
Fix pre-commit
Amronos Aug 20, 2025
3048023
Merge branch 'master' into update-diff_drive-odom
Amronos Sep 4, 2025
93806d6
Fix build errors
Amronos Sep 4, 2025
1d47fed
Update diff_drive_controller/src/odometry.cpp
Amronos Sep 9, 2025
a52855b
Merge branch 'master' into update-diff_drive-odom
Amronos Sep 9, 2025
77eade3
Apply suggestions from code review
Amronos Sep 24, 2025
831c9c7
Merge branch 'master' into update-diff_drive-odom
Amronos Sep 24, 2025
a95a450
Fix pre-commit
Amronos Sep 24, 2025
8ecb548
Fix pre-commit
Amronos Sep 24, 2025
ec25473
Fix pre-commit
Amronos Oct 3, 2025
3e04f37
Merge branch 'master' into update-diff_drive-odom
Amronos Oct 3, 2025
93b0c0c
Merge branch 'master' into update-diff_drive-odom
Amronos Oct 5, 2025
620aec5
Merge branch 'master' into update-diff_drive-odom
Amronos Oct 22, 2025
574c3ba
Update diff_drive_controller/src/diff_drive_controller.cpp
Amronos Oct 22, 2025
f52b6b1
Update diff_drive_controller/src/diff_drive_controller.cpp
Amronos Oct 22, 2025
5c2620c
Merge branch 'master' into update-diff_drive-odom
Amronos Nov 7, 2025
6a6c38c
Apply suggestions from code review
Amronos Nov 9, 2025
e28abfa
Merge branch 'master' into update-diff_drive-odom
Amronos Nov 9, 2025
b474fde
Merge branch 'master' into update-diff_drive-odom
Amronos Nov 24, 2025
a268833
Apply suggestions from code review
Amronos Nov 30, 2025
d85632f
Fix pre-commit
Amronos Nov 30, 2025
8dc9951
Merge branch 'master' into update-diff_drive-odom
Amronos Nov 30, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 18 additions & 0 deletions diff_drive_controller/include/diff_drive_controller/odometry.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,24 @@ class Odometry
public:
explicit Odometry(size_t velocity_rolling_window_size = 10);

[[deprecated]]
void init(const rclcpp::Time & time);
[[deprecated(
"Replaced by bool update_from_pos(double left_pos, double right_pos, double "
"dt).")]]
bool update(double left_pos, double right_pos, const rclcpp::Time & time);
[[deprecated(
"Replaced by bool update_from_vel(double left_vel, double right_vel, double "
"dt).")]]
bool updateFromVelocity(double left_vel, double right_vel, const rclcpp::Time & time);
[[deprecated(
"Replaced by bool try_update_open_loop(double linear_vel, double angular_vel, double "
"dt).")]]
void updateOpenLoop(double linear, double angular, const rclcpp::Time & time);

bool update_from_pos(double left_pos, double right_pos, double dt);
bool update_from_vel(double left_vel, double right_vel, double dt);
bool try_update_open_loop(double linear_vel, double angular_vel, double dt);
void resetOdometry();

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

[[deprecated("Replaced by void integrate(double linear_vel, double angular_vel, double dt).")]]
void integrateRungeKutta2(double linear, double angular);
[[deprecated("Replaced by void integrate(double linear_vel, double angular_vel, double dt).")]]
void integrateExact(double linear, double angular);

void integrate(double linear_vel, double angular_vel, double dt);
void resetAccumulators();

// Current timestamp:
Expand Down
94 changes: 50 additions & 44 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,9 +160,12 @@ controller_interface::return_type DiffDriveController::update_and_write_commands
const double left_wheel_radius = params_.left_wheel_radius_multiplier * params_.wheel_radius;
const double right_wheel_radius = params_.right_wheel_radius_multiplier * params_.wheel_radius;

// Update odometry
bool odometry_updated = false;
if (params_.open_loop)
{
odometry_.updateOpenLoop(linear_command, angular_command, time);
odometry_updated =
odometry_.try_update_open_loop(linear_command, angular_command, period.seconds());
}
else
{
Expand Down Expand Up @@ -200,62 +203,65 @@ controller_interface::return_type DiffDriveController::update_and_write_commands

if (params_.position_feedback)
{
odometry_.update(left_feedback_mean, right_feedback_mean, time);
odometry_updated =
odometry_.update_from_pos(left_feedback_mean, right_feedback_mean, period.seconds());
}
else
{
odometry_.updateFromVelocity(
left_feedback_mean * left_wheel_radius * period.seconds(),
right_feedback_mean * right_wheel_radius * period.seconds(), time);
odometry_updated =
odometry_.update_from_vel(left_feedback_mean, right_feedback_mean, period.seconds());
}
}

tf2::Quaternion orientation;
orientation.setRPY(0.0, 0.0, odometry_.getHeading());

bool should_publish = false;
try
if (odometry_updated)
{
if (previous_publish_timestamp_ + publish_period_ < time)
tf2::Quaternion orientation;
orientation.setRPY(0.0, 0.0, odometry_.getHeading());

bool should_publish = false;
try
{
previous_publish_timestamp_ += publish_period_;
should_publish = true;
if (previous_publish_timestamp_ + publish_period_ <= time)
{
previous_publish_timestamp_ += publish_period_;
should_publish = true;
}
}
}
catch (const std::runtime_error &)
{
// Handle exceptions when the time source changes and initialize publish timestamp
previous_publish_timestamp_ = time;
should_publish = true;
}

if (should_publish)
{
if (realtime_odometry_publisher_)
catch (const std::runtime_error &)
{
odometry_message_.header.stamp = time;
odometry_message_.pose.pose.position.x = odometry_.getX();
odometry_message_.pose.pose.position.y = odometry_.getY();
odometry_message_.pose.pose.orientation.x = orientation.x();
odometry_message_.pose.pose.orientation.y = orientation.y();
odometry_message_.pose.pose.orientation.z = orientation.z();
odometry_message_.pose.pose.orientation.w = orientation.w();
odometry_message_.twist.twist.linear.x = odometry_.getLinear();
odometry_message_.twist.twist.angular.z = odometry_.getAngular();
realtime_odometry_publisher_->try_publish(odometry_message_);
// Handle exceptions when the time source changes and initialize publish timestamp
previous_publish_timestamp_ = time;
should_publish = true;
}
Comment on lines +230 to 235
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this block meant to catch the error of previous_publish_timestamp as unintialized ? if so, we should initialize it in on_configure. If not, this block may not be reachable.

Copy link
Contributor Author

@Amronos Amronos Nov 30, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This isn't really a part of the changes made in this PR, perhaps create a separate issue? A similar pattern exists in other controllers as well, so the change will need to be propagated to them as well.
If you create another issue, please also link this suggestion in it.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You are right, this existed before and the diff is just not properly rendered by the UI. @Juliaj please open a (first) issue with this.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.


if (params_.enable_odom_tf && realtime_odometry_transform_publisher_)
if (should_publish)
{
auto & transform = odometry_transform_message_.transforms.front();
transform.header.stamp = time;
transform.transform.translation.x = odometry_.getX();
transform.transform.translation.y = odometry_.getY();
transform.transform.rotation.x = orientation.x();
transform.transform.rotation.y = orientation.y();
transform.transform.rotation.z = orientation.z();
transform.transform.rotation.w = orientation.w();
realtime_odometry_transform_publisher_->try_publish(odometry_transform_message_);
if (realtime_odometry_publisher_)
{
odometry_message_.header.stamp = time;
odometry_message_.pose.pose.position.x = odometry_.getX();
odometry_message_.pose.pose.position.y = odometry_.getY();
odometry_message_.pose.pose.orientation.x = orientation.x();
odometry_message_.pose.pose.orientation.y = orientation.y();
odometry_message_.pose.pose.orientation.z = orientation.z();
odometry_message_.pose.pose.orientation.w = orientation.w();
odometry_message_.twist.twist.linear.x = odometry_.getLinear();
odometry_message_.twist.twist.angular.z = odometry_.getAngular();
realtime_odometry_publisher_->try_publish(odometry_message_);
}

if (params_.enable_odom_tf && realtime_odometry_transform_publisher_)
{
auto & transform = odometry_transform_message_.transforms.front();
transform.header.stamp = time;
transform.transform.translation.x = odometry_.getX();
transform.transform.translation.y = odometry_.getY();
transform.transform.rotation.x = orientation.x();
transform.transform.rotation.y = orientation.y();
transform.transform.rotation.z = orientation.z();
transform.transform.rotation.w = orientation.w();
realtime_odometry_transform_publisher_->try_publish(odometry_transform_message_);
}
}
}

Expand Down
80 changes: 80 additions & 0 deletions diff_drive_controller/src/odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,25 @@ bool Odometry::update(double left_pos, double right_pos, const rclcpp::Time & ti
return true;
}

bool Odometry::update_from_pos(double left_pos, double right_pos, double dt)
{
// We cannot estimate angular velocity with very small time intervals
if (std::fabs(dt) < 1e-6)
{
return false;
}

// Estimate angular velocity of wheels using old and current position [rads/s]:
double left_vel = (left_pos - left_wheel_old_pos_) / dt;
double right_vel = (right_pos - right_wheel_old_pos_) / dt;

// Update old position with current:
left_wheel_old_pos_ = left_pos;
right_wheel_old_pos_ = right_pos;

return update_from_vel(left_vel, right_vel, dt);
}

bool Odometry::updateFromVelocity(double left_vel, double right_vel, const rclcpp::Time & time)
{
const double dt = time.seconds() - timestamp_.seconds();
Expand Down Expand Up @@ -100,6 +119,30 @@ bool Odometry::updateFromVelocity(double left_vel, double right_vel, const rclcp
return true;
}

bool Odometry::update_from_vel(double left_vel, double right_vel, double dt)
{
if (std::fabs(dt) < 1e-6)
{
return false; // Interval too small to integrate with
}
// Compute linear and angular velocities of the robot:
const double linear_vel = (left_vel * left_wheel_radius_ + right_vel * right_wheel_radius_) * 0.5;
const double angular_vel =
(right_vel * right_wheel_radius_ - left_vel * left_wheel_radius_) / wheel_separation_;

// Integrate odometry:
integrate(linear_vel, angular_vel, dt);

// Estimate speeds using a rolling mean to filter them out:
linear_accumulator_.accumulate(linear_vel);
angular_accumulator_.accumulate(angular_vel);

linear_ = linear_accumulator_.getRollingMean();
angular_ = angular_accumulator_.getRollingMean();

return true;
}

void Odometry::updateOpenLoop(double linear, double angular, const rclcpp::Time & time)
{
/// Save last linear and angular velocity:
Expand All @@ -112,6 +155,18 @@ void Odometry::updateOpenLoop(double linear, double angular, const rclcpp::Time
integrateExact(linear * dt, angular * dt);
}

bool Odometry::try_update_open_loop(double linear_vel, double angular_vel, double dt)
{
// Integrate odometry:
integrate(linear_vel, angular_vel, dt);

// Save last linear and angular velocity:
linear_ = linear_vel;
angular_ = angular_vel;

return true;
}

void Odometry::resetOdometry()
{
x_ = 0.0;
Expand Down Expand Up @@ -161,6 +216,31 @@ void Odometry::integrateExact(double linear, double angular)
}
}

void Odometry::integrate(double linear_vel, double angular_vel, double dt)
{
// Skip integration for invalid time intervals
if (std::fabs(dt) < 1e-6)
{
return;
}
const double dx = linear_vel * dt;
const double dheading = angular_vel * dt;
if (fabs(dheading) < 1e-6)
{
// For very small dheading, approximate to linear motion
x_ += (dx * std::cos(heading_));
y_ += (dx * std::sin(heading_));
heading_ += dheading;
}
else
{
const double heading_old = heading_;
heading_ += dheading;
x_ += ((dx / dheading) * (std::sin(heading_) - std::sin(heading_old)));
y_ += -(dx / dheading) * (std::cos(heading_) - std::cos(heading_old));
}
}

void Odometry::resetAccumulators()
{
linear_accumulator_ = RollingMeanAccumulator(velocity_rolling_window_size_);
Expand Down