123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192 |
- <?xml version="1.0"?>
- <robot name="mecanum_robot" xmlns:xacro="http://ros.org/wiki/xacro">
- <property name="M_PI" value="3.14159"/>
-
- <!-- Macro for mecanum_robot body. Including Gazebo extensions, but does not include lidar -->
- <include filename="$(find gazebo_robot)/urdf/gazebo.urdf.xacro"/>
-
- <property name="base_x" value="0.33" />
- <property name="base_y" value="0.33" />
-
- <xacro:macro name="mecanum_robot_body">
-
-
- <link name="base_link">
- <inertial>
- <origin xyz="0 0 0.055"/>
- <mass value="100.0" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- <visual>
- <geometry>
- <box size="0.25 .16 .05"/>
- </geometry>
- <origin rpy="0 0 0" xyz="0 0 0.055"/>
- <material name="blue">
- <color rgba="0 0 .8 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0 0 0" xyz="0 0 0.055"/>
- <geometry>
- <box size="0.25 .16 .05" />
- </geometry>
- </collision>
- </link>
-
-
- <link name="left_front_wheel">
- <inertial>
- <origin xyz="0.08 0.08 0.025"/>
- <mass value="1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- <visual>
- <geometry>
- <cylinder length=".02" radius="0.025"/>
- </geometry>
- <material name="black">
- <color rgba="0 0 0 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0 1.57075 1.57075" xyz="0.08 0.08 0.025"/>
- <geometry>
- <cylinder length=".02" radius="0.025"/>
- </geometry>
- </collision>
- </link>
-
- <joint name="left_front_wheel_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="base_link"/>
- <child link="left_front_wheel"/>
- <origin rpy="0 1.57075 1.57075" xyz="0.08 0.08 0.025"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
- <link name="right_front_wheel">
- <inertial>
- <origin xyz="0.08 -0.08 0.025"/>
- <mass value="1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- <visual>
- <geometry>
- <cylinder length=".02" radius="0.025"/>
- </geometry>
- <material name="black">
- <color rgba="0 0 0 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0 1.57075 1.57075" xyz="0.08 -0.08 0.025"/>
- <geometry>
- <cylinder length=".02" radius="0.025"/>
- </geometry>
- </collision>
- </link>
-
- <joint name="right_front_wheel_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="base_link"/>
- <child link="right_front_wheel"/>
- <origin rpy="0 1.57075 1.57075" xyz="0.08 -0.08 0.025"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
- <link name="left_back_wheel">
- <inertial>
- <origin xyz="-0.08 0.08 0.025"/>
- <mass value="1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- <visual>
- <geometry>
- <cylinder length=".02" radius="0.025"/>
- </geometry>
- <material name="black">
- <color rgba="0 0 0 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0 1.57075 1.57075" xyz="-0.08 0.08 0.025"/>
- <geometry>
- <cylinder length=".02" radius="0.025"/>
- </geometry>
- </collision>
- </link>
-
- <joint name="left_back_wheel_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="base_link"/>
- <child link="left_back_wheel"/>
- <origin rpy="0 1.57075 1.57075" xyz="-0.08 0.08 0.025"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
- <link name="right_back_wheel">
- <inertial>
- <origin xyz="-0.08 -0.08 0.025"/>
- <mass value="1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- <visual>
- <geometry>
- <cylinder length=".02" radius="0.025"/>
- </geometry>
- <material name="black">
- <color rgba="0 0 0 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0 1.57075 1.57075" xyz="-0.08 -0.08 0.025"/>
- <geometry>
- <cylinder length=".02" radius="0.025"/>
- </geometry>
- </collision>
- </link>
-
-
- <joint name="right_back_wheel_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="base_link"/>
- <child link="right_back_wheel"/>
- <origin rpy="0 1.57075 1.57075" xyz="-0.08 -0.08 0.025"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
- <link name="head">
- <inertial>
- <origin xyz="0.08 0 0.08"/>
- <mass value="1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- <visual>
- <geometry>
- <box size=".02 .03 .03"/>
- </geometry>
- <material name="white">
- <color rgba="1 1 1 1"/>
- </material>
- </visual>
- <collision>
- <origin xyz="0.08 0 0.08"/>
- <geometry>
- <cylinder length=".02" radius="0.025"/>
- </geometry>
- </collision>
- </link>
-
- <joint name="tobox" type="fixed">
- <parent link="base_link"/>
- <child link="head"/>
- <origin xyz="0.08 0 0.08"/>
- </joint>
- </xacro:macro>
-
- </robot>
|