We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent a35db48 commit a1b5789Copy full SHA for a1b5789
steering_controllers_library/src/steering_controllers_library.cpp
@@ -507,9 +507,13 @@ controller_interface::return_type SteeringControllersLibrary::update_reference_f
507
controller_interface::return_type SteeringControllersLibrary::update_and_write_commands(
508
const rclcpp::Time & time, const rclcpp::Duration & period)
509
{
510
- update_odometry(period);
511
auto logger = get_node()->get_logger();
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
+
517
// MOVE ROBOT
518
519
// Limit velocities and accelerations:
0 commit comments