This is where the next level modeling stuff is going. This will provide the ability for the model parts to work in RVIZ and Gazebo simulations and working with input for control within the simulations.
Originally, this was going to be a how-to on teleoperations with a joystick. Unfortunately, the joystick I have doesn't seem to be working. My guess is that the USB to joystick port isn't right for the model joystick, or the joystick itself is broken. On a positive note, I discovered that my laptop has a built in gyroscope that operates on js0 in linux. So, that's a no-go on the joystick teleop.
The new and improved modeling format for ROS is xacro. It allows for macros to be integrated into the model language and should make the code a little bit easier to read. For the conversion from the simpler URDF to the xacro model I used the examples from http://moorerobots.com/ . As I described in the Rant About ROS Books, this website does a really good job making ROS easier to learn.
Because I used the website's models as a template, I could simply modify what was there to make the conversion process easier.
Thank you, Mr. Wang.
These are the simulation programs I hope to use. Gazebo (left) and Rviz (right)
The files covered in this section will be hosted on github. That's right, I learned how to use github! For now, the most up to date files will be here: https://github.com/matrhint/model-problems . The files on this google site will not be as functional as the ones on the github page--As the files start to approach the "as good as I am going to do limit," I will change the github page to something that reflects the robot lawnmower. But for now and everyone not familiar to github, here is what the program files look like. Beware: errrors ahead.
The first file is lawnmow.xacro:
<?xml version='1.0'?>
<robot name="lawnmow" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="cameraSize" value="0.05"/>
<xacro:property name="cameraMass" value="0.1"/>
<xacro:include filename="$(find lawnmow_description)/urdf/lawnmow.gazebo" />
<xacro:include filename="$(find lawnmow_description)/urdf/materials.xacro" />
<xacro:include filename="$(find lawnmow_description)/urdf/macros.xacro" />
<link name='chassis'>
<pose>0 0 0.1 0 0 0</pose>
<inertial>
<mass value="10.0"/>
<origin xyz="0.0 0 0.1" rpy=" 0 0 0"/>
<inertia
ixx="1.0" ixy="0" ixz="0"
iyy="1.0" iyz="0"
izz="1.0"
/>
</inertial>
<collision name='collision'>
<geometry>
<box size="0.657359 0.4441 0.085"/>
</geometry>
</collision>
<visual name='chassis_visual'>
<origin xyz="0 0 0" rpy=" 1.58 0 0"/>
<geometry>
<mesh scale=".0010 .0010 .0010" filename="package://lawnmow_description/meshes/frame.stl"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
</link>
<link name="lfcaster">
<collision name='lfcollision'>
<origin xyz="-0.4 0.605 .35" rpy="1.58 0 0"/>
<geometry>
<cylinder radius="0.167022" length="0.07"/>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1</slip1>
<slip2>1</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='lfcaster_visual'>
<origin xyz="0 0 0" rpy="0 -1.55 0"/>
<geometry>
<mesh scale=".0010 .0010 .0010" filename="package://lawnmow_description/meshes/caster.stl"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
</link>
<link name="rfcaster">
<collision name='rfcollision'>
<origin xyz="0.016 0.605 .35" rpy="1.58 0 0"/>
<geometry>
<cylinder radius="0.167022" length="0.07"/>
</geometry>
<surface>
<friction>
<ode1>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1</slip1>
<slip2>1</slip2>
</ode1>
</friction>
</surface>
</collision>
<visual name='rfcaster_visual'>
<origin xyz="0 0 0" rpy="0 -1.55 0"/>
<geometry>
<mesh scale=".0010 .0010 .0010" filename="package://lawnmow_description/meshes/caster.stl"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
</link>
<link name="left_wheel">
<collision name="collision">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.167022" length="0.07"/>1.
</geometry>
</collision>
<visual name="left_wheel_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh scale=".0010 .0010 .0010" filename="package://lawnmow_description/meshes/wheel.stl"/>
</geometry>
<material name="black">
<color rgba="1 0 0 1"/>
</material>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1.5"/>
<cylinder_inertia m="1.5" r="0.167022" h="0.07"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<link name="right_wheel">
<collision name="collision">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.167022" length="0.07"/>
</geometry>
</collision>
<visual name="right_wheel_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh scale=".0010 .0010 .0010" filename="package://lawnmow_description/meshes/wheel.stl"/>
</geometry>
<material name="black">
<color rgba="1 0 0 1"/>
</material>
</visual>
<inertial>
<origin xyz="0.04 0.12 .18" rpy="1.58 0 0"/>
<mass value="1.5"/>
<cylinder_inertia m="1.5" r="0.167022" h="0.07"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<joint type="continuous" name="lfcaster_hinge">
<origin xyz="-0.4 0.605 .35" rpy=".1 0 3.1"/>
<child link="lfcaster"/>
<parent link="chassis"/>
<axis xyz="0 0 1" rpy="0 0 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<joint type="continuous" name="rfcaster_hinge">
<origin xyz="0.016 0.605 .35" rpy=".1 0 3.1"/>
<child link="rfcaster"/>
<parent link="chassis"/>
<axis xyz="0 0 1" rpy="0 0 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<joint type="continuous" name="left_wheel_hinge">
<origin xyz="-0.5 0.12 .18" rpy="0 0 0"/>
<child link="left_wheel"/>
<parent link="chassis"/>
<axis xyz="0 1 0" rpy="0 0 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<joint type="continuous" name="right_wheel_hinge">
<origin xyz="0.04 0.12 .18" rpy="0 0 0"/>
<child link="right_wheel"/>
<parent link="chassis"/>
<axis xyz="0 1 0" rpy="0 0 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="camera">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${cameraSize} ${cameraSize} ${cameraSize}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${cameraSize} ${cameraSize} ${cameraSize}"/>
</geometry>
<material name="green"/>
</visual>
<inertial>
<mass value="${cameraMass}" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<box_inertia m="${cameraMass}" x="${cameraSize}" y="${cameraSize}" z="${cameraSize}" />
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="camera_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz=".2 0 0" rpy="0 0 0"/>
<parent link="chassis"/>
<child link="camera"/>
</joint>
</robot>
The second file macros.xacro:
<?xml version="1.0"?>
<robot>
<macro name="box_inertia" params="m x y z">
<inertia ixx="${m*(y*y+z*z)/12}" ixy = "0" ixz = "0"
iyy="${m*(x*x+z*z)/12}" iyz = "0"
izz="${m*(x*x+z*z)/12}"
/>
</macro>
<macro name="wheel" params="lr tY">
<link name="${lr}_wheel">
<collision>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<geometry>
<cylinder length="${wheelWidth}" radius="${wheelRadius}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<geometry>
<cylinder length="${wheelWidth}" radius="${wheelRadius}"/>
</geometry>
<material name="black"/>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<mass value="${wheelMass}"/>
<cylinder_inertia m="${wheelMass}" r="${wheelRadius}" h="${wheelWidth}"/>
</inertial>
</link>
<gazebo reference="${lr}_wheel">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0" />
<kd value="1.0" />
<fdir1 value="1 0 0"/>
<material>Gazebo/Black</material>
</gazebo>
<joint name="${lr}_wheel_hinge" type="continuous">
<parent link="chassis"/>
<child link="${lr}_wheel"/>
<origin xyz="${-wheelPos+chassisLength/2} ${tY*wheelWidth/2+tY*chassisWidth/2} ${wheelRadius}" rpy="0 0 0" />
<axis xyz="0 1 0" rpy="0 0 0" />
<limit effort="10000" velocity="10000"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<transmission name="${lr}_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${lr}_wheel_hinge">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${lr}Motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>10</mechanicalReduction>
</actuator>
</transmission>
</macro>
</robot>
The third file, materials.xacro
<?xml version="1.0"?>
<robot>
<material name="Black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="Red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</robot>
And last, lawnmow.gazebo
<?xml version="1.0"?>
<robot>
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<legacyMode>false</legacyMode>
<alwaysOn>true</alwaysOn>
<updateRate>20</updateRate>
<leftJoint>left_wheel_hinge</leftJoint>
<rightJoint>right_wheel_hinge</rightJoint>
<wheelSeparation>0.54</wheelSeparation>
<wheelDiameter>0.14</wheelDiameter>
<torque>20</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<robotBaseFrame>chassis</robotBaseFrame>
</plugin>
</gazebo>
<gazebo reference="chassis">
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="lfcaster">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="rfcaster">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="left_wheel">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="right_wheel">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="camera">
<material>Gazebo/Black</material>
<sensor type="camera" name="camera1">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>lawnmow/camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
</robot>
All of these files would go in the urdf folder.
Once again, I give the the creator of the original version, Richard Wang, major props for publishing the original version of this for others to learn from.
4/21/17
4/23/17 -fixed macros name and code.
4/25/17 - fixed issues with gazebo in lawnmow.xacro (thanks Geoff!).
4/27/17 - fixed issues with gazebo crashing and not showing casters.