From 4f0702208c8ec90e14f6556b616b4ce8f940d7bf Mon Sep 17 00:00:00 2001
From: Aditya Pawar <adityavpawar2003@gmail.com>
Date: Tue, 25 Mar 2025 00:03:31 +0530
Subject: [PATCH 1/8] Extend odometry tests for steering controllers

---
 .../test_steering_controllers_library.cpp     | 34 +++++++++++++++++++
 1 file changed, 34 insertions(+)

diff --git a/steering_controllers_library/test/test_steering_controllers_library.cpp b/steering_controllers_library/test/test_steering_controllers_library.cpp
index 10a0f00376..28c1f17e9a 100644
--- a/steering_controllers_library/test/test_steering_controllers_library.cpp
+++ b/steering_controllers_library/test/test_steering_controllers_library.cpp
@@ -123,6 +123,10 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   // case 1 position_feedback = false
   controller_->params_.position_feedback = false;
 
+  // pre odometry values
+  auto pre_odom_x_1 = controller_->odometry_.get_x();
+  auto pre_odom_y_1 = controller_->odometry_.get_y();
+
   // age_of_last_command > ref_timeout_
   ASSERT_FALSE(age_of_last_command <= controller_->ref_timeout_);
   ASSERT_EQ((*(controller_->input_ref_.readFromRT()))->twist.linear.x, TEST_LINEAR_VELOCITY_X);
@@ -130,6 +134,16 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
     controller_->update(controller_->get_node()->now(), rclcpp::Duration::from_seconds(0.01)),
     controller_interface::return_type::OK);
 
+  // post odometry values
+  auto post_odom_x_1 = controller_->odometry_.get_x();
+  auto post_odom_y_1 = controller_->odometry_.get_y();
+
+  const double position_tolerance = 1e-5;
+
+  // Position should remain stable
+  EXPECT_NEAR(pre_odom_x_1, post_odom_x_1, position_tolerance);
+  EXPECT_NEAR(pre_odom_y_1, post_odom_y_1, position_tolerance);
+
   EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[0]));
   EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[1]));
   for (const auto & interface : controller_->reference_interfaces_)
@@ -153,9 +167,17 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   EXPECT_NEAR(controller_->command_interfaces_[2].get_value(), 0.575875, 1e-6);
   EXPECT_NEAR(controller_->command_interfaces_[3].get_value(), 0.575875, 1e-6);
 
+  // Linear and angular velocity should be reset to zero
+  EXPECT_DOUBLE_EQ(controller_->odometry_.get_linear(), 0.0);
+  EXPECT_DOUBLE_EQ(controller_->odometry_.get_angular(), 0.0);
+
   // case 2 position_feedback = true
   controller_->params_.position_feedback = true;
 
+  // pre odometry values
+  auto pre_odom_x_2 = controller_->odometry_.get_x();
+  auto pre_odom_y_2 = controller_->odometry_.get_y();
+
   // adjusting to achieve age_of_last_command > ref_timeout
   msg->header.stamp = controller_->get_node()->now() - controller_->ref_timeout_ -
                       rclcpp::Duration::from_seconds(0.1);
@@ -167,6 +189,14 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   msg->twist.angular.z = TEST_ANGULAR_VELOCITY_Z;
   controller_->input_ref_.writeFromNonRT(msg);
 
+  // post odometry values
+  auto post_odom_x_2 = controller_->odometry_.get_x();
+  auto post_odom_y_2 = controller_->odometry_.get_y();
+
+  // Position should remain stable
+  EXPECT_NEAR(pre_odom_x_2, post_odom_x_2, position_tolerance);
+  EXPECT_NEAR(pre_odom_y_2, post_odom_y_2, position_tolerance);
+
   // age_of_last_command > ref_timeout_
   ASSERT_FALSE(age_of_last_command <= controller_->ref_timeout_);
   ASSERT_EQ((*(controller_->input_ref_.readFromRT()))->twist.linear.x, TEST_LINEAR_VELOCITY_X);
