Last active
December 23, 2021 18:03
-
-
Save mintar/5d8e60a145ec80643d3ea82544c2c233 to your computer and use it in GitHub Desktop.
Example URDF for diff_drive_controller, see https://answers.ros.org/question/300763/is-it-necessary-to-have-urdf-model-for-diff_drive_controller/
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0" ?> | |
<robot name="mir_100" xmlns:xacro="http://ros.org/wiki/xacro"> | |
<link name="base_footprint"/> | |
<joint name="base_joint" type="fixed"> | |
<parent link="base_footprint"/> | |
<child link="base_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
</joint> | |
<link name="base_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0.037646 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/mir_100_base.stl"/> | |
</geometry> | |
<material name="white"> | |
<color rgba="1 1 1 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0.037646 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/collision/mir_100_base.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<joint name="left_wheel_joint" type="continuous"> | |
<origin rpy="0 0 0" xyz="0.0 0.222604 0.0625"/> | |
<parent link="base_link"/> | |
<child link="left_wheel_link"/> | |
<axis xyz="0 1 0"/> | |
</joint> | |
<link name="left_wheel_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
<material name="dark_grey"> | |
<color rgba="0.3 0.3 0.3 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<joint name="right_wheel_joint" type="continuous"> | |
<origin rpy="0 0 0" xyz="0.0 -0.222604 0.0625"/> | |
<parent link="base_link"/> | |
<child link="right_wheel_link"/> | |
<axis xyz="0 1 0"/> | |
</joint> | |
<link name="right_wheel_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
<material name="dark_grey"> | |
<color rgba="0.3 0.3 0.3 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<!-- caster hub --> | |
<joint name="fl_caster_rotation_joint" type="continuous"> | |
<origin rpy="0 0 0" xyz="0.341346 0.203 0.1565"/> | |
<parent link="base_link"/> | |
<child link="fl_caster_rotation_link"/> | |
<axis xyz="0 0 1"/> | |
<dynamics damping="0.01" friction="0.0"/> | |
</joint> | |
<link name="fl_caster_rotation_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/caster_wheel_base.stl"/> | |
</geometry> | |
<material name="silver"> | |
<color rgba="0.79 0.82 0.93 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/collision/caster_wheel_base.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<!-- caster wheel --> | |
<joint name="fl_caster_wheel_joint" type="continuous"> | |
<origin rpy="0 0 0" xyz="-0.0382 0 -0.094"/> | |
<parent link="fl_caster_rotation_link"/> | |
<child link="fl_caster_wheel_link"/> | |
<axis xyz="0 1 0"/> | |
</joint> | |
<link name="fl_caster_wheel_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
<material name="dark_grey"> | |
<color rgba="0.3 0.3 0.3 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<!-- caster hub --> | |
<joint name="fr_caster_rotation_joint" type="continuous"> | |
<origin rpy="0 0 0" xyz="0.341346 -0.203 0.1565"/> | |
<parent link="base_link"/> | |
<child link="fr_caster_rotation_link"/> | |
<axis xyz="0 0 1"/> | |
<dynamics damping="0.01" friction="0.0"/> | |
</joint> | |
<link name="fr_caster_rotation_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/caster_wheel_base.stl"/> | |
</geometry> | |
<material name="silver"> | |
<color rgba="0.79 0.82 0.93 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/collision/caster_wheel_base.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<!-- caster wheel --> | |
<joint name="fr_caster_wheel_joint" type="continuous"> | |
<origin rpy="0 0 0" xyz="-0.0382 0 -0.094"/> | |
<parent link="fr_caster_rotation_link"/> | |
<child link="fr_caster_wheel_link"/> | |
<axis xyz="0 1 0"/> | |
</joint> | |
<link name="fr_caster_wheel_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
<material name="dark_grey"> | |
<color rgba="0.3 0.3 0.3 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<!-- caster hub --> | |
<joint name="bl_caster_rotation_joint" type="continuous"> | |
<origin rpy="0 0 0" xyz="-0.270154 0.203 0.1565"/> | |
<parent link="base_link"/> | |
<child link="bl_caster_rotation_link"/> | |
<axis xyz="0 0 1"/> | |
<dynamics damping="0.01" friction="0.0"/> | |
</joint> | |
<link name="bl_caster_rotation_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/caster_wheel_base.stl"/> | |
</geometry> | |
<material name="silver"> | |
<color rgba="0.79 0.82 0.93 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/collision/caster_wheel_base.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<!-- caster wheel --> | |
<joint name="bl_caster_wheel_joint" type="continuous"> | |
<origin rpy="0 0 0" xyz="-0.0382 0 -0.094"/> | |
<parent link="bl_caster_rotation_link"/> | |
<child link="bl_caster_wheel_link"/> | |
<axis xyz="0 1 0"/> | |
</joint> | |
<link name="bl_caster_wheel_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
<material name="dark_grey"> | |
<color rgba="0.3 0.3 0.3 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<!-- caster hub --> | |
<joint name="br_caster_rotation_joint" type="continuous"> | |
<origin rpy="0 0 0" xyz="-0.270154 -0.203 0.1565"/> | |
<parent link="base_link"/> | |
<child link="br_caster_rotation_link"/> | |
<axis xyz="0 0 1"/> | |
<dynamics damping="0.01" friction="0.0"/> | |
</joint> | |
<link name="br_caster_rotation_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/caster_wheel_base.stl"/> | |
</geometry> | |
<material name="silver"> | |
<color rgba="0.79 0.82 0.93 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/collision/caster_wheel_base.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<!-- caster wheel --> | |
<joint name="br_caster_wheel_joint" type="continuous"> | |
<origin rpy="0 0 0" xyz="-0.0382 0 -0.094"/> | |
<parent link="br_caster_rotation_link"/> | |
<child link="br_caster_wheel_link"/> | |
<axis xyz="0 1 0"/> | |
</joint> | |
<link name="br_caster_wheel_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
<material name="dark_grey"> | |
<color rgba="0.3 0.3 0.3 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://mir_description/meshes/visual/wheel.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<transmission name="left_wheel_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="left_wheel_joint"> | |
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="left_wheel_motor"> | |
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<transmission name="right_wheel_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="right_wheel_joint"> | |
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="right_wheel_motor"> | |
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
</transmission> | |
</robot> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment