## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
-find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation)
+find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation urdf)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
--- /dev/null
+<?xml version="1.0"?>
+<robot name="explorer">
+ <link name="base_link">
+ <visual>
+ <geometry>
+ <box size="0.14 0.155 0.085"/>
+ </geometry>
+ <origin xyz="0.06 0 0.0525" rpy="0 0 0"/>
+ <material name="white">
+ <color rgba="1 1 1 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="tail">
+ <visual>
+ <geometry>
+ <box size="0.06 0.09 0.075"/>
+ </geometry>
+ <origin xyz="0 0 0.0525" rpy="0 0 0"/>
+ <material name="red">
+ <color rgba="1 0 0 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="left_wheel">
+ <visual>
+ <geometry>
+ <cylinder radius="0.026" length="0.02"/>
+ </geometry>
+ <material name="black">
+ <color rgba="0 0 0 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="right_wheel">
+ <visual>
+ <geometry>
+ <cylinder radius="0.026" length="0.02"/>
+ </geometry>
+ <material name="black">
+ <color rgba="0 0 0 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="aft_wheel">
+ <visual>
+ <geometry>
+ <cylinder radius="0.01" length="0.02"/>
+ </geometry>
+ <material name="black">
+ <color rgba="0 0 0 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="scan">
+ <visual>
+ <geometry>
+ <box size="0.015 0.045 0.03"/>
+ </geometry>
+ <origin xyz="0.065 0 0.06" rpy="0 0 0"/>
+ <material name="black">
+ <color rgba="0 0 0 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <joint name="tail_joint" type="fixed">
+ <parent link="base_link"/>
+ <child link="tail"/>
+ <origin xyz="-0.04 0 0.005" rpy="0 0 0"/>
+ </joint>
+
+ <joint name="left_wheel_joint" type="fixed">
+ <parent link="base_link"/>
+ <child link="left_wheel"/>
+ <origin xyz="0.07 -0.08 0.026" rpy="1.57 0 0"/>
+ </joint>
+
+ <joint name="right_wheel_joint" type="fixed">
+ <parent link="base_link"/>
+ <child link="right_wheel"/>
+ <origin xyz="0.07 0.08 0.026" rpy="1.57 0 0"/>
+ </joint>
+
+ <joint name="aft_wheel_joint" type="fixed">
+ <parent link="tail"/>
+ <child link="aft_wheel"/>
+ <origin xyz="0 0 0.005" rpy="1.57 0 0"/>
+ </joint>
+
+ <joint name="scan_joint" type="fixed">
+ <parent link="base_link"/>
+ <child link="scan"/>
+ <origin xyz="0.06 0 0" rpy="0 0 0"/>
+ </joint>
+</robot>