@@ -196,6 +226,10 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   // Steer angles should not reset
   EXPECT_NEAR(controller_->command_interfaces_[2].get_value(), 0.575875, 1e-6);
   EXPECT_NEAR(controller_->command_interfaces_[3].get_value(), 0.575875, 1e-6);
+
+  // Linear and angular velocity should be reset to zero
+  EXPECT_DOUBLE_EQ(controller_->odometry_.get_linear(), 0.0);
+  EXPECT_DOUBLE_EQ(controller_->odometry_.get_angular(), 0.0);
 }
 
 int main(int argc, char ** argv)

From 618c36d97eb7f508f8da3c4eb07672dfe8eca7a9 Mon Sep 17 00:00:00 2001
From: Aditya Pawar <adityavpawar2003@gmail.com>
Date: Tue, 25 Mar 2025 09:14:46 +0000
Subject: [PATCH 2/8] Updated the post_odom sequence and added last velocities
 check

---
 .../test_steering_controllers_library.cpp     | 24 ++++++++++++++-----
 1 file changed, 18 insertions(+), 6 deletions(-)

diff --git a/steering_controllers_library/test/test_steering_controllers_library.cpp b/steering_controllers_library/test/test_steering_controllers_library.cpp
index 28c1f17e9a..25587e172c 100644
--- a/steering_controllers_library/test/test_steering_controllers_library.cpp
+++ b/steering_controllers_library/test/test_steering_controllers_library.cpp
@@ -126,6 +126,7 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   // pre odometry values
   auto pre_odom_x_1 = controller_->odometry_.get_x();
   auto pre_odom_y_1 = controller_->odometry_.get_y();
+  auto pre_odom_heading_1 = controller_->odometry_->get_heading();
 
   // age_of_last_command > ref_timeout_
   ASSERT_FALSE(age_of_last_command <= controller_->ref_timeout_);
@@ -137,12 +138,17 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   // post odometry values
   auto post_odom_x_1 = controller_->odometry_.get_x();
   auto post_odom_y_1 = controller_->odometry_.get_y();
+  auto post_odom_heading_1 = controller_->odometry_->get_heading();
 
   const double position_tolerance = 1e-5;
 
   // Position should remain stable
   EXPECT_NEAR(pre_odom_x_1, post_odom_x_1, position_tolerance);
   EXPECT_NEAR(pre_odom_y_1, post_odom_y_1, position_tolerance);
+  EXPECT_NEAR(pre_odom_heading_1, post_odom_heading_1, position_tolerance);
+
+  EXPECT_DOUBLE_EQ(controller_->last_linear_velocity_, 0.0);
+  EXPECT_DOUBLE_EQ(controller_->last_angular_velocity_, 0.0);
 
   EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[0]));
   EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[1]));
@@ -177,6 +183,7 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   // pre odometry values
   auto pre_odom_x_2 = controller_->odometry_.get_x();
   auto pre_odom_y_2 = controller_->odometry_.get_y();
+  auto pre_odom_heading_2 = controller_->odometry_.get_heading();
 
   // adjusting to achieve age_of_last_command > ref_timeout
   msg->header.stamp = controller_->get_node()->now() - controller_->ref_timeout_ -
@@ -189,20 +196,25 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   msg->twist.angular.z = TEST_ANGULAR_VELOCITY_Z;
   controller_->input_ref_.writeFromNonRT(msg);
 
+  // age_of_last_command > ref_timeout_
+  ASSERT_FALSE(age_of_last_command <= controller_->ref_timeout_);
+  ASSERT_EQ((*(controller_->input_ref_.readFromRT()))->twist.linear.x, TEST_LINEAR_VELOCITY_X);
+  ASSERT_EQ(
+    controller_->update(controller_->get_node()->now(), rclcpp::Duration::from_seconds(0.01)),
+    controller_interface::return_type::OK);
+
   // post odometry values
   auto post_odom_x_2 = controller_->odometry_.get_x();
   auto post_odom_y_2 = controller_->odometry_.get_y();
