cps_loki_description/urdf/odrive.urdf.xacro
2023-06-06 10:53:36 +02:00

34 lines
920 B
XML

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="odrive">
<xacro:arg name="enable_joint0" default="true" />
<xacro:arg name="enable_joint1" default="true" />
<xacro:include filename="$(find odrive_demo_description)/urdf/odrive.ros2_control.xacro" />
<link name="world" />
<xacro:if value="$(arg enable_joint0)">
<link name="link0" />
<joint name="joint0" type="continuous">
<parent link="world" />
<child link="link0" />
<axis xyz="0 0 1" />
</joint>
</xacro:if>
<xacro:if value="$(arg enable_joint1)">
<link name="link1" />
<joint name="joint1" type="continuous">
<parent link="world" />
<child link="link1" />
<axis xyz="0 0 1" />
</joint>
</xacro:if>
<xacro:odrive_ros2_control
name="odrive_ros2_control"
enable_joint0="$(arg enable_joint0)"
enable_joint1="$(arg enable_joint1)" />
</robot>