XTDrone/sitl_config/ugv/catvehicle/urdf/catvehicle4-6.xacro

739 lines
28 KiB
XML

<?xml version="1.0" ?>
<!--
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="$(arg roboname)" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:arg name="camera_left" default="true"/>
<xacro:arg name="camera_right" default="true"/>
<xacro:arg name="triclops" default="true"/>
<xacro:arg name="velodyne_points" default="true"/>
<xacro:arg name="laser_points" default="true"/>
<xacro:property name="velodyne_points" value="$(arg velodyne_points)"/>
<xacro:property name="laser_points" value="$(arg laser_points)"/>
<xacro:property name="camera_right" value="$(arg camera_right)"/>
<xacro:property name="camera_left" value="$(arg camera_left)"/>
<xacro:property name="triclops" value="$(arg triclops)"/>
<xacro:property name="camera_box" value="0.1"/>
<xacro:property name="sensor_box" value="0.25"/>
<xacro:property name="PI" value="3.1415926835897931"/>
<xacro:property name="base_height" value="1.0639"/>
<xacro:property name="base_mass" value="1703.239"/>
<!--Car's height is the height of bouding box of the 3D
mesh given by meshlab -->
<xacro:property name="car_height" value="1.5837572084"/>
<!-- car_to_bumper is car's length. The value reported here
is the lenght of the bounding box of the 3D mesh of the car's
body given by meshlab. Actual length of the car may be slightly
less and if require, we may use some offset to use this value
anywhere -->
<!-- Wheelbase is roughly 2.8232111 m -->
<xacro:property name="car_to_bumper" value="4.4324092962"/>
<xacro:property name="car_COM_x" value="-0.0202"/>
<xacro:property name="car_COM_y" value="0.0126"/>
<xacro:property name="car_COM_z" value="-0.0256"/>
<!-- We are assuming that front bumper's height is half of the car's
bounding box height -->
<xacro:property name="front_bumper_height" value="${car_height/2}"/>
<!--This is the car tread, i.e distance between right and left front wheels-->
<xacro:property name="car_width" value="1.290"/>
<xacro:property name="car_width_offset" value="0.05"/>
<!-- Inertial tensor of car body has been taken from meshlab after
analyzing the 3D structure of car body -->
<xacro:property name="base_mass_ixx" value="347.195805"/>
<xacro:property name="base_mass_ixy" value="-11.4914985"/>
<xacro:property name="base_mass_ixz" value="18.5070628"/>
<xacro:property name="base_mass_iyy" value="2330.10026"/>
<xacro:property name="base_mass_iyz" value="3.97814264"/>
<xacro:property name="base_mass_izz" value="2529.41827"/>
<xacro:property name="tyre_x" value="1.05"/>
<xacro:property name="tyre_front_x" value="1.55"/>
<xacro:property name="tyre_back_x" value="-1.05"/>
<xacro:property name="tyre_y" value="0.765"/>
<xacro:property name="tyre_r" value="0.66"/>
<!--Below is the thickness of the car's tyre-->
<xacro:property name="tyre_length" value="0.2336291492"/>
<xacro:property name="tyre_radius" value="0.3671951254"/>
<xacro:property name="tyre_mass" value="20"/>
<!--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"/-->
<!-- Here we are calculating inertial tensor of a cylinderical body.
In this model, we didn't use actual mesh of tyre, but a simplified
cylindrical model. -->
<xacro:property name="tyre_mass_ixx" value="${((1/2)*tyre_mass*tyre_radius*tyre_radius)}"/>
<xacro:property name="tyre_mass_iyy" value="${((1/12)*tyre_mass*tyre_length*tyre_length) + ((1/4)*tyre_mass*tyre_radius*tyre_radius)}"/>
<xacro:property name="tyre_mass_izz" value="${((1/12)*tyre_mass*tyre_length*tyre_length) + ((1/4)*tyre_mass*tyre_radius*tyre_radius)}"/>
<xacro:property name="tyre_mass_ixz" value="0.0"/>
<xacro:property name="tyre_mass_ixy" value="0.0"/>
<xacro:property name="tyre_mass_iyz" value="0.0"/>
<xacro:property name="tyre_height" value="-0.696"/>
<xacro:property name="str_mass" value="50.00"/>
<xacro:property name="str_length" value="0.05"/>
<xacro:property name="str_radius" value="0.1"/>
<xacro:property name="front_right_offset" value="0.05"/>
<xacro:property name="str_mass_ixx" value="${((1/2)*str_mass*str_radius*str_radius)}"/>
<xacro:property name="str_mass_iyy" value="${((1/12)*str_mass*str_length*str_length) + ((1/4)*str_mass*str_radius*str_radius)}"/>
<xacro:property name="str_mass_izz" value="${((1/12)*str_mass*str_length*str_length) + ((1/4)*str_mass*str_radius*str_radius)}"/>
<xacro:property name="str_angle" value="0.6"/>
<xacro:property name="tyre_origin">
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
</xacro:property>
<xacro:property name="tyre_origin_2">
<origin xyz="0 0 0" rpy="0 0 ${PI/2}"/>
</xacro:property>
<xacro:property name="tyre_origin_3">
<origin xyz="0 0 0" rpy="0 0 ${-PI/2}"/>
</xacro:property>
<xacro:property name="marker_origin">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:property>
<xacro:property name="front_laser_size" value="0.25"/>
<xacro:property name="front_laser_mass" value="1"/>
<xacro:include filename="$(find catvehicle)/urdf/catvehicle.gazebo"/>
<xacro:if value="${velodyne_points}">
<!-- You can pass parameters in order to change the max/min
horizontal angles of the velodyne sensors. These are interpreted
in the velodyne_points gazebo file -->
<xacro:arg name="velodyne_min_angle" default="-0.4"/>
<xacro:arg name="velodyne_max_angle" default="0.4"/>
<xacro:property name="velodyne_min_angle" value="$(arg velodyne_min_angle)"/>
<xacro:property name="velodyne_max_angle" value="$(arg velodyne_max_angle)"/>
<xacro:include filename="$(find catvehicle)/urdf/catvehicle_velodyne_points.gazebo"/>
</xacro:if>
<xacro:if value="${camera_right}">
<xacro:include filename="$(find catvehicle)/urdf/catvehicle_right_camera.gazebo"/>
</xacro:if>
<xacro:if value="${camera_left}">
<xacro:include filename="$(find catvehicle)/urdf/catvehicle_left_camera.gazebo"/>
</xacro:if>
<xacro:if value="${triclops}">
<xacro:include filename="$(find catvehicle)/urdf/catvehicle_triclops.gazebo"/>
</xacro:if>
<xacro:if value="${laser_points}">
<xacro:include filename="$(find catvehicle)/urdf/catvehicle_laser_points.gazebo"/>
</xacro:if>
<!--Car Body-->
<link name="base_link">
<collision>
<origin xyz="0 0 ${base_height}" rpy="0 0 0"/>
<geometry>
<mesh filename="package://catvehicle/meshes/ford_escape_no_wheels_2.dae"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 ${base_height}" rpy="0 0 0"/>
<geometry>
<mesh filename="package://catvehicle/meshes/ford_escape_no_wheels_2.dae"/>
</geometry>
</visual>
</link>
<joint name="inertial_joint" type="fixed">
<parent link="base_link"/>
<child link="main_mass"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>
<link name="main_mass" type="fixed">
<parent link="inertial_joint"/>
<inertial>
<origin xyz="${car_COM_x} ${car_COM_y} ${car_COM_z}" rpy="0 0 0"/> <!-- This is the center of mass of Car Body-->
<mass value="${base_mass}"/>
<inertia
ixx="${base_mass_ixx}" ixy="${base_mass_ixy}" ixz="${base_mass_ixz}"
iyy="${base_mass_iyy}" iyz="${base_mass_iyz}"
izz="${base_mass_izz}"/>
</inertial>
</link>
<!--Back Right Wheel-->
<joint name="back_right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="back_right_wheel_link"/>
<origin xyz="${tyre_back_x} ${-tyre_y} ${tyre_r}" rpy="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="back_right_wheel_link">
<collision>
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
<geometry>
<cylinder length="${tyre_length}" radius="${tyre_radius}"/>
<!--mesh filename="package://catvehicle/meshes/ford_escape_wheel.dae"/-->
</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 xyz="0 ${car_width_offset*2} 0.0" rpy="0 0 ${-PI/2}"/>
<geometry>
<!--cylinder length="${tyre_length}" radius="${tyre_radius}"/>
<scale xyz="1 1 1"/-->
<mesh scale="1.2 1 1" filename="package://catvehicle/meshes/ford_escape_wheel.dae"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${tyre_mass}"/>
<inertia
ixx="${tyre_mass_ixx}" ixy="${tyre_mass_ixy}" ixz="${tyre_mass_ixz}"
iyy="${tyre_mass_iyy}" iyz="${tyre_mass_iyz}"
izz="${tyre_mass_izz}"/>
</inertial>
</link>
<!--Back Left Wheel -->
<joint name="back_left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="back_left_wheel_link"/>
<origin xyz="${tyre_back_x} ${tyre_y} ${tyre_r}" rpy="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="back_left_wheel_link">
<collision>
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
<geometry>
<cylinder length="${tyre_length}" radius="${tyre_radius}"/>
<!--mesh filename="package://catvehicle/meshes/ford_escape_wheel.dae"/-->
</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 xyz="0 ${-car_width_offset*2} 0.0" rpy="0 0 ${PI/2}"/>
<geometry>
<!--cylinder length="${tyre_length}" radius="${tyre_radius}"/-->
<mesh scale="1.2 1 1" filename="package://catvehicle/meshes/ford_escape_wheel.dae"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${tyre_mass}"/>
<inertia
ixx="${tyre_mass_ixx}" ixy="${tyre_mass_ixy}" ixz="${tyre_mass_ixz}"
iyy="${tyre_mass_iyy}" iyz="${tyre_mass_iyz}"
izz="${tyre_mass_izz}"/>
</inertial>
</link>
<!--Right Steering-->
<joint name="front_right_steering_joint" type="revolute">
<parent link="base_link"/>
<child link="front_right_steering_link"/>
<origin xyz="${tyre_front_x} ${-car_width/2 - 2*str_length} ${tyre_r}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="10000" lower="${-str_angle}" upper="${str_angle}" velocity="1000"/>
</joint>
<link name="front_right_steering_link">
<collision>
<xacro:insert_block name="tyre_origin"/>
<geometry>
<cylinder length="${str_length}" radius="${str_radius}"/>
</geometry>
</collision>
<visual>
<xacro:insert_block name="tyre_origin"/>
<geometry>
<cylinder length="${str_length}" radius="${str_radius}"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${str_mass}"/>
<inertia
ixx="${str_mass_ixx}" ixy="0.000000" ixz="0.000000"
iyy="${str_mass_iyy}" iyz="0.000000"
izz="${str_mass_izz}"/>
</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 xyz="0 0 0" rpy="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 xyz="0 0 0" rpy="${PI/2} 0 0"/>
<!--origin xyz="0 0 0" rpy="0 0 ${-PI/2}"/-->
<geometry>
<cylinder length="${tyre_length}" radius="${tyre_radius}"/>
<!--mesh filename="package://catvehicle/meshes/ford_escape_wheel.dae"/-->
</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 xyz="0 ${car_width_offset*2} 0.0" rpy="0 0 ${-PI/2}"/>
<geometry>
<!--cylinder length="${tyre_length}" radius="${tyre_radius}"/>
<scale xyz="1 1 1"/-->
<mesh scale="1.2 1 1" filename="package://catvehicle/meshes/ford_escape_wheel.dae"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${tyre_mass}"/>
<inertia
ixx="${tyre_mass_ixx}" ixy="${tyre_mass_ixy}" ixz="${tyre_mass_ixz}"
iyy="${tyre_mass_iyy}" iyz="${tyre_mass_iyz}"
izz="${tyre_mass_izz}"/>
</inertial>
</link>
<!--Left Steering-->
<joint name="front_left_steering_joint" type="revolute">
<parent link="base_link"/>
<child link="front_left_steering_link"/>
<origin xyz="${tyre_front_x} ${car_width/2 + 2*str_length} ${tyre_r}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="10000" lower="${-str_angle}" upper="${str_angle}" velocity="1000"/>
</joint>
<link name="front_left_steering_link">
<parent link="base_link"/>
<collision>
<xacro:insert_block name="tyre_origin"/>
<geometry>
<cylinder length="${str_length}" radius="${str_radius}"/>
</geometry>
</collision>
<visual>
<xacro:insert_block name="tyre_origin"/>
<geometry>
<cylinder length="${str_length}" radius="${str_radius}"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${str_mass}"/>
<inertia
ixx="${str_mass_ixx}" ixy="0.000000" ixz="0.000000"
iyy="${str_mass_iyy}" iyz="0.000000"
izz="${str_mass_izz}"/>
</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 xyz="0 0 0" rpy="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 xyz="0 0 0" rpy="${PI/2} 0 0"/>
<!--origin xyz="0 0 0" rpy="0 0 ${PI/2}"/-->
<geometry>
<cylinder length="${tyre_length}" radius="${tyre_radius}"/>
<!--mesh filename="package://catvehicle/meshes/ford_escape_wheel.dae"/-->
</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 xyz="0 ${-car_width_offset*2} 0.0" rpy="0 0 ${PI/2}"/>
<geometry>
<!--cylinder length="${tyre_length}" radius="${tyre_radius}"/-->
<mesh scale="1.2 1 1" filename="package://catvehicle/meshes/ford_escape_wheel.dae"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${tyre_mass}"/>
<inertia
ixx="${tyre_mass_ixx}" ixy="${tyre_mass_ixy}" ixz="${tyre_mass_ixz}"
iyy="${tyre_mass_iyy}" iyz="${tyre_mass_iyz}"
izz="${tyre_mass_izz}"/>
</inertial>
</link>
<!-- front laser-->
<joint name="front_laser_joint" type="fixed">
<origin xyz="${car_to_bumper/2 + front_laser_size} 0 ${front_bumper_height + front_laser_size/2 + 0.01}" rpy="0 0 0"/>
<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 xyz="0 0 0" rpy="0 0.0 0"/>
<geometry>
<box size="${front_laser_size} ${front_laser_size} ${front_laser_size}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://catvehicle/meshes/SickLMS.dae"/>
<!--box size="${front_laser_size} ${front_laser_size} ${front_laser_size}"/-->
</geometry>
</visual>
<inertial>
<mass value="${front_laser_mass}" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="${(1/6)*front_laser_mass*front_laser_size*front_laser_size}" ixy="0" ixz="0"
iyy="${(1/6)*front_laser_mass*front_laser_size*front_laser_size}" iyz="0"
izz="${(1/6)*front_laser_mass*front_laser_size*front_laser_size}" />
</inertial>
</link>
<joint name="camera_right_joint" type="fixed">
<origin xyz="-0.75 -${car_width/2} ${0.725 + camera_box/2 + 1.25}" rpy="0 0 -${PI/2}"/>
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="camera_right_link"/>
</joint>
<link name="camera_right_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_box} ${camera_box} ${camera_box}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_box} ${camera_box} ${camera_box}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="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 xyz="-0.75 ${car_width/2} ${0.725 + camera_box/2 + 1.25}" rpy="0 0 ${PI/2}"/>
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="camera_left_link"/>
</joint>
<link name="camera_left_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_box} ${camera_box} ${camera_box}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_box} ${camera_box} ${camera_box}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="triclops" type="fixed">
<origin xyz="0.65 0 ${0.725 + sensor_box/2 + 1}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="triclops_link"/>
</joint>
<link name="triclops_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_box/2} ${3*camera_box} ${camera_box/2}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_box/2} ${3*camera_box} ${camera_box/2}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="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 xyz="-1.2 0 ${sensor_box/2 + 0.01}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="triclops_link"/>
<child link="velodyne_link"/>
</joint>
<link name="velodyne_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${sensor_box*10} ${sensor_box*4} ${sensor_box/2}"/>
</geometry>
<surface>
<friction>
<ode>
<mu>10000000</mu>
<mu2>7000</mu2>
</ode>
</friction>
</surface>
</collision>
<visual>
<origin xyz="0 -0.5 0.05" rpy="0 1.57 1.57"/>
<geometry>
<mesh filename="model://apriltag3-5/meshes/apriltag3-5.dae" scale="2 5 2"/>
</geometry>
</visual>
<inertial>
<mass value="${front_laser_mass}" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="${(1/6)*front_laser_mass*front_laser_size*front_laser_size}" ixy="0" ixz="0"
iyy="${(1/6)*front_laser_mass*front_laser_size*front_laser_size}" iyz="0"
izz="${(1/6)*front_laser_mass*front_laser_size*front_laser_size}" />
</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>