+  auto post_odom_heading_2 = controller_->odometry_.get_heading();
 
   // Position should remain stable
   EXPECT_NEAR(pre_odom_x_2, post_odom_x_2, position_tolerance);
   EXPECT_NEAR(pre_odom_y_2, post_odom_y_2, position_tolerance);
+  EXPECT_NEAR(pre_odom_heading_2, post_odom_heading_2, position_tolerance);
 
-  // age_of_last_command > ref_timeout_
-  ASSERT_FALSE(age_of_last_command <= controller_->ref_timeout_);
-  ASSERT_EQ((*(controller_->input_ref_.readFromRT()))->twist.linear.x, TEST_LINEAR_VELOCITY_X);
-  ASSERT_EQ(
-    controller_->update(controller_->get_node()->now(), rclcpp::Duration::from_seconds(0.01)),
-    controller_interface::return_type::OK);
+  EXPECT_DOUBLE_EQ(controller_->last_linear_velocity_, 0.0);
+  EXPECT_DOUBLE_EQ(controller_->last_angular_velocity_, 0.0);
 
   EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[0]));
   EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[1]));

From 590f7473d94fd42572c67c8ded292ac95546b3fd Mon Sep 17 00:00:00 2001
From: Aditya Pawar <adityavpawar2003@gmail.com>
Date: Tue, 25 Mar 2025 10:01:38 +0000
Subject: [PATCH 3/8] Fixed pointer

---
 .../test/test_steering_controllers_library.cpp                | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/steering_controllers_library/test/test_steering_controllers_library.cpp b/steering_controllers_library/test/test_steering_controllers_library.cpp
index 25587e172c..db06ad734c 100644
--- a/steering_controllers_library/test/test_steering_controllers_library.cpp
+++ b/steering_controllers_library/test/test_steering_controllers_library.cpp
@@ -126,7 +126,7 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   // pre odometry values
   auto pre_odom_x_1 = controller_->odometry_.get_x();
   auto pre_odom_y_1 = controller_->odometry_.get_y();
-  auto pre_odom_heading_1 = controller_->odometry_->get_heading();
+  auto pre_odom_heading_1 = controller_->odometry_.get_heading();
 
   // age_of_last_command > ref_timeout_
   ASSERT_FALSE(age_of_last_command <= controller_->ref_timeout_);
@@ -138,7 +138,7 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   // post odometry values
   auto post_odom_x_1 = controller_->odometry_.get_x();
   auto post_odom_y_1 = controller_->odometry_.get_y();
-  auto post_odom_heading_1 = controller_->odometry_->get_heading();
+  auto post_odom_heading_1 = controller_->odometry_.get_heading();
 
   const double position_tolerance = 1e-5;
 

From 551a67e7ff32276a4ee9889e024c0c74a6b1ef62 Mon Sep 17 00:00:00 2001
From: Aditya Pawar <adityavpawar2003@gmail.com>
Date: Wed, 26 Mar 2025 23:10:51 +0530
Subject: [PATCH 4/8] Added a new parameters yaml and updated CMakelists.txt

---
 steering_controllers_library/CMakeLists.txt     | 14 ++++++++++++++
 ...ollers_library_open_loop_timeout_params.yaml | 17 +++++++++++++++++
 .../test/test_steering_controllers_library.hpp  |  9 ++++++++-
 3 files changed, 39 insertions(+), 1 deletion(-)
 create mode 100644 steering_controllers_library/test/steering_controllers_library_open_loop_timeout_params.yaml

