Skip to content

Commit

Permalink
Rename wheel_0/1 to wheel_left/right
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Feb 1, 2024
1 parent d85af80 commit df937b9
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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"});
Expand All @@ -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"});
Expand Down Expand Up @@ -435,8 +435,8 @@ class TestControllerChainingWithControllerManager
const std::vector<std::string> DIFF_DRIVE_REFERENCE_INTERFACES = {
"diff_drive_controller/vel_x", "diff_drive_controller/vel_y", "diff_drive_controller/rot_z"};

const std::vector<std::string> PID_LEFT_WHEEL_CLAIMED_INTERFACES = {"wheel_0_joint/velocity"};
const std::vector<std::string> PID_RIGHT_WHEEL_CLAIMED_INTERFACES = {"wheel_1_joint/velocity"};
const std::vector<std::string> PID_LEFT_WHEEL_CLAIMED_INTERFACES = {"wheel_left/velocity"};
const std::vector<std::string> PID_RIGHT_WHEEL_CLAIMED_INTERFACES = {"wheel_right/velocity"};
const std::vector<std::string> DIFF_DRIVE_CLAIMED_INTERFACES = {
"pid_left_wheel_controller/velocity", "pid_right_wheel_controller/velocity"};
const std::vector<std::string> POSITION_CONTROLLER_CLAIMED_INTERFACES = {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -498,16 +498,16 @@ const auto diffbot_urdf =
</geometry>
</collision>
</link>
<joint name="wheel_0_joint" type="continuous">
<joint name="wheel_left" type="continuous">
<parent link="base_link"/>
<child link="wheel_0_link"/>
<origin rpy="-1.5707963267948966 0 0" xyz="0.3 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<!-- Transmission is important to link the joints and the controller -->
<transmission name="wheel_0_joint_trans" type="SimpleTransmission">
<actuator name="wheel_0_joint_motor"/>
<joint name="wheel_0_joint"/>
<transmission name="wheel_left_trans" type="SimpleTransmission">
<actuator name="wheel_left_motor"/>
<joint name="wheel_left"/>
<mechanicalReduction>1</mechanicalReduction>
<motorTorqueConstant>1</motorTorqueConstant>
</transmission>
Expand All @@ -533,16 +533,16 @@ const auto diffbot_urdf =
</geometry>
</collision>
</link>
<joint name="wheel_1_joint" type="continuous">
<joint name="wheel_right" type="continuous">
<parent link="base_link"/>
<child link="wheel_1_link"/>
<origin rpy="-1.5707963267948966 0 0" xyz="-0.2 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<!-- Transmission is important to link the joints and the controller -->
<transmission name="wheel_1_joint_trans" type="SimpleTransmission">
<actuator name="wheel_1_joint_motor"/>
<joint name="wheel_1_joint"/>
<transmission name="wheel_right_trans" type="SimpleTransmission">
<actuator name="wheel_right_motor"/>
<joint name="wheel_right"/>
<mechanicalReduction>1</mechanicalReduction>
<motorTorqueConstant>1</motorTorqueConstant>
</transmission>
Expand All @@ -560,7 +560,7 @@ const auto diffbot_urdf =
<hardware>
<plugin>test_actuator</plugin>
</hardware>
<joint name="wheel_0_joint">
<joint name="wheel_left">
<state_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="velocity"/>
Expand All @@ -570,7 +570,7 @@ const auto diffbot_urdf =
<hardware>
<plugin>test_actuator</plugin>
</hardware>
<joint name="wheel_1_joint">
<joint name="wheel_right">
<state_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="velocity"/>
Expand Down

0 comments on commit df937b9

Please sign in to comment.