XTDrone/sitl_config/ugv/catvehicle/urdf/catvehicle.urdf

932 lines
31 KiB
XML

<?xml version="1.0" encoding="utf-8"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from catvehicle.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<!--
Author: Jonathan Sprinkle, Sam Taylor, Alex Warren, Rahul Bhadani
Hannah Grace Mason, Joe Macinnes, Landon Chase Bentley
Copyright (c) 2013-2018 Arizona Board of Regents
All rights reserved.
Permission is hereby granted, without written agreement and without
license or royalty fees, to use, copy, modify, and distribute this
software and its documentation for any purpose, provided that the
above copyright notice and the following two paragraphs appear in
all copies of this software.
IN NO EVENT SHALL THE ARIZONA BOARD OF REGENTS BE LIABLE TO ANY PARTY
FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES
ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN
IF THE ARIZONA BOARD OF REGENTS HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGE.
THE ARIZONA BOARD OF REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY
AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER
IS ON AN "AS IS" BASIS, AND THE ARIZONA BOARD OF REGENTS HAS NO OBLIGATION
TO PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
Summary:
=======
This file specifies 3D structure of the car with their inertial properties
and other dynamics.
-->
<!-- Inertial parameters selected with the help of
http://www.car-engineer.com/vehicle-inertia-calculation-tool/
-->
<robot name="catvehicle" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!--xacro:property name="tyre_mass_ixx" value="2.53174430759784"/>
<xacro:property name="tyre_mass_iyy" value="1.43724304615612"/>
<xacro:property name="tyre_mass_izz" value="1.39917175362076"/>
<xacro:property name="tyre_mass_ixz" value="0.0295230888350046"/>
<xacro:property name="tyre_mass_ixy" value="-0.00131884944491474"/>
<xacro:property name="tyre_mass_iyz" value="-0.00115883839900594"/-->
<gazebo reference="back_right_wheel_link">
<mu1>1000000</mu1>
<mu2>1000000</mu2>
<kp>10000000</kp>
<!--kp is surface elasticity-->
<kd>100</kd>
<!-- kd is damping-->
<minDepth>0.01</minDepth>
<maxVel>1000.0</maxVel>
</gazebo>
<gazebo reference="back_left_wheel_link">
<mu1>100000000</mu1>
<mu2>100000000</mu2>
<kp>10000000</kp>
<kd>100</kd>
<minDepth>0.01</minDepth>
<maxVel>1000.0</maxVel>
</gazebo>
<gazebo reference="front_right_wheel_link">
<mu1>100000000</mu1>
<mu2>100000000</mu2>
<kp>1000000</kp>
<kd>100</kd>
<minDepth>0.01</minDepth>
<maxVel>1000.0</maxVel>
</gazebo>
<gazebo reference="front_left_wheel_link">
<mu1>100000000</mu1>
<mu2>100000000</mu2>
<kp>1000000</kp>
<kd>100</kd>
<minDepth>0.01</minDepth>
<maxVel>1000.0</maxVel>
</gazebo>
<gazebo reference="front_right_steering_link">
<mu1>100000000</mu1>
<mu2>100000000</mu2>
<kp>1000000</kp>
<kd>0.1</kd>
<minDepth>0.01</minDepth>
<maxVel>1000.0</maxVel>
</gazebo>
<gazebo reference="front_left_steering_link">
<mu1>100000000</mu1>
<mu2>100000000</mu2>
<kp>1000000</kp>
<kd>0.1</kd>
<minDepth>0.01</minDepth>
<maxVel>1000.0</maxVel>
</gazebo>
<!--camera-->
<!-- JMS removed to see if it improves sim times -->
<!--
<gazebo reference="camera_link">
<mu1>0.6</mu1>
<mu2>0.5</mu2>
</gazebo>
<gazebo reference="camera_link">
<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>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<robotNamespace>/$(arg roboname)</robotNamespace>
<cameraName>camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</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>
-->
<gazebo reference="laser_link">
<mu1>0.6</mu1>
<mu2>0.5</mu2>
</gazebo>
<gazebo reference="laser_link">
<sensor name="lidar_sensor" type="ray">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>100</samples>
<resolution>1</resolution>
<min_angle>-0.4</min_angle>
<max_angle>0.4</max_angle>
</horizontal>
<vertical>
<samples>20</samples>
<resolution>1</resolution>
<min_angle>-0.034906585</min_angle>
<!-- <max_angle>0.432841654</max_angle> -->
<max_angle>0.326</max_angle>
</vertical>
</scan>
<range>
<min>1</min>
<max>50.0</max>
<resolution>0.02</resolution>
</range>
</ray>
<!-- <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/cat/laser/scan</topicName>
<frameName>laser_link</frameName> -->
<plugin filename="libgazebo_ros_block_laser.so" name="laser_controller">
<frameName>laser_link</frameName>
<hokuyoMinIntensity>101</hokuyoMinIntensity>
<robotNamespace>/catvehicle</robotNamespace>
<topicName>lidar_points</topicName>
<gaussianNoise>0.02</gaussianNoise>
<updateRate>5</updateRate>
</plugin>
</sensor>
</gazebo>
<gazebo reference="front_laser_link">
<mu1>0.6</mu1>
<mu2>0.5</mu2>
</gazebo>
<gazebo reference="front_laser_link">
<sensor name="sick_lms291" type="ray">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>75</update_rate>
<ray>
<scan>
<horizontal>
<samples>180</samples>
<resolution>1</resolution>
<min_angle>-1.57</min_angle>
<max_angle>1.57</max_angle>
</horizontal>
</scan>
<range>
<min>1.5</min>
<!-- This range is in m, I hope... -->
<max>80.0</max>
<resolution>0.05</resolution>
</range>
<!--
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.02</stddev>
</noise>
-->
</ray>
<plugin filename="libgazebo_ros_laser.so" name="sick_lms291_controller">
<!-- <robotNamespace>/catvehicle</robotNamespace>-->
<topicName>/catvehicle/front_laser_points</topicName>
<update_rate>75</update_rate>
<frameName>front_laser_link</frameName>
<gaussianNoise>0.02</gaussianNoise>
</plugin>
</sensor>
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<robotNamespace>/catvehicle</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
<!--Rear Wheel Drive, cuz why not-->
<!--
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<robotNamespace>/catvehicle</robotNamespace>
<rosDebugLevel>Debug</rosDebugLevel>
<publishWheelTF>false</publishWheelTF>
<publishWheelJointState>true</publishWheelJointState>
<alwaysOn>true</alwaysOn>
<leftJoint>back_left_wheel_joint</leftJoint>
<rightJoint>back_right_wheel_joint</rightJoint>
<wheelSeparation>1.73</wheelSeparation>
<wheelDiameter>0.712</wheelDiameter>
<wheelTorque>350</wheelTorque>
<wheelAcceleration>1.0</wheelAcceleration>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<odometrySource>world</odometrySource>
<robotBaseFrame>base_link</robotBaseFrame>
<cmd_vel_timeout>0.20</cmd_vel_timeout>
<updateRate>10.0</updateRate>
</plugin>
</gazebo>
-->
<gazebo>
<plugin filename="libgazebo_ros_joint_state_publisher.so" name="joint_state_publisher">
<jointName>back_left_wheel_joint, back_right_wheel_joint, front_left_steering_joint, front_right_steering_joint, front_right_wheel_joint, front_left_wheel_joint</jointName>
<updateRate>50.0</updateRate>
<robotNamespace>/catvehicle</robotNamespace>
<alwaysOn>true</alwaysOn>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libcatvehiclegazebo.so" name="cmdvel_controller">
<robotNamespace>/catvehicle</robotNamespace>
</plugin>
</gazebo>
<gazebo reference="velodyne_link">
<mu1>0.6</mu1>
<mu2>0.5</mu2>
</gazebo>
<gazebo reference="velodyne_link">
<sensor name="lidar_sensor" type="ray">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>100</samples>
<resolution>1</resolution>
<min_angle>-0.4</min_angle>
<max_angle>0.4</max_angle>
</horizontal>
<vertical>
<samples>20</samples>
<resolution>1</resolution>
<min_angle>-0.034906585</min_angle>
<!-- <max_angle>0.432841654</max_angle> -->
<max_angle>0.326</max_angle>
</vertical>
</scan>
<range>
<min>1</min>
<max>50.0</max>
<resolution>0.02</resolution>
</range>
</ray>
<!-- <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/cat/laser/scan</topicName>
<frameName>laser_link</frameName> -->
<plugin filename="libgazebo_ros_block_laser.so" name="laser_controller">
<frameName>velodyne_link</frameName>
<hokuyoMinIntensity>101</hokuyoMinIntensity>
<robotNamespace>/catvehicle</robotNamespace>
<topicName>lidar_points</topicName>
<gaussianNoise>0.02</gaussianNoise>
<updateRate>5</updateRate>
</plugin>
</sensor>
</gazebo>
<!--right camera-->
<gazebo reference="camera_right_link">
<mu1>0.6</mu1>
<mu2>0.5</mu2>
</gazebo>
<gazebo reference="camera_right_link">
<sensor name="camera_right" type="camera">
<update_rate>30.0</update_rate>
<camera name="right">
<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>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin filename="libgazebo_ros_camera.so" name="camera_right_controller">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<robotNamespace>/catvehicle</robotNamespace>
<cameraName>camera_right</cameraName>
<imageTopicName>image_raw_right</imageTopicName>
<cameraInfoTopicName>camera_right_info</cameraInfoTopicName>
<frameName>camera_right_link</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>
<!--left camera-->
<gazebo reference="camera_left_link">
<mu1>0.6</mu1>
<mu2>0.5</mu2>
</gazebo>
<gazebo reference="camera_left_link">
<sensor name="camera_left" type="camera">
<update_rate>30.0</update_rate>
<camera name="left">
<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>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin filename="libgazebo_ros_camera.so" name="camera_left_controller">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<robotNamespace>/catvehicle</robotNamespace>
<cameraName>camera_left</cameraName>
<imageTopicName>image_raw_left</imageTopicName>
<cameraInfoTopicName>camera_left_info</cameraInfoTopicName>
<frameName>camera_left_link</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>
<!--triclops camera-->
<gazebo reference="triclops_link">
<mu1>0.6</mu1>
<mu2>0.5</mu2>
</gazebo>
<gazebo reference="triclops_link">
<sensor name="triclops" type="camera">
<update_rate>16.0</update_rate>
<camera name="triclops">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1280</width>
<height>960</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin filename="libgazebo_ros_camera.so" name="camera_triclops_controller">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<robotNamespace>/catvehicle</robotNamespace>
<cameraName>triclops</cameraName>
<imageTopicName>triclops/left/image</imageTopicName>
<cameraInfoTopicName>camera_triclops_info</cameraInfoTopicName>
<frameName>triclops_link</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>
<!--Car Body-->
<link name="base_link">
<collision>
<origin rpy="0 0 0" xyz="0 0 1.0639"/>
<geometry>
<mesh filename="package://catvehicle/meshes/ford_escape_no_wheels_2.stl"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 1.0639"/>
<geometry>
<mesh filename="package://catvehicle/meshes/ford_escape_no_wheels_2.stl"/>
</geometry>
</visual>
</link>
<joint name="inertial_joint" type="fixed">
<parent link="base_link"/>
<child link="main_mass"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="main_mass" type="fixed">
<parent link="inertial_joint"/>
<inertial>
<origin rpy="0 0 0" xyz="-0.0202 0.0126 -0.0256"/>
<!-- This is the center of mass of Car Body-->
<mass value="1703.239"/>
<inertia ixx="347.195805" ixy="-11.4914985" ixz="18.5070628" iyy="2330.10026" iyz="3.97814264" izz="2529.41827"/>
</inertial>
</link>
<!--Back Right Wheel-->
<joint name="back_right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="back_right_wheel_link"/>
<origin rpy="0 0 0" xyz="-1.05 -0.765 0.66"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="10" friction="10.0"/>
</joint>
<link name="back_right_wheel_link">
<collision>
<origin rpy="1.57079634179 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.2336291492" radius="0.3671951254"/>
<!--mesh filename="package://catvehicle/meshes/ford_escape_wheel.stl"/-->
</geometry>
<surface>
<friction>
<ode>
<mu>10000000</mu>
<mu2>7000</mu2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0.0</restitution_coefficient>
</bounce>
<contact>
<ode>
<soft_cfm>0.001</soft_cfm>
<soft_erp>0.5</soft_erp>
<kp>10000000</kp>
<kd>1</kd>
</ode>
</contact>
</surface>
</collision>
<visual>
<!--origin xyz="0 0 0" rpy="${PI/2} 0 0"/-->
<origin rpy="0 0 -1.57079634179" xyz="0 0.1 0.0"/>
<geometry>
<!--cylinder length="${tyre_length}" radius="${tyre_radius}"/>
<scale xyz="1 1 1"/-->
<mesh filename="package://catvehicle/meshes/ford_escape_wheel.stl" scale="1.2 1 1"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="20"/>
<inertia ixx="1.34832260118" ixy="0.0" ixz="0.0" iyy="0.765132266181" iyz="0.0" izz="0.765132266181"/>
</inertial>
</link>
<!--Back Left Wheel -->
<joint name="back_left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="back_left_wheel_link"/>
<origin rpy="0 0 0" xyz="-1.05 0.765 0.66"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="10" friction="10.0"/>
</joint>
<link name="back_left_wheel_link">
<collision>
<origin rpy="1.57079634179 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.2336291492" radius="0.3671951254"/>
<!--mesh filename="package://catvehicle/meshes/ford_escape_wheel.stl"/-->
</geometry>
<surface>
<friction>
<ode>
<mu>10000000</mu>
<mu2>7000</mu2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0.0</restitution_coefficient>
</bounce>
<contact>
<ode>
<soft_cfm>0.001</soft_cfm>
<soft_erp>0.5</soft_erp>
<kp>10000000</kp>
<kd>1</kd>
</ode>
</contact>
</surface>
</collision>
<visual>
<!--origin xyz="0 0 0" rpy="${PI/2} 0 0"/-->
<origin rpy="0 0 1.57079634179" xyz="0 -0.1 0.0"/>
<geometry>
<!--cylinder length="${tyre_length}" radius="${tyre_radius}"/-->
<mesh filename="package://catvehicle/meshes/ford_escape_wheel.stl" scale="1.2 1 1"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="20"/>
<inertia ixx="1.34832260118" ixy="0.0" ixz="0.0" iyy="0.765132266181" iyz="0.0" izz="0.765132266181"/>
</inertial>
</link>
<!--Right Steering-->
<joint name="front_right_steering_joint" type="revolute">
<parent link="base_link"/>
<child link="front_right_steering_link"/>
<origin rpy="0 0 0" xyz="1.55 -0.745 0.66"/>
<axis xyz="0 0 1"/>
<limit effort="10000" lower="-0.6" upper="0.6" velocity="1000"/>
</joint>
<link name="front_right_steering_link">
<collision>
<origin rpy="1.57079634179 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="1.57079634179 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="50.0"/>
<inertia ixx="0.25" ixy="0.000000" ixz="0.000000" iyy="0.135416666667" iyz="0.000000" izz="0.135416666667"/>
</inertial>
</link>
<!--Front Right Wheel-->
<joint name="front_right_wheel_joint" type="continuous">
<parent link="front_right_steering_link"/>
<child link="front_right_wheel_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="10" friction="10.0"/>
</joint>
<link name="front_right_wheel_link">
<collision>
<origin rpy="1.57079634179 0 0" xyz="0 0 0"/>
<!--origin xyz="0 0 0" rpy="0 0 ${-PI/2}"/-->
<geometry>
<cylinder length="0.2336291492" radius="0.3671951254"/>
<!--mesh filename="package://catvehicle/meshes/ford_escape_wheel.stl"/-->
</geometry>
<surface>
<friction>
<ode>
<mu>10000000</mu>
<mu2>7000</mu2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0.0</restitution_coefficient>
</bounce>
<contact>
<ode>
<soft_cfm>0.001</soft_cfm>
<soft_erp>0.5</soft_erp>
<kp>10000000</kp>
<kd>1</kd>
</ode>
</contact>
</surface>
</collision>
<visual>
<!--origin xyz="0 0 0" rpy="${PI/2} 0 0"/-->
<origin rpy="0 0 -1.57079634179" xyz="0 0.1 0.0"/>
<geometry>
<!--cylinder length="${tyre_length}" radius="${tyre_radius}"/>
<scale xyz="1 1 1"/-->
<mesh filename="package://catvehicle/meshes/ford_escape_wheel.stl" scale="1.2 1 1"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="20"/>
<inertia ixx="1.34832260118" ixy="0.0" ixz="0.0" iyy="0.765132266181" iyz="0.0" izz="0.765132266181"/>
</inertial>
</link>
<!--Left Steering-->
<joint name="front_left_steering_joint" type="revolute">
<parent link="base_link"/>
<child link="front_left_steering_link"/>
<origin rpy="0 0 0" xyz="1.55 0.745 0.66"/>
<axis xyz="0 0 1"/>
<limit effort="10000" lower="-0.6" upper="0.6" velocity="1000"/>
</joint>
<link name="front_left_steering_link">
<parent link="base_link"/>
<collision>
<origin rpy="1.57079634179 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="1.57079634179 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="50.0"/>
<inertia ixx="0.25" ixy="0.000000" ixz="0.000000" iyy="0.135416666667" iyz="0.000000" izz="0.135416666667"/>
</inertial>
</link>
<!--Front Left Wheel-->
<joint name="front_left_wheel_joint" type="continuous">
<parent link="front_left_steering_link"/>
<child link="front_left_wheel_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="10" friction="10.0"/>
</joint>
<link name="front_left_wheel_link">
<parent link="front_left_wheel_joint"/>
<collision>
<origin rpy="1.57079634179 0 0" xyz="0 0 0"/>
<!--origin xyz="0 0 0" rpy="0 0 ${PI/2}"/-->
<geometry>
<cylinder length="0.2336291492" radius="0.3671951254"/>
<!--mesh filename="package://catvehicle/meshes/ford_escape_wheel.stl"/-->
</geometry>
<surface>
<friction>
<ode>
<mu>10000000</mu>
<mu2>7000</mu2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0.0</restitution_coefficient>
</bounce>
<contact>
<ode>
<soft_cfm>0.001</soft_cfm>
<soft_erp>0.5</soft_erp>
<kp>10000000</kp>
<kd>1</kd>
</ode>
</contact>
</surface>
</collision>
<visual>
<!--origin xyz="0 0 0" rpy="${PI/2} 0 0"/-->
<origin rpy="0 0 1.57079634179" xyz="0 -0.1 0.0"/>
<geometry>
<!--cylinder length="${tyre_length}" radius="${tyre_radius}"/-->
<mesh filename="package://catvehicle/meshes/ford_escape_wheel.stl" scale="1.2 1 1"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="20"/>
<inertia ixx="1.34832260118" ixy="0.0" ixz="0.0" iyy="0.765132266181" iyz="0.0" izz="0.765132266181"/>
</inertial>
</link>
<!-- front laser-->
<joint name="front_laser_joint" type="fixed">
<origin rpy="0 0 0" xyz="2.4662046481 0 0.9268786042"/>
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="front_laser_link"/>
</joint>
<link name="front_laser_link">
<parent link="front_laser_joint"/>
<collision>
<origin rpy="0 0.0 0" xyz="0 0 0"/>
<geometry>
<box size="0.25 0.25 0.25"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://catvehicle/meshes/SickLMS.stl"/>
<!--box size="${front_laser_size} ${front_laser_size} ${front_laser_size}"/-->
</geometry>
</visual>
<inertial>
<mass value="1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0104166666667" ixy="0" ixz="0" iyy="0.0104166666667" iyz="0" izz="0.0104166666667"/>
</inertial>
</link>
<joint name="camera_right_joint" type="fixed">
<origin rpy="0 0 -1.57079634179" xyz="-0.75 -0.645 2.025"/>
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="camera_right_link"/>
</joint>
<link name="camera_right_link">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<joint name="camera_left_joint" type="fixed">
<origin rpy="0 0 1.57079634179" xyz="-0.75 0.645 2.025"/>
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="camera_left_link"/>
</joint>
<link name="camera_left_link">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<!-- TRICLOPS -->
<joint name="triclops" type="fixed">
<origin rpy="0 0 0" xyz="0.3 0 2.025"/>
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="triclops_link"/>
</joint>
<link name="triclops_link">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.05 0.3 0.05"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.05 0.3 0.05"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<joint name="parking_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.5 0 2.025"/>
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="parking_link"/>
</joint>
<link name="parking_link">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1 0.8 0.15"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.25 0.25 0.25"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<joint name="velodyne_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.135"/>
<axis xyz="0 0 1"/>
<parent link="camera_link"/>
<child link="velodyne_link"/>
</joint>
<link name="velodyne_link">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.25 0.25 0.25"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.25 0.25 0.25"/>
</geometry>
</visual>
<inertial>
<mass value="1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0104166666667" ixy="0" ixz="0" iyy="0.0104166666667" iyz="0" izz="0.0104166666667"/>
</inertial>
</link>
<!-- motors and transmissions for the two rear wheels -->
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="back_right_wheel_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="tran2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="back_left_wheel_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="motor2">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rack_and_pinion_left">
<type>transmission_interface/SimpleTransmission</type>
<joint name="front_left_steering_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="eps_left">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rack_and_pinion_right">
<type>transmission_interface/SimpleTransmission</type>
<joint name="front_right_steering_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="eps_right">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>