diff --git a/steering_controllers_library/CMakeLists.txt b/steering_controllers_library/CMakeLists.txt
index 2e80ed198f..3fed8ce0ad 100644
--- a/steering_controllers_library/CMakeLists.txt
+++ b/steering_controllers_library/CMakeLists.txt
@@ -74,6 +74,20 @@ if(BUILD_TESTING)
   ament_add_gmock(test_steering_odometry test/test_steering_odometry.cpp)
   target_link_libraries(test_steering_odometry steering_controllers_library)
 
+  add_rostest_with_parameters_gmock(
+    test_steering_controllers_open_library test/test_steering_controllers_library.cpp
+    ${CMAKE_CURRENT_SOURCE_DIR}/test/steering_controllers_library_open_loop_timeout_params.yaml)
+  target_include_directories(test_steering_controllers_open_library PRIVATE include)
+  target_link_libraries(test_steering_controllers_open_library steering_controllers_library)
+  ament_target_dependencies(
+    test_steering_controllers_open_library
+    controller_interface
+    hardware_interface
+  )
+
+  ament_add_gmock(test_steering_odometry_open_loop_timeout test/test_steering_odometry.cpp)
+  target_link_libraries(test_steering_odometry_open_loop_timeout steering_controllers_library)
+
 endif()
 
 install(
diff --git a/steering_controllers_library/test/steering_controllers_library_open_loop_timeout_params.yaml b/steering_controllers_library/test/steering_controllers_library_open_loop_timeout_params.yaml
new file mode 100644
index 0000000000..5b4f0daa40
--- /dev/null
+++ b/steering_controllers_library/test/steering_controllers_library_open_loop_timeout_params.yaml
@@ -0,0 +1,17 @@
+test_steering_controllers_library_open_loop_timeout:
+  ros__parameters:
+
+    reference_timeout: 0.1
+    front_steering: true
+    open_loop: true
+    velocity_rolling_window_size: 10
+    position_feedback: false
+    use_stamped_vel: true
+    rear_wheels_names: [rear_right_wheel_joint, rear_left_wheel_joint]
+    front_wheels_names: [front_right_steering_joint, front_left_steering_joint]
+
+    wheelbase: 3.24644
+    front_wheel_track: 2.12321
+    rear_wheel_track: 1.76868
+    front_wheels_radius: 0.45
+    rear_wheels_radius: 0.45
diff --git a/steering_controllers_library/test/test_steering_controllers_library.hpp b/steering_controllers_library/test/test_steering_controllers_library.hpp
index 52bd69744f..5b4c408c20 100644
--- a/steering_controllers_library/test/test_steering_controllers_library.hpp
+++ b/steering_controllers_library/test/test_steering_controllers_library.hpp
@@ -127,7 +127,14 @@ class TestableSteeringControllersLibrary
     return controller_interface::CallbackReturn::SUCCESS;
   }
 
-  bool update_odometry(const rclcpp::Duration & /*period*/) { return true; }
+  bool update_odometry(const rclcpp::Duration & period)
+  {
+    if (params_.open_loop)
+    {
+      odometry_.update_open_loop(last_linear_velocity_, last_angular_velocity_, period.seconds());
+    }
+    return true;
+  }
 };
 
 // We are using template class here for easier reuse of Fixture in specializations of controllers

From d059bcce5ea8b12f1e214e6acd7f785b33c41e3f Mon Sep 17 00:00:00 2001
From: Aditya Pawar <adityavpawar2003@gmail.com>
Date: Thu, 27 Mar 2025 07:12:01 +0000
Subject: [PATCH 5/8] Removed redundant gmock target and applied requested
 modifications

---
 steering_controllers_library/CMakeLists.txt                 | 3 ---
 ...eering_controllers_library_open_loop_timeout_params.yaml | 2 +-
 .../test/test_steering_controllers_library.cpp              | 6 ++++++
 3 files changed, 7 insertions(+), 4 deletions(-)

