Skip to content

Commit

Permalink
[Steering controllers library] Reference interfaces are body twist (#…
Browse files Browse the repository at this point in the history
…1168) (#1174)

(cherry picked from commit 6155248)

Co-authored-by: Christoph Fröhlich <christophfroehlich@users.noreply.github.com>
  • Loading branch information
mergify[bot] and christophfroehlich committed Jun 19, 2024
1 parent 3005fea commit bb02f1c
Show file tree
Hide file tree
Showing 10 changed files with 13 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfsTIME
// check ref itfs
auto reference_interfaces = controller_->export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size());
for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,7 @@ class AckermannSteeringControllerFixture : public ::testing::Test

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<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
std::string steering_interface_name_ = "position";
// defined in setup
std::string traction_interface_name_ = "";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ TEST_F(BicycleSteeringControllerTest, check_exported_interfaces)
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfsTIME
// check ref itfs
auto reference_interfaces = controller_->export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size());
for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ class BicycleSteeringControllerFixture : public ::testing::Test

std::array<double, 2> joint_state_values_ = {3.3, 0.5};
std::array<double, 2> joint_command_values_ = {1.1, 2.2};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
std::string steering_interface_name_ = "position";

// defined in setup
Expand Down
4 changes: 3 additions & 1 deletion steering_controllers_library/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,9 @@ References (from a preceding controller)
Used when controller is in chained mode (``in_chained_mode == true``).

- ``<controller_name>/linear/velocity`` double, in m/s
- ``<controller_name>/angular/position`` double, in rad
- ``<controller_name>/angular/velocity`` double, in rad/s

representing the body twist.

Command interfaces
,,,,,,,,,,,,,,,,,,,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl
// name constants for reference interfaces
size_t nr_ref_itfs_;

// store last velocity
// last velocity commands for open loop odometry
double last_linear_velocity_ = 0.0;
double last_angular_velocity_ = 0.0;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -373,7 +373,7 @@ SteeringControllersLibrary::on_export_reference_interfaces()
&reference_interfaces_[0]));

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

return reference_interfaces;
Expand Down Expand Up @@ -445,7 +445,7 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c

if (!std::isnan(reference_interfaces_[0]) && !std::isnan(reference_interfaces_[1]))
{
// store and set commands
// store (for open loop odometry) and set commands
last_linear_velocity_ = reference_interfaces_[0];
last_angular_velocity_ = reference_interfaces_[1];

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ TEST_F(SteeringControllersLibraryTest, check_exported_interfaces)
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfsTIME
// check ref itfs
auto reference_interfaces = controller_->export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size());
for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -323,7 +323,7 @@ class SteeringControllersLibraryFixture : public ::testing::Test
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<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
std::string steering_interface_name_ = "position";
// defined in setup
std::string traction_interface_name_ = "";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,7 @@ class TricycleSteeringControllerFixture : public ::testing::Test

std::array<double, 3> joint_state_values_ = {0.5, 0.5, 0.0};
std::array<double, 3> joint_command_values_ = {1.1, 3.3, 2.2};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
std::string steering_interface_name_ = "position";
// defined in setup
std::string traction_interface_name_ = "";
Expand Down

0 comments on commit bb02f1c

Please sign in to comment.