Skip to content

Fix: Disable Platform Controllers in Manipulator Controllers #239

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 1 commit into from
Jul 17, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
63 changes: 33 additions & 30 deletions clearpath_platform_description/urdf/do100/do100.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<xacro:arg name="namespace" default="" />
<xacro:arg name="is_sim" default="false" />
<xacro:arg name="gazebo_controllers" default="$(find clearpath_control)/config/do100/control.yaml"/>
<xacro:arg name="use_platform_controllers" default="true"/>

<!-- Included URDF/Xacro Files -->
<xacro:include filename="$(find clearpath_platform_description)/urdf/do100/wheels/wheel.urdf.xacro"/>
Expand Down Expand Up @@ -185,36 +186,38 @@
<xacro:include filename="$(find clearpath_platform_description)/urdf/generic/gazebo.urdf.xacro"/>

<!-- ROS2 controls -->
<ros2_control name="do100_hardware" type="system">
<hardware>
<xacro:if value="$(arg is_sim)">
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</xacro:if>
<xacro:unless value="$(arg is_sim)">
<plugin>clearpath_hardware_interfaces/PumaHardware</plugin>
</xacro:unless>
</hardware>
<joint name="front_left_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="front_right_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="rear_left_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="rear_right_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
<xacro:if value="$(arg use_platform_controllers)">
<ros2_control name="do100_hardware" type="system">
<hardware>
<xacro:if value="$(arg is_sim)">
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</xacro:if>
<xacro:unless value="$(arg is_sim)">
<plugin>clearpath_hardware_interfaces/PumaHardware</plugin>
</xacro:unless>
</hardware>
<joint name="front_left_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="front_right_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="rear_left_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="rear_right_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
</xacro:if>
</xacro:macro>

<!-- Joint State Publisher -->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<xacro:arg name="namespace" default="" />
<xacro:arg name="is_sim" default="false" />
<xacro:arg name="gazebo_controllers" default="$(find clearpath_control)/config/do150/control.yaml"/>
<xacro:arg name="use_platform_controllers" default="true"/>

<!-- Included URDF/Xacro Files -->
<xacro:include filename="$(find clearpath_platform_description)/urdf/do100/do100.urdf.xacro"/>
Expand Down
63 changes: 33 additions & 30 deletions clearpath_platform_description/urdf/r100/r100.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<xacro:arg name="namespace" default="" />
<xacro:arg name="is_sim" default="false" />
<xacro:arg name="gazebo_controllers" default="$(find clearpath_control)/config/r100/control.yaml"/>
<xacro:arg name="use_platform_controllers" default="true"/>

<!-- Includes -->
<xacro:include filename="$(find clearpath_platform_description)/urdf/r100/wheels/wheel.urdf.xacro"/>
Expand Down Expand Up @@ -296,36 +297,38 @@
<xacro:include filename="$(find clearpath_platform_description)/urdf/generic/gazebo.urdf.xacro"/>

<!-- ROS2 controls -->
<ros2_control name="r100_hardware" type="system">
<hardware>
<xacro:if value="$(arg is_sim)">
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</xacro:if>
<xacro:unless value="$(arg is_sim)">
<plugin>clearpath_hardware_interfaces/PumaHardware</plugin>
</xacro:unless>
</hardware>
<joint name="front_left_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="front_right_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="rear_left_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="rear_right_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
<xacro:if value="$(arg use_platform_controllers)">
<ros2_control name="r100_hardware" type="system">
<hardware>
<xacro:if value="$(arg is_sim)">
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</xacro:if>
<xacro:unless value="$(arg is_sim)">
<plugin>clearpath_hardware_interfaces/PumaHardware</plugin>
</xacro:unless>
</hardware>
<joint name="front_left_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="front_right_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="rear_left_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="rear_right_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
</xacro:if>

</xacro:macro>
</robot>