diff --git a/steering_controllers_library/CMakeLists.txt b/steering_controllers_library/CMakeLists.txt
index 3fed8ce0ad..5393ff88b8 100644
--- a/steering_controllers_library/CMakeLists.txt
+++ b/steering_controllers_library/CMakeLists.txt
@@ -85,9 +85,6 @@ if(BUILD_TESTING)
     hardware_interface
   )
 
-  ament_add_gmock(test_steering_odometry_open_loop_timeout test/test_steering_odometry.cpp)
-  target_link_libraries(test_steering_odometry_open_loop_timeout steering_controllers_library)
-
 endif()
 
 install(
diff --git a/steering_controllers_library/test/steering_controllers_library_open_loop_timeout_params.yaml b/steering_controllers_library/test/steering_controllers_library_open_loop_timeout_params.yaml
index 5b4f0daa40..61436ec184 100644
--- a/steering_controllers_library/test/steering_controllers_library_open_loop_timeout_params.yaml
+++ b/steering_controllers_library/test/steering_controllers_library_open_loop_timeout_params.yaml
@@ -1,4 +1,4 @@
-test_steering_controllers_library_open_loop_timeout:
+test_steering_controllers_library:
   ros__parameters:
 
     reference_timeout: 0.1
diff --git a/steering_controllers_library/test/test_steering_controllers_library.cpp b/steering_controllers_library/test/test_steering_controllers_library.cpp
index db06ad734c..a7dd0024a1 100644
--- a/steering_controllers_library/test/test_steering_controllers_library.cpp
+++ b/steering_controllers_library/test/test_steering_controllers_library.cpp
@@ -134,6 +134,9 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   ASSERT_EQ(
     controller_->update(controller_->get_node()->now(), rclcpp::Duration::from_seconds(0.01)),
     controller_interface::return_type::OK);
+  ASSERT_EQ(
+    controller_->update(controller_->get_node()->now(), rclcpp::Duration::from_seconds(0.01)),
+    controller_interface::return_type::OK);
 
   // post odometry values
   auto post_odom_x_1 = controller_->odometry_.get_x();
@@ -202,6 +205,9 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
   ASSERT_EQ(
     controller_->update(controller_->get_node()->now(), rclcpp::Duration::from_seconds(0.01)),
     controller_interface::return_type::OK);
+  ASSERT_EQ(
+    controller_->update(controller_->get_node()->now(), rclcpp::Duration::from_seconds(0.01)),
+    controller_interface::return_type::OK);
 
   // post odometry values
   auto post_odom_x_2 = controller_->odometry_.get_x();

From 9b5e9762e71db54eea4ef5b185cd1c08a173fbce Mon Sep 17 00:00:00 2001
From: Aditya Pawar <adityavpawar2003@gmail.com>
Date: Sun, 30 Mar 2025 00:14:07 +0530
Subject: [PATCH 6/8] Modified steering_controller_library to handle timeout

---
 .../src/steering_controllers_library.cpp      | 57 ++++++++++++++-----
 1 file changed, 43 insertions(+), 14 deletions(-)

diff --git a/steering_controllers_library/src/steering_controllers_library.cpp b/steering_controllers_library/src/steering_controllers_library.cpp
index ed0346cbbc..b2c3e33627 100644
--- a/steering_controllers_library/src/steering_controllers_library.cpp
+++ b/steering_controllers_library/src/steering_controllers_library.cpp
@@ -339,6 +339,15 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_activate(
   // Set default value in command
   reset_controller_reference_msg(*(input_ref_.readFromRT()), get_node());
 
+  // Set the initial steering angle values
+  size_t steering_count_idx =
+    params_.front_steering ? params_.front_wheels_names.size() : params_.rear_wheels_names.size();
+
+  for (size_t i = 0; i < steering_count_idx; i++)
+  {
+    command_interfaces_[steering_count_idx + i].set_value(0.575875);
+  }
+
   return controller_interface::CallbackReturn::SUCCESS;
 }
 
@@ -386,32 +395,52 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c
     last_linear_velocity_ = timeout ? 0.0 : reference_interfaces_[0];
     last_angular_velocity_ = timeout ? 0.0 : reference_interfaces_[1];
 
-    auto [traction_commands, steering_commands] = odometry_.get_commands(
-      reference_interfaces_[0], reference_interfaces_[1], params_.open_loop,
-      params_.reduce_wheel_speed_until_steering_reached);
-
-    if (params_.front_steering)
+    // calculate new commands if not in timeout
+    if (!timeout)
     {
-      for (size_t i = 0; i < params_.rear_wheels_names.size(); i++)
+      auto [traction_commands, steering_commands] = odometry_.get_commands(
+        reference_interfaces_[0], reference_interfaces_[1], params_.open_loop,
+        params_.reduce_wheel_speed_until_steering_reached);
+
+      if (params_.front_steering)
       {
-        command_interfaces_[i].set_value(timeout ? 0.0 : traction_commands[i]);
+        for (size_t i = 0; i < params_.rear_wheels_names.size(); i++)
+        {
+          command_interfaces_[i].set_value(traction_commands[i]);
+        }
+        for (size_t i = 0; i < params_.front_wheels_names.size(); i++)
+        {
+          command_interfaces_[i + params_.rear_wheels_names.size()].set_value(steering_commands[i]);
+        }
       }
-      for (size_t i = 0; i < params_.front_wheels_names.size(); i++)
+      else
       {
-        command_interfaces_[i + params_.rear_wheels_names.size()].set_value(steering_commands[i]);
+        for (size_t i = 0; i < params_.front_wheels_names.size(); i++)
+        {
+          command_interfaces_[i].set_value(traction_commands[i]);
+        }
+        for (size_t i = 0; i < params_.rear_wheels_names.size(); i++)
+        {
+          command_interfaces_[i + params_.front_wheels_names.size()].set_value(
+            steering_commands[i]);
+        }
       }
     }
     else
     {
+      // In timeout, only reset wheel velocities to zero
+      if (params_.front_steering)
       {
-        for (size_t i = 0; i < params_.front_wheels_names.size(); i++)
+        for (size_t i = 0; i < params_.rear_wheels_names.size(); i++)
         {
-          command_interfaces_[i].set_value(timeout ? 0.0 : traction_commands[i]);
+          command_interfaces_[i].set_value(0.0);
         }
-        for (size_t i = 0; i < params_.rear_wheels_names.size(); i++)
+      }
+      else
+      {
+        for (size_t i = 0; i < params_.front_wheels_names.size(); i++)
         {
-          command_interfaces_[i + params_.front_wheels_names.size()].set_value(
-            steering_commands[i]);
+          command_interfaces_[i].set_value(0.0);
         }
       }
     }

From 891d4ec29cc37dd86647532140d64ed74613c04d Mon Sep 17 00:00:00 2001
From: Aditya Pawar <adityavpawar2003@gmail.com>
Date: Sun, 30 Mar 2025 01:43:14 +0530
Subject: [PATCH 7/8] Removed duplicate constants

---
 .../test_steering_controllers_library.hpp     | 23 -------------------
 1 file changed, 23 deletions(-)

diff --git a/steering_controllers_library/test/test_steering_controllers_library.hpp b/steering_controllers_library/test/test_steering_controllers_library.hpp
index 5b4c408c20..6037dcf14c 100644
--- a/steering_controllers_library/test/test_steering_controllers_library.hpp
+++ b/steering_controllers_library/test/test_steering_controllers_library.hpp
@@ -55,10 +55,8 @@ static constexpr size_t NR_CMD_ITFS = 4;
 static constexpr size_t NR_REF_ITFS = 2;
 
 static constexpr double WHEELBASE_ = 3.24644;
-static constexpr double FRONT_WHEEL_TRACK_ = 2.12321;
 static constexpr double REAR_WHEEL_TRACK_ = 1.76868;
 static constexpr double FRONT_WHEELS_RADIUS_ = 0.45;
-static constexpr double REAR_WHEELS_RADIUS_ = 0.45;
 
 namespace
 {
@@ -296,30 +294,10 @@ class SteeringControllersLibraryFixture : public ::testing::Test
 
 protected:
   // Controller-related parameters
-  double reference_timeout_ = 2.0;
-  bool front_steering_ = true;
-  bool open_loop_ = false;
-  unsigned int velocity_rolling_window_size_ = 10;
   bool position_feedback_ = false;
   std::vector<std::string> rear_wheels_names_ = {"rear_right_wheel_joint", "rear_left_wheel_joint"};
   std::vector<std::string> front_wheels_names_ = {
     "front_right_steering_joint", "front_left_steering_joint"};
-  std::vector<std::string> joint_names_ = {
-    rear_wheels_names_[0], rear_wheels_names_[1], front_wheels_names_[0], front_wheels_names_[1]};
-
-  std::vector<std::string> rear_wheels_preceeding_names_ = {
-    "pid_controller/rear_right_wheel_joint", "pid_controller/rear_left_wheel_joint"};
-  std::vector<std::string> front_wheels_preceeding_names_ = {
-    "pid_controller/front_right_steering_joint", "pid_controller/front_left_steering_joint"};
-  std::vector<std::string> preceeding_joint_names_ = {
-    rear_wheels_preceeding_names_[0], rear_wheels_preceeding_names_[1],
-    front_wheels_preceeding_names_[0], front_wheels_preceeding_names_[1]};
-
-  double wheelbase_ = 3.24644;
-  double front_wheel_track_ = 2.12321;
-  double rear_wheel_track_ = 1.76868;
-  double front_wheels_radius_ = 0.45;
-  double rear_wheels_radius_ = 0.45;
 
   std::array<double, 4> joint_state_values_ = {{0.5, 0.5, 0.0, 0.0}};
   std::array<double, 4> joint_command_values_ = {{1.1, 3.3, 2.2, 4.4}};
@@ -328,7 +306,6 @@ class SteeringControllersLibraryFixture : public ::testing::Test
   std::string steering_interface_name_ = "position";
   // defined in setup
   std::string traction_interface_name_ = "";
-  std::string preceeding_prefix_ = "pid_controller";
 
   std::vector<hardware_interface::StateInterface> state_itfs_;
   std::vector<hardware_interface::CommandInterface> command_itfs_;

From f93c6d5773353dff9b2b2233160f094b91e87dc6 Mon Sep 17 00:00:00 2001
From: Aditya Pawar <adityavpawar2003@gmail.com>
Date: Sun, 6 Apr 2025 18:29:52 +0530
Subject: [PATCH 8/8] Changed the joint_command_values_

---
 .../test/test_steering_controllers_library.hpp                  | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/steering_controllers_library/test/test_steering_controllers_library.hpp b/steering_controllers_library/test/test_steering_controllers_library.hpp
index 8c61869207..d45a39a95e 100644
--- a/steering_controllers_library/test/test_steering_controllers_library.hpp
+++ b/steering_controllers_library/test/test_steering_controllers_library.hpp
@@ -308,7 +308,7 @@ class SteeringControllersLibraryFixture : public ::testing::Test
     "front_right_steering_joint", "front_left_steering_joint"};
 
   std::array<double, 4> joint_state_values_ = {{0.5, 0.5, 0.0, 0.0}};
-  std::array<double, 4> joint_command_values_ = {{1.1, 3.3, 2.2, 4.4}};
+  std::array<double, 4> joint_command_values_ = {{1.1, 3.3, 0.575875, 0.575875}};
 
   std::array<std::string, 2> joint_reference_interfaces_ = {{"linear", "angular"}};
   std::string steering_interface_name_ = "position";