diff --git a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp index e52715604c1..eadca397561 100644 --- a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp +++ b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp @@ -128,18 +128,18 @@ class TestControllerChainingWithControllerManager // configure Left Wheel controller controller_interface::InterfaceConfiguration pid_left_cmd_ifs_cfg = { - controller_interface::interface_configuration_type::INDIVIDUAL, {"wheel_0_joint/velocity"}}; + controller_interface::interface_configuration_type::INDIVIDUAL, {"wheel_left/velocity"}}; controller_interface::InterfaceConfiguration pid_left_state_ifs_cfg = { - controller_interface::interface_configuration_type::INDIVIDUAL, {"wheel_0_joint/velocity"}}; + controller_interface::interface_configuration_type::INDIVIDUAL, {"wheel_left/velocity"}}; pid_left_wheel_controller->set_command_interface_configuration(pid_left_cmd_ifs_cfg); pid_left_wheel_controller->set_state_interface_configuration(pid_left_state_ifs_cfg); pid_left_wheel_controller->set_reference_interface_names({"velocity"}); // configure Left Wheel controller controller_interface::InterfaceConfiguration pid_right_cmd_ifs_cfg = { - controller_interface::interface_configuration_type::INDIVIDUAL, {"wheel_1_joint/velocity"}}; + controller_interface::interface_configuration_type::INDIVIDUAL, {"wheel_right/velocity"}}; controller_interface::InterfaceConfiguration pid_right_state_ifs_cfg = { - controller_interface::interface_configuration_type::INDIVIDUAL, {"wheel_1_joint/velocity"}}; + controller_interface::interface_configuration_type::INDIVIDUAL, {"wheel_right/velocity"}}; pid_right_wheel_controller->set_command_interface_configuration(pid_right_cmd_ifs_cfg); pid_right_wheel_controller->set_state_interface_configuration(pid_right_state_ifs_cfg); pid_right_wheel_controller->set_reference_interface_names({"velocity"}); @@ -150,7 +150,7 @@ class TestControllerChainingWithControllerManager {std::string(PID_LEFT_WHEEL) + "/velocity", std::string(PID_RIGHT_WHEEL) + "/velocity"}}; controller_interface::InterfaceConfiguration diff_drive_state_ifs_cfg = { controller_interface::interface_configuration_type::INDIVIDUAL, - {"wheel_0_joint/velocity", "wheel_1_joint/velocity"}}; + {"wheel_left/velocity", "wheel_right/velocity"}}; diff_drive_controller->set_command_interface_configuration(diff_drive_cmd_ifs_cfg); diff_drive_controller->set_state_interface_configuration(diff_drive_state_ifs_cfg); diff_drive_controller->set_reference_interface_names({"vel_x", "vel_y", "rot_z"}); @@ -435,8 +435,8 @@ class TestControllerChainingWithControllerManager const std::vector DIFF_DRIVE_REFERENCE_INTERFACES = { "diff_drive_controller/vel_x", "diff_drive_controller/vel_y", "diff_drive_controller/rot_z"}; - const std::vector PID_LEFT_WHEEL_CLAIMED_INTERFACES = {"wheel_0_joint/velocity"}; - const std::vector PID_RIGHT_WHEEL_CLAIMED_INTERFACES = {"wheel_1_joint/velocity"}; + const std::vector PID_LEFT_WHEEL_CLAIMED_INTERFACES = {"wheel_left/velocity"}; + const std::vector PID_RIGHT_WHEEL_CLAIMED_INTERFACES = {"wheel_right/velocity"}; const std::vector DIFF_DRIVE_CLAIMED_INTERFACES = { "pid_left_wheel_controller/velocity", "pid_right_wheel_controller/velocity"}; const std::vector POSITION_CONTROLLER_CLAIMED_INTERFACES = { diff --git a/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp b/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp index 7c66aed94cb..c71b5d70a12 100644 --- a/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp +++ b/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp @@ -498,16 +498,16 @@ const auto diffbot_urdf = - + - - - + + + 1 1 @@ -533,16 +533,16 @@ const auto diffbot_urdf = - + - - - + + + 1 1 @@ -560,7 +560,7 @@ const auto diffbot_urdf = test_actuator - + @@ -570,7 +570,7 @@ const auto diffbot_urdf = test_actuator - +