Skip to content

Commit 286aa23

Browse files
christophfroehlichmergify[bot]
authored andcommitted
[Steering controllers library] Reference interfaces are body twist (#1168)
(cherry picked from commit 6155248)
1 parent 36ce104 commit 286aa23

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

+1-1
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

+1-1
Original file line numberDiff line numberDiff line change
@@ -301,7 +301,7 @@ class AckermannSteeringControllerFixture : public ::testing::Test
301301

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

bicycle_steering_controller/test/test_bicycle_steering_controller.cpp

+1-1
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

+1-1
Original file line numberDiff line numberDiff line change
@@ -265,7 +265,7 @@ class BicycleSteeringControllerFixture : public ::testing::Test
265265

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

271271
// defined in setup

steering_controllers_library/doc/userdoc.rst

+3-1
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

+1-1
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,7 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl
132132
// name constants for reference interfaces
133133
size_t nr_ref_itfs_;
134134

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

steering_controllers_library/src/steering_controllers_library.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -373,7 +373,7 @@ SteeringControllersLibrary::on_export_reference_interfaces()
373373
&reference_interfaces_[0]));
374374

375375
reference_interfaces.push_back(hardware_interface::CommandInterface(
376-
get_node()->get_name(), std::string("angular/") + hardware_interface::HW_IF_POSITION,
376+
get_node()->get_name(), std::string("angular/") + hardware_interface::HW_IF_VELOCITY,
377377
&reference_interfaces_[1]));
378378

379379
return reference_interfaces;
@@ -445,7 +445,7 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c
445445

446446
if (!std::isnan(reference_interfaces_[0]) && !std::isnan(reference_interfaces_[1]))
447447
{
448-
// store and set commands
448+
// store (for open loop odometry) and set commands
449449
last_linear_velocity_ = reference_interfaces_[0];
450450
last_angular_velocity_ = reference_interfaces_[1];
451451

steering_controllers_library/test/test_steering_controllers_library.cpp

+1-1
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

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

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

tricycle_steering_controller/test/test_tricycle_steering_controller.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -284,7 +284,7 @@ class TricycleSteeringControllerFixture : public ::testing::Test
284284

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

0 commit comments

Comments
 (0)