Skip to content

Commit 6155248

Browse files
[Steering controllers library] Reference interfaces are body twist (#1168)
1 parent b245155 commit 6155248

File tree

10 files changed

+13
-11
lines changed

10 files changed

+13
-11
lines changed

ackermann_steering_controller/test/test_ackermann_steering_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,7 @@ TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
8484
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
8585
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
8686

87-
// check ref itfsTIME
87+
// check ref itfs
8888
auto reference_interfaces = controller_->export_reference_interfaces();
8989
ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size());
9090
for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i)

ackermann_steering_controller/test/test_ackermann_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -302,7 +302,7 @@ class AckermannSteeringControllerFixture : public ::testing::Test
302302

303303
std::array<double, 4> joint_state_values_ = {0.5, 0.5, 0.0, 0.0};
304304
std::array<double, 4> joint_command_values_ = {1.1, 3.3, 2.2, 4.4};
305-
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
305+
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
306306
std::string steering_interface_name_ = "position";
307307
// defined in setup
308308
std::string traction_interface_name_ = "";

bicycle_steering_controller/test/test_bicycle_steering_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ TEST_F(BicycleSteeringControllerTest, check_exported_interfaces)
6868
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
6969
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
7070

71-
// check ref itfsTIME
71+
// check ref itfs
7272
auto reference_interfaces = controller_->export_reference_interfaces();
7373
ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size());
7474
for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i)

bicycle_steering_controller/test/test_bicycle_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -266,7 +266,7 @@ class BicycleSteeringControllerFixture : public ::testing::Test
266266

267267
std::array<double, 2> joint_state_values_ = {3.3, 0.5};
268268
std::array<double, 2> joint_command_values_ = {1.1, 2.2};
269-
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
269+
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
270270
std::string steering_interface_name_ = "position";
271271

272272
// defined in setup

steering_controllers_library/doc/userdoc.rst

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,9 @@ References (from a preceding controller)
5656
Used when controller is in chained mode (``in_chained_mode == true``).
5757

5858
- ``<controller_name>/linear/velocity`` double, in m/s
59-
- ``<controller_name>/angular/position`` double, in rad
59+
- ``<controller_name>/angular/velocity`` double, in rad/s
60+
61+
representing the body twist.
6062

6163
Command interfaces
6264
,,,,,,,,,,,,,,,,,,,

steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -131,7 +131,7 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl
131131
// name constants for reference interfaces
132132
size_t nr_ref_itfs_;
133133

134-
// store last velocity
134+
// last velocity commands for open loop odometry
135135
double last_linear_velocity_ = 0.0;
136136
double last_angular_velocity_ = 0.0;
137137

steering_controllers_library/src/steering_controllers_library.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -324,7 +324,7 @@ SteeringControllersLibrary::on_export_reference_interfaces()
324324
&reference_interfaces_[0]));
325325

326326
reference_interfaces.push_back(hardware_interface::CommandInterface(
327-
get_node()->get_name(), std::string("angular/") + hardware_interface::HW_IF_POSITION,
327+
get_node()->get_name(), std::string("angular/") + hardware_interface::HW_IF_VELOCITY,
328328
&reference_interfaces_[1]));
329329

330330
return reference_interfaces;
@@ -396,7 +396,7 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c
396396

397397
if (!std::isnan(reference_interfaces_[0]) && !std::isnan(reference_interfaces_[1]))
398398
{
399-
// store and set commands
399+
// store (for open loop odometry) and set commands
400400
last_linear_velocity_ = reference_interfaces_[0];
401401
last_angular_velocity_ = reference_interfaces_[1];
402402

steering_controllers_library/test/test_steering_controllers_library.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ TEST_F(SteeringControllersLibraryTest, check_exported_interfaces)
6666
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
6767
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
6868

69-
// check ref itfsTIME
69+
// check ref itfs
7070
auto reference_interfaces = controller_->export_reference_interfaces();
7171
ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size());
7272
for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i)

steering_controllers_library/test/test_steering_controllers_library.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -324,7 +324,7 @@ class SteeringControllersLibraryFixture : public ::testing::Test
324324
std::array<double, 4> joint_state_values_ = {0.5, 0.5, 0.0, 0.0};
325325
std::array<double, 4> joint_command_values_ = {1.1, 3.3, 2.2, 4.4};
326326

327-
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
327+
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
328328
std::string steering_interface_name_ = "position";
329329
// defined in setup
330330
std::string traction_interface_name_ = "";

tricycle_steering_controller/test/test_tricycle_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -285,7 +285,7 @@ class TricycleSteeringControllerFixture : public ::testing::Test
285285

286286
std::array<double, 3> joint_state_values_ = {0.5, 0.5, 0.0};
287287
std::array<double, 3> joint_command_values_ = {1.1, 3.3, 2.2};
288-
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
288+
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
289289
std::string steering_interface_name_ = "position";
290290
// defined in setup
291291
std::string traction_interface_name_ = "";

0 commit comments

Comments
 (0)