Skip to content

Commit

Permalink
Reference interfaces are body twist
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jun 9, 2024
1 parent b245155 commit f4e0859
Show file tree
Hide file tree
Showing 5 changed files with 8 additions and 6 deletions.
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 @@ -131,7 +131,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 @@ -324,7 +324,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 @@ -396,7 +396,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 @@ -324,7 +324,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

0 comments on commit f4e0859

Please sign in to comment.