Skip to content

Commit a1b5789

Browse files
authored
Fix open_loop odometry of steering controllers (backport #2087) (#2089)
1 parent a35db48 commit a1b5789

File tree

1 file changed

+5
-1
lines changed

1 file changed

+5
-1
lines changed

steering_controllers_library/src/steering_controllers_library.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -507,9 +507,13 @@ controller_interface::return_type SteeringControllersLibrary::update_reference_f
507507
controller_interface::return_type SteeringControllersLibrary::update_and_write_commands(
508508
const rclcpp::Time & time, const rclcpp::Duration & period)
509509
{
510-
update_odometry(period);
511510
auto logger = get_node()->get_logger();
512511

512+
// store current ref (for open loop odometry) and update odometry
513+
last_linear_velocity_ = reference_interfaces_[0];
514+
last_angular_velocity_ = reference_interfaces_[1];
515+
update_odometry(period);
516+
513517
// MOVE ROBOT
514518

515519
// Limit velocities and accelerations:

0 commit comments

Comments
 (0)