Commit be8b7f65 authored by Günter Niemeyer's avatar Günter Niemeyer
Browse files

Created two URDFS: For camera over wheels or over caster

The uses two distinct URDF files and distinct mesh files to create two
bots: (a) bot_front_wheels.urdf and bot_front_caster.urdf.  The camera
is always in front, but the bot direction is inherently reversed.

It also includes two demo launch files: display_front_wheels.launch
and display_front_caster.launch to show the two options.

Finally, the URDF files include the frames for the depth camera and
artificial laser scaner, so we can process the camera data correctly.

Note the depth camera angle is calibrated to 20deg (using the depth
camera to make a vertical object appear vertical).  Hopefully the
angle is consistent between all bots.
parent c2a25085
Showing with 218 additions and 115 deletions
+218 -115
File deleted
......@@ -24,5 +24,6 @@
type="rviz"
name="rviz"
args="-d $(arg cfg)"
output="screen"/>
output="screen"
required="true"/>
</launch>
<launch>
<include file="$(find bot_description)/launch/display.launch">
<arg name="urdf" value="bot_front_caster.urdf"/>
</include>
</launch>
<launch>
<include file="$(find bot_description)/launch/display.launch">
<arg name="urdf" value="bot_front_wheels.urdf"/>
</include>
</launch>
File deleted
File added
File added
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was modified from an auto-created version by SolidWorks to URDF Exporter -->
<robot name="simpleURDF">
<link name="base">
<visual>
<origin xyz="-0.04875 0 0.04" rpy="0 0 0"/>
<geometry>
<mesh
filename="package://bot_description/meshes/base.stl" />
</geometry>
<material name="">
<color rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
</link>
<joint name="leftwheeljoint" type="fixed">
<origin xyz="0 0.065 0.03" rpy="-1.5708 0 0"/>
<parent link="base"/>
<child link="leftwheel"/>
</joint>
<link name="leftwheel">
<visual>
<origin xyz="0 0 -0.01750" rpy="3.1416 0 0"/>
<geometry>
<mesh
filename="package://bot_description/meshes/wheel.stl" />
</geometry>
<material name="">
<color rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
</link>
<joint name="rightwheeljoint" type="fixed">
<origin xyz="0 -0.065 0.03" rpy="1.5708 0 0"/>
<parent link="base"/>
<child link="rightwheel"/>
</joint>
<link name="rightwheel">
<visual>
<origin xyz="0 0 -0.01750" rpy="3.1416 0 0"/>
<geometry>
<mesh
filename="package://bot_description/meshes/wheel.stl" />
</geometry>
<material name="">
<color rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
</link>
</robot>
bot_front_wheels.urdf
\ No newline at end of file
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF describes the ME/CS/EE 129 bot, -->
<!-- with the front edge at the big wheels! -->
<robot name="bot">
<!-- Pick the colors -->
<material name="body"> <color rgba="0.79 0.82 0.93 1"/> </material>
<material name="wheel"> <color rgba="0.39 0.41 0.46 1"/> </material>
<!-- The base is the midpoint between the wheels on the ground -->
<link name="base"/>
<!-- Move up to the wheel axle (midway between the wheels) -->
<!-- This is where the body STL is anchored -->
<joint name="basetoaxle" type="fixed">
<parent link="base"/>
<child link="axle"/>
<origin xyz="0 0 0.03" rpy="0 0 0"/>
</joint>
<link name="axle">
<visual>
<origin xyz="0 0 0" rpy="0 0 3.1416"/>
<geometry>
<mesh
filename="package://bot_description/meshes/body_front_caster.stl" />
</geometry>
<material name="body"/>
</visual>
</link>
<!-- Left wheel -->
<joint name="leftwheeljoint" type="fixed">
<parent link="axle"/>
<child link="leftwheel"/>
<origin xyz="0 0.065 0" rpy="-1.5708 0 0"/>
</joint>
<link name="leftwheel">
<visual>
<origin xyz="0 0 -0.01750" rpy="3.1416 0 0"/>
<geometry>
<mesh
filename="package://bot_description/meshes/wheel.stl" />
</geometry>
<material name="wheel"/>
</visual>
</link>
<!-- Right wheel -->
<joint name="rightwheeljoint" type="fixed">
<parent link="axle"/>
<child link="rightwheel"/>
<origin xyz="0 -0.065 0" rpy="1.5708 0 0"/>
</joint>
<link name="rightwheel">
<visual>
<origin xyz="0 0 -0.01750" rpy="3.1416 0 0"/>
<geometry>
<mesh
filename="package://bot_description/meshes/wheel.stl" />
</geometry>
<material name="wheel"/>
</visual>
</link>
<!-- Camera Plate (frame on camera's front plate) -->
<!-- The plate is 0.10183 in front of center of body, -->
<!-- which is 0.04875 in front of the wheel axle. -->
<!-- So shifted 0.15058 in front of the wheel axle. -->
<!-- Also Shifted 0.03633 above the wheel axle. -->
<!-- And turned 20deg up! -->
<joint name="axletocameraplate" type="fixed">
<parent link="axle"/>
<child link="cameraplate"/>
<origin xyz="0.15058 0 0.03633" rpy="0 -0.35 0"/>
</joint>
<link name="cameraplate"/>
<!-- Camera Origin (of Depth Camera, used by RealSense) -->
<!-- Shifted 17.5mm left, 4.2mm back -->
<joint name="camerainternaloffset" type="fixed">
<parent link="cameraplate"/>
<child link="camera_link"/>
<origin xyz="-0.00420 0.01750 0" rpy="0 0 0"/>
</joint>
<link name="camera_link"/>
<!-- Laser scanner (placed at camera but horizontal) -->
<joint name="cameratolaser" type="fixed">
<parent link="camera_link"/>
<child link="laser"/>
<origin xyz="0 0 0" rpy="0 0.35 0"/>
</joint>
<link name="laser"/>
</robot>
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF describes the ME/CS/EE 129 bot, -->
<!-- with the front edge at the big wheels! -->
<robot name="bot">
<!-- Pick the colors -->
<material name="body"> <color rgba="0.79 0.82 0.93 1"/> </material>
<material name="wheel"> <color rgba="0.39 0.41 0.46 1"/> </material>
<!-- The base is the midpoint between the wheels on the ground -->
<link name="base"/>
<!-- Move up to the wheel axle (midway between the wheels) -->
<!-- This is where the body STL is anchored -->
<joint name="basetoaxle" type="fixed">
<parent link="base"/>
<child link="axle"/>
<origin xyz="0 0 0.03" rpy="0 0 0"/>
</joint>
<link name="axle">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh
filename="package://bot_description/meshes/body_front_wheels.stl" />
</geometry>
<material name="body"/>
</visual>
</link>
<!-- Left wheel -->
<joint name="leftwheeljoint" type="fixed">
<parent link="axle"/>
<child link="leftwheel"/>
<origin xyz="0 0.065 0" rpy="-1.5708 0 0"/>
</joint>
<link name="leftwheel">
<visual>
<origin xyz="0 0 -0.01750" rpy="3.1416 0 0"/>
<geometry>
<mesh
filename="package://bot_description/meshes/wheel.stl" />
</geometry>
<material name="wheel"/>
</visual>
</link>
<!-- Right wheel -->
<joint name="rightwheeljoint" type="fixed">
<parent link="axle"/>
<child link="rightwheel"/>
<origin xyz="0 -0.065 0" rpy="1.5708 0 0"/>
</joint>
<link name="rightwheel">
<visual>
<origin xyz="0 0 -0.01750" rpy="3.1416 0 0"/>
<geometry>
<mesh
filename="package://bot_description/meshes/wheel.stl" />
</geometry>
<material name="wheel"/>
</visual>
</link>
<!-- Camera Plate (frame on camera's front plate) -->
<!-- The plate is 0.10183 in front of center of body, -->
<!-- which is -0.04875 behind the wheel axle. -->
<!-- So shifted 0.05308 in front of the wheel axle. -->
<!-- Also Shifted 0.03633 above the wheel axle. -->
<!-- And turned 20deg up! -->
<joint name="axletocameraplate" type="fixed">
<parent link="axle"/>
<child link="cameraplate"/>
<origin xyz="0.05308 0 0.03633" rpy="0 -0.35 0"/>
</joint>
<link name="cameraplate"/>
<!-- Camera Origin (of Depth Camera, used by RealSense) -->
<!-- Shifted 17.5mm left, 4.2mm back -->
<joint name="camerainternaloffset" type="fixed">
<parent link="cameraplate"/>
<child link="camera_link"/>
<origin xyz="-0.00420 0.01750 0" rpy="0 0 0"/>
</joint>
<link name="camera_link"/>
<!-- Laser scanner (placed at camera but horizontal) -->
<joint name="cameratolaser" type="fixed">
<parent link="camera_link"/>
<child link="laser"/>
<origin xyz="0 0 0" rpy="0 0.35 0"/>
</joint>
<link name="laser"/>
</robot>
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment