git commit -m "first commit"
This commit is contained in:
15
mir_robot/mir_description/urdf/include/common.gazebo.xacro
Executable file
15
mir_robot/mir_description/urdf/include/common.gazebo.xacro
Executable file
@@ -0,0 +1,15 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="controller_plugin_gazebo" params="robot_namespace">
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<xacro:unless value="${robot_namespace == ''}">
|
||||
<robotNamespace>${robot_namespace}</robotNamespace>
|
||||
</xacro:unless>
|
||||
<controlPeriod>0.001</controlPeriod>
|
||||
<legacyModeNS>false</legacyModeNS>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
84
mir_robot/mir_description/urdf/include/common_properties.urdf.xacro
Executable file
84
mir_robot/mir_description/urdf/include/common_properties.urdf.xacro
Executable file
@@ -0,0 +1,84 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!--
|
||||
Various useful properties such as constants and materials
|
||||
-->
|
||||
<robot name="xacro_properties" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
<!-- #################### RViz materials #################### -->
|
||||
<xacro:property name="material_white">
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</xacro:property>
|
||||
<xacro:property name="material_yellow">
|
||||
<material name="yellow">
|
||||
<color rgba="${255/255} ${226/255} ${0/255} 1"/>
|
||||
</material>
|
||||
</xacro:property>
|
||||
<xacro:property name="material_almost_white">
|
||||
<material name="almost_white">
|
||||
<color rgba="0.9 0.9 0.9 1" />
|
||||
</material>
|
||||
</xacro:property>
|
||||
<xacro:property name="material_grey">
|
||||
<material name="grey">
|
||||
<color rgba="0.5 0.5 0.5 1"/>
|
||||
</material>
|
||||
</xacro:property>
|
||||
<xacro:property name="material_light_grey">
|
||||
<material name="light_grey">
|
||||
<color rgba="0.6 0.6 0.6 1"/>
|
||||
</material>
|
||||
</xacro:property>
|
||||
<xacro:property name="material_dark_grey">
|
||||
<material name="dark_grey">
|
||||
<color rgba="0.3 0.3 0.3 1"/>
|
||||
</material>
|
||||
</xacro:property>
|
||||
<xacro:property name="material_black">
|
||||
<material name="black">
|
||||
<color rgba="0.1 0.1 0.1 1"/>
|
||||
</material>
|
||||
</xacro:property>
|
||||
<xacro:property name="material_aluminum">
|
||||
<material name="aluminum">
|
||||
<color rgba="0.8 0.8 0.8 1" />
|
||||
</material>
|
||||
</xacro:property>
|
||||
<xacro:property name="material_silver">
|
||||
<material name="silver">
|
||||
<color rgba="0.79 0.82 0.93 1" />
|
||||
</material>
|
||||
</xacro:property>
|
||||
|
||||
<!-- #################### inertials with origin #################### -->
|
||||
<!-- see https://secure.wikimedia.org/wikipedia/en/wiki/List_of_moment_of_inertia_tensors -->
|
||||
<xacro:macro name="sphere_inertial" params="radius mass *origin">
|
||||
<inertial>
|
||||
<mass value="${mass}" />
|
||||
<xacro:insert_block name="origin" />
|
||||
<inertia ixx="${0.4 * mass * radius * radius}" ixy="0.0" ixz="0.0"
|
||||
iyy="${0.4 * mass * radius * radius}" iyz="0.0"
|
||||
izz="${0.4 * mass * radius * radius}" />
|
||||
</inertial>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
|
||||
<inertial>
|
||||
<mass value="${mass}" />
|
||||
<xacro:insert_block name="origin" />
|
||||
<inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
|
||||
izz="${0.5 * mass * radius * radius}" />
|
||||
</inertial>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="box_inertial" params="x y z mass *origin">
|
||||
<inertial>
|
||||
<mass value="${mass}" />
|
||||
<xacro:insert_block name="origin" />
|
||||
<inertia ixx="${0.0833333 * mass * (y*y + z*z)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${0.0833333 * mass * (x*x + z*z)}" iyz="0.0"
|
||||
izz="${0.0833333 * mass * (x*x + y*y)}" />
|
||||
</inertial>
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
31
mir_robot/mir_description/urdf/include/imu.gazebo.urdf.xacro
Executable file
31
mir_robot/mir_description/urdf/include/imu.gazebo.urdf.xacro
Executable file
@@ -0,0 +1,31 @@
|
||||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
<!-- If tf_prefix is given, use "frame tf_prefix/imu_frame", else "imu_frame" -->
|
||||
<xacro:arg name="tf_prefix" default="" />
|
||||
<xacro:property name="tf_prefix" value="$(arg tf_prefix)" />
|
||||
<xacro:if value="${tf_prefix == ''}">
|
||||
<xacro:property name="imu_frame" value="imu_frame" />
|
||||
</xacro:if>
|
||||
<xacro:unless value="${tf_prefix == ''}">
|
||||
<xacro:property name="imu_frame" value="$(arg tf_prefix)/imu_frame" />
|
||||
</xacro:unless>
|
||||
|
||||
|
||||
<xacro:macro name="imu_gazebo" params="link imu_topic update_rate">
|
||||
<gazebo>
|
||||
<plugin name="imu_plugin" filename="libhector_gazebo_ros_imu.so">
|
||||
<updateRate>${update_rate}</updateRate>
|
||||
<bodyName>${link}</bodyName>
|
||||
<frameId>${imu_frame}</frameId> <!-- from real MiR -->
|
||||
<topicName>${imu_topic}</topicName>
|
||||
<accelDrift>0.0 0.0 0.0</accelDrift>
|
||||
<accelGaussianNoise>${sqrt(5e-05)} ${sqrt(0.0001)} ${sqrt(0.00013)}</accelGaussianNoise> <!-- real MiR linear_acceleration_covariance: [5e-05, 0.0, 0.0, 0.0, 0.0001, 0.0, 0.0, 0.0, 0.00013] -->
|
||||
<rateDrift>0.0 0.0 0.0</rateDrift>
|
||||
<rateGaussianNoise>${sqrt(8e-06)} ${sqrt(8e-06)} ${sqrt(3e-07)}</rateGaussianNoise> <!-- real MiR angular_velocity_covariance: [8e-06, 0.0, 0.0, 0.0, 8e-06, 0.0, 0.0, 0.0, 3e-07] -->
|
||||
<yawDrift>0.0</yawDrift>
|
||||
<yawGaussianNoise>${sqrt(0.1)}</yawGaussianNoise> <!-- real MiR orientation_covariance: [0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1] -->
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
62
mir_robot/mir_description/urdf/include/mir.gazebo.xacro
Executable file
62
mir_robot/mir_description/urdf/include/mir.gazebo.xacro
Executable file
@@ -0,0 +1,62 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="diff_controller_plugin_gazebo" params="prefix left_wheel_joint right_wheel_joint wheel_separation wheel_radius">
|
||||
<gazebo>
|
||||
<plugin name="diff_drive_controller" filename="libgazebo_ros_diff_drive.so">
|
||||
<legacyMode>false</legacyMode>
|
||||
<alwaysOn>true</alwaysOn>
|
||||
<updateRate>1000.0</updateRate>
|
||||
<leftJoint>${left_wheel_joint}</leftJoint>
|
||||
<rightJoint>${right_wheel_joint}</rightJoint>
|
||||
<wheelSeparation>${wheel_separation}</wheelSeparation>
|
||||
<wheelDiameter>${2*wheel_radius}</wheelDiameter>
|
||||
<wheelTorque>10</wheelTorque>
|
||||
<publishTf>1</publishTf>
|
||||
<odometryFrame>map</odometryFrame>
|
||||
<commandTopic>mobile_base_controller/cmd_vel</commandTopic>
|
||||
<odometryTopic>mobile_base_controller/odom</odometryTopic>
|
||||
<robotBaseFrame>base_footprint</robotBaseFrame>
|
||||
<wheelAcceleration>2.8</wheelAcceleration>
|
||||
<publishWheelJointState>true</publishWheelJointState>
|
||||
<publishWheelTF>false</publishWheelTF>
|
||||
<odometrySource>world</odometrySource>
|
||||
<rosDebugLevel>Debug</rosDebugLevel>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="set_wheel_friction" params="link friction">
|
||||
<gazebo reference="${link}">
|
||||
<mu1 value="${friction}"/>
|
||||
<mu2 value="${friction}"/>
|
||||
<kp value="10000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
<minDepth>0.01</minDepth>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="set_all_wheel_frictions" params="prefix">
|
||||
<xacro:set_wheel_friction link="${prefix}left_wheel_link" friction="200"/>
|
||||
<xacro:set_wheel_friction link="${prefix}right_wheel_link" friction="200"/>
|
||||
<xacro:set_wheel_friction link="${prefix}fl_caster_wheel_link" friction="1"/>
|
||||
<xacro:set_wheel_friction link="${prefix}fr_caster_wheel_link" friction="1"/>
|
||||
<xacro:set_wheel_friction link="${prefix}bl_caster_wheel_link" friction="1"/>
|
||||
<xacro:set_wheel_friction link="${prefix}br_caster_wheel_link" friction="1"/>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="p3d_base_controller" params="prefix">
|
||||
<gazebo>
|
||||
<plugin name="p3d_base_controller" filename="libgazebo_ros_p3d.so">
|
||||
<alwaysOn>true</alwaysOn>
|
||||
<updateRate>50.0</updateRate>
|
||||
<bodyName>${prefix}base_footprint</bodyName>
|
||||
<topicName>base_pose_ground_truth</topicName>
|
||||
<gaussianNoise>0.01</gaussianNoise>
|
||||
<frameName>map</frameName>
|
||||
<xyzOffsets>0 0 0</xyzOffsets>
|
||||
<rpyOffsets>0 0 0</rpyOffsets>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
22
mir_robot/mir_description/urdf/include/mir.transmission.xacro
Executable file
22
mir_robot/mir_description/urdf/include/mir.transmission.xacro
Executable file
@@ -0,0 +1,22 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="mir_wheel_transmission" params="prefix locationprefix">
|
||||
<transmission name="${prefix}${locationprefix}_wheel_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${prefix}${locationprefix}_wheel_joint">
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${prefix}${locationprefix}_wheel_motor">
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="mir_wheel_transmissions" params="prefix">
|
||||
<xacro:mir_wheel_transmission prefix="${prefix}" locationprefix="left"/>
|
||||
<xacro:mir_wheel_transmission prefix="${prefix}" locationprefix="right"/>
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
12
mir_robot/mir_description/urdf/include/mir_100_v1.urdf.xacro
Executable file
12
mir_robot/mir_description/urdf/include/mir_100_v1.urdf.xacro
Executable file
@@ -0,0 +1,12 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro"
|
||||
name="mir_100" >
|
||||
|
||||
<!-- This file is only for backward compatibility before the "mir_100" to "mir" rename. -->
|
||||
|
||||
<xacro:include filename="$(find mir_description)/urdf/include/mir_v1.urdf.xacro" />
|
||||
|
||||
<xacro:macro name="mir_100" params="prefix">
|
||||
<xacro:mir prefix="${prefix}" />
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
308
mir_robot/mir_description/urdf/include/mir_v1.urdf.xacro
Executable file
308
mir_robot/mir_description/urdf/include/mir_v1.urdf.xacro
Executable file
@@ -0,0 +1,308 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
<xacro:arg name="mir_type" default="mir_250" /> <!-- The MiR variant. Can be "mir_100" or "mir_250" for now.-->
|
||||
<xacro:property name="mir_type" value="$(arg mir_type)" /> <!-- necessary because args cannot be accessed inside ${} expressions -->
|
||||
|
||||
<xacro:include filename="$(find mir_description)/urdf/include/common_properties.urdf.xacro" />
|
||||
<xacro:include filename="$(find mir_description)/urdf/include/imu.gazebo.urdf.xacro" />
|
||||
<xacro:include filename="$(find mir_description)/urdf/include/mir.gazebo.xacro" />
|
||||
<xacro:include filename="$(find mir_description)/urdf/include/mir.transmission.xacro" />
|
||||
<xacro:include filename="$(find mir_description)/urdf/include/sick_s300.urdf.xacro" />
|
||||
|
||||
<xacro:property name="deg_to_rad" value="0.017453293" />
|
||||
|
||||
<!-- The inertia for the MiR platform is intentionally chosen to be smaller than
|
||||
the bounding box and also shifted a bit to the back, because most of the mass
|
||||
is in the lower center back (because of the batteries). -->
|
||||
<xacro:property name="mir_base_inertial_x" value="-0.05" />
|
||||
<xacro:property name="mir_base_inertial_y" value="0.0" />
|
||||
<xacro:property name="mir_base_inertial_z" value="0.15" />
|
||||
<xacro:property name="mir_base_inertial_x_length" value="0.50" />
|
||||
<xacro:property name="mir_base_inertial_y_length" value="0.30" />
|
||||
<xacro:property name="mir_base_inertial_z_length" value="0.20" />
|
||||
|
||||
<xacro:if value="${mir_type == 'mir_100'}">
|
||||
<xacro:property name="mir_base_mass" value="77.0" />
|
||||
<xacro:property name="mir_act_wheel_radius" value="0.0625" />
|
||||
<xacro:property name="mir_act_wheel_width" value="0.032" />
|
||||
<xacro:property name="mir_act_wheel_mass" value="1.0" />
|
||||
<xacro:property name="mir_act_wheel_dx" value="0.037646" />
|
||||
<xacro:property name="mir_act_wheel_dy" value="0.222604" />
|
||||
</xacro:if>
|
||||
|
||||
<xacro:if value="${mir_type == 'mir_250'}">
|
||||
<xacro:property name="mir_base_mass" value="97.0" />
|
||||
<xacro:property name="mir_act_wheel_radius" value="0.100" />
|
||||
<xacro:property name="mir_act_wheel_width" value="0.038" />
|
||||
<xacro:property name="mir_act_wheel_mass" value="1.0" />
|
||||
<xacro:property name="mir_act_wheel_dx" value="-0.004485" />
|
||||
<xacro:property name="mir_act_wheel_dy" value="0.2015" />
|
||||
</xacro:if>
|
||||
|
||||
<xacro:property name="mir_caster_wheel_radius" value="0.0625" />
|
||||
<xacro:property name="mir_caster_wheel_width" value="0.032" />
|
||||
<xacro:property name="mir_caster_wheel_mass" value="1.0" />
|
||||
<xacro:property name="mir_caster_wheel_dx" value="-0.0382" />
|
||||
<xacro:property name="mir_caster_wheel_dy" value="0" />
|
||||
<xacro:property name="mir_caster_wheel_dz" value="-0.094" />
|
||||
<xacro:property name="mir_front_caster_wheel_base_dx" value="0.3037" />
|
||||
<xacro:if value="${mir_type == 'mir_100'}">
|
||||
<xacro:property name="mir_back_caster_wheel_base_dx" value="0.3078" />
|
||||
<xacro:property name="mir_caster_wheel_base_dy" value="0.203" />
|
||||
</xacro:if>
|
||||
|
||||
<xacro:if value="${mir_type == 'mir_250'}">
|
||||
<xacro:property name="mir_back_caster_wheel_base_dx" value="0.296" />
|
||||
<xacro:property name="mir_caster_wheel_base_dy" value="0.188" />
|
||||
</xacro:if>
|
||||
<xacro:property name="mir_caster_wheel_base_dz" value="${mir_caster_wheel_radius - mir_caster_wheel_dz}" />
|
||||
|
||||
<!-- from visually matching up the meshes of the MiR and the laser scanner -->
|
||||
<xacro:if value="${mir_type == 'mir_100'}">
|
||||
<xacro:property name="laser_dx" value="0.392" />
|
||||
<xacro:property name="laser_dy" value="0.2358" />
|
||||
<xacro:property name="laser_dz" value="0.1914" />
|
||||
</xacro:if>
|
||||
|
||||
<xacro:if value="${mir_type == 'mir_250'}">
|
||||
<xacro:property name="laser_dx" value="0.315" />
|
||||
<xacro:property name="laser_dy" value="0.205" />
|
||||
<xacro:property name="laser_dz" value="0.1914" />
|
||||
</xacro:if>
|
||||
|
||||
|
||||
<xacro:macro name="actuated_wheel" params="prefix locationprefix locationright">
|
||||
<joint name="${prefix}${locationprefix}_wheel_joint" type="continuous">
|
||||
<origin xyz="0.0 ${-mir_act_wheel_dy * locationright} ${mir_act_wheel_radius}" rpy="0 0 0" />
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}${locationprefix}_wheel_link" />
|
||||
<axis xyz="0 1 0" />
|
||||
<limit effort="100" velocity="20.0" />
|
||||
</joint>
|
||||
|
||||
<link name="${prefix}${locationprefix}_wheel_link">
|
||||
<xacro:cylinder_inertial mass="${mir_act_wheel_mass}" radius="${mir_act_wheel_radius}" length="${mir_act_wheel_width}">
|
||||
<origin xyz="0 0 0" rpy="${0.5 * pi} 0 0" />
|
||||
</xacro:cylinder_inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="${pi/2} 0 0" />
|
||||
<geometry>
|
||||
<cylinder radius="${mir_act_wheel_radius}" length="${mir_act_wheel_width}" />
|
||||
</geometry>
|
||||
<xacro:insert_block name="material_black" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="${pi/2} 0 0" />
|
||||
<geometry>
|
||||
<cylinder radius="${mir_act_wheel_radius}" length="${mir_act_wheel_width}" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<gazebo reference="${prefix}${locationprefix}_wheel_link">
|
||||
<material>Gazebo/FlatBlack</material>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="caster_wheel" params="prefix locationprefix locationright wheel_base_dx">
|
||||
<!-- caster hub -->
|
||||
<joint name="${prefix}${locationprefix}_caster_rotation_joint" type="continuous">
|
||||
<origin xyz="${wheel_base_dx} ${-mir_caster_wheel_base_dy * locationright} ${mir_caster_wheel_base_dz}" rpy="0 0 0" />
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}${locationprefix}_caster_rotation_link" />
|
||||
<axis xyz="0 0 1" />
|
||||
<dynamics damping="0.01" friction="0.0"/>
|
||||
</joint>
|
||||
|
||||
<link name="${prefix}${locationprefix}_caster_rotation_link">
|
||||
<inertial>
|
||||
<!-- <origin xyz="0 0 -0.042500000044" rpy="${0.5 * pi} ${24 * deg_to_rad} ${1.5 * pi}" /> -->
|
||||
<origin xyz="0 0 -0.042500000044" rpy="${24 * deg_to_rad} 0 ${0.5 * pi} " />
|
||||
<mass value="0.3097539019" />
|
||||
<inertia
|
||||
ixx="0.0005844517978"
|
||||
ixy="0"
|
||||
ixz="0"
|
||||
iyy="0.00052872551237"
|
||||
iyz="0"
|
||||
izz="0.00017923555074" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://mir_description/meshes/visual/caster_wheel_base.stl" />
|
||||
</geometry>
|
||||
<xacro:if value="${mir_type == 'mir_100'}">
|
||||
<xacro:insert_block name="material_silver" />
|
||||
</xacro:if>
|
||||
<xacro:if value="${mir_type == 'mir_250'}">
|
||||
<xacro:insert_block name="material_black" />
|
||||
</xacro:if>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://mir_description/meshes/collision/caster_wheel_base.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<gazebo reference="${prefix}${locationprefix}_caster_rotation_link">
|
||||
<xacro:if value="${mir_type == 'mir_100'}">
|
||||
<material>Gazebo/Grey</material>
|
||||
</xacro:if>
|
||||
<xacro:if value="${mir_type == 'mir_250'}">
|
||||
<material>Gazebo/FlatBlack</material>
|
||||
</xacro:if>
|
||||
</gazebo>
|
||||
|
||||
<!-- caster wheel -->
|
||||
<joint name="${prefix}${locationprefix}_caster_wheel_joint" type="continuous">
|
||||
<origin xyz="${mir_caster_wheel_dx} ${-mir_caster_wheel_dy * locationright} ${mir_caster_wheel_dz}" rpy="0 0 0" />
|
||||
<parent link="${prefix}${locationprefix}_caster_rotation_link" />
|
||||
<child link="${prefix}${locationprefix}_caster_wheel_link" />
|
||||
<axis xyz="0 1 0" />
|
||||
</joint>
|
||||
|
||||
<link name="${prefix}${locationprefix}_caster_wheel_link">
|
||||
<xacro:cylinder_inertial mass="${mir_caster_wheel_mass}" radius="${mir_caster_wheel_radius}" length="${mir_caster_wheel_width}">
|
||||
<origin xyz="0 0 0" rpy="${0.5 * pi} 0 0" />
|
||||
</xacro:cylinder_inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="${pi/2} 0 0" />
|
||||
<geometry>
|
||||
<cylinder radius="${mir_caster_wheel_radius}" length="${mir_caster_wheel_width}" />
|
||||
</geometry>
|
||||
<xacro:insert_block name="material_black" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="${pi/2} 0 0" />
|
||||
<geometry>
|
||||
<cylinder radius="${mir_caster_wheel_radius}" length="${mir_caster_wheel_width}" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<gazebo reference="${prefix}${locationprefix}_caster_wheel_link">
|
||||
<material>Gazebo/FlatBlack</material>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="mir" params="prefix">
|
||||
<link name="${prefix}base_footprint" />
|
||||
|
||||
<joint name="${prefix}base_joint" type="fixed">
|
||||
<parent link="${prefix}base_footprint" />
|
||||
<child link="${prefix}base_link" />
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
</joint>
|
||||
|
||||
<link name="${prefix}base_link">
|
||||
<xacro:box_inertial mass="${mir_base_mass}" x="${mir_base_inertial_x_length}" y="${mir_base_inertial_y_length}" z="${mir_base_inertial_z_length}">
|
||||
<origin xyz="${mir_base_inertial_x + mir_act_wheel_dx} ${mir_base_inertial_y} ${mir_base_inertial_z}" rpy="0 0 0" />
|
||||
</xacro:box_inertial>
|
||||
<visual>
|
||||
<origin xyz="${mir_act_wheel_dx} 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://mir_description/meshes/visual/${mir_type}_base.stl" />
|
||||
</geometry>
|
||||
<xacro:if value="${mir_type == 'mir_100'}">
|
||||
<xacro:insert_block name="material_white" />
|
||||
</xacro:if>
|
||||
<xacro:if value="${mir_type == 'mir_250'}">
|
||||
<xacro:insert_block name="material_dark_grey" />
|
||||
</xacro:if>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="${mir_act_wheel_dx} 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://mir_description/meshes/collision/${mir_type}_base.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<gazebo reference="${prefix}base_link">
|
||||
<xacro:if value="${mir_type == 'mir_100'}">
|
||||
<material>Gazebo/White</material>
|
||||
</xacro:if>
|
||||
<xacro:if value="${mir_type == 'mir_250'}">
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</xacro:if>
|
||||
</gazebo>
|
||||
|
||||
<!-- IMU -->
|
||||
<joint name="${prefix}base_link_to_imu_joint" type="fixed">
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}imu_link" />
|
||||
<origin xyz="0.0 0.0 0.25" rpy="0 0 0" /> <!-- same as real MiR -->
|
||||
</joint>
|
||||
|
||||
<link name="${prefix}imu_link" />
|
||||
|
||||
<xacro:imu_gazebo link="${prefix}imu_link" imu_topic="imu_data" update_rate="50.0" />
|
||||
|
||||
<!-- Create an alias for imu_link. This is necessary because the real MiR's
|
||||
TF has imu_link, but the imu_data topic is published in the imu_frame
|
||||
frame. -->
|
||||
<joint name="${prefix}imu_link_to_imu_frame_joint" type="fixed">
|
||||
<parent link="${prefix}imu_link" />
|
||||
<child link="${prefix}imu_frame" />
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
</joint>
|
||||
|
||||
<link name="${prefix}imu_frame" />
|
||||
|
||||
<!-- Laser scanners -->
|
||||
<joint name="${prefix}base_link_to_front_laser_joint" type="fixed">
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}front_laser_link" />
|
||||
<origin xyz="${laser_dx + mir_act_wheel_dx} ${laser_dy} ${laser_dz}" rpy="0.0 0.0 ${0.25 * pi}" />
|
||||
</joint>
|
||||
<xacro:sick_s300 prefix="${prefix}" link="front_laser_link" topic="f_scan" />
|
||||
|
||||
<joint name="${prefix}base_link_to_back_laser_joint" type="fixed">
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}back_laser_link" />
|
||||
<origin xyz="${-laser_dx + mir_act_wheel_dx} ${-laser_dy} ${laser_dz}" rpy="0.0 0.0 ${-0.75 * pi}" />
|
||||
</joint>
|
||||
|
||||
<xacro:sick_s300 prefix="${prefix}" link="back_laser_link" topic="b_scan" />
|
||||
|
||||
<!-- Ultrasound sensors -->
|
||||
<joint name="${prefix}us_1_joint" type="fixed"> <!-- right ultrasound -->
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}us_1_frame" />
|
||||
<origin xyz="0.45 -0.12 0.16 " rpy="0 0 0" /> <!-- from visually matching to the mesh of the MiR -->
|
||||
</joint>
|
||||
|
||||
<link name="${prefix}us_1_frame" />
|
||||
|
||||
<joint name="${prefix}us_2_joint" type="fixed"> <!-- left ultrasound -->
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}us_2_frame" />
|
||||
<origin xyz="0.45 0.12 0.16 " rpy="0 0 0" /> <!-- from visually matching to the mesh of the MiR -->
|
||||
</joint>
|
||||
|
||||
<link name="${prefix}us_2_frame" />
|
||||
|
||||
<!-- wheels -->
|
||||
<xacro:actuated_wheel prefix="${prefix}" locationprefix="left" locationright="-1"/>
|
||||
<xacro:actuated_wheel prefix="${prefix}" locationprefix="right" locationright="1"/>
|
||||
<xacro:caster_wheel prefix="${prefix}" locationprefix="fl" locationright="-1" wheel_base_dx="${mir_front_caster_wheel_base_dx + mir_act_wheel_dx}"/>
|
||||
<xacro:caster_wheel prefix="${prefix}" locationprefix="fr" locationright="1" wheel_base_dx="${mir_front_caster_wheel_base_dx + mir_act_wheel_dx}"/>
|
||||
<xacro:caster_wheel prefix="${prefix}" locationprefix="bl" locationright="-1" wheel_base_dx="${-mir_back_caster_wheel_base_dx + mir_act_wheel_dx}"/>
|
||||
<xacro:caster_wheel prefix="${prefix}" locationprefix="br" locationright="1" wheel_base_dx="${-mir_back_caster_wheel_base_dx + mir_act_wheel_dx}"/>
|
||||
|
||||
<joint name="${prefix}base_link_surface_joint" type="fixed">
|
||||
<origin xyz="${mir_act_wheel_dx} 0 0.352" rpy="0 0 0" />
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}surface" />
|
||||
<axis xyz="0 0 1" />
|
||||
</joint>
|
||||
|
||||
<link name="${prefix}surface"/>
|
||||
|
||||
<xacro:mir_wheel_transmissions prefix="${prefix}"/>
|
||||
|
||||
<!-- set the gazebo friction parameters for the wheels -->
|
||||
<xacro:set_all_wheel_frictions prefix="${prefix}"/>
|
||||
|
||||
<xacro:p3d_base_controller prefix="${prefix}" />
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
72
mir_robot/mir_description/urdf/include/sick_s300.urdf.xacro
Executable file
72
mir_robot/mir_description/urdf/include/sick_s300.urdf.xacro
Executable file
@@ -0,0 +1,72 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find mir_description)/urdf/include/common_properties.urdf.xacro" />
|
||||
|
||||
<xacro:property name="laser_x" value="0.156" />
|
||||
<xacro:property name="laser_y" value="0.155" />
|
||||
<xacro:property name="laser_z" value="0.185" />
|
||||
<xacro:property name="laser_mass" value="1.2" />
|
||||
|
||||
<xacro:macro name="sick_s300" params="link topic prefix">
|
||||
<link name="${prefix}${link}">
|
||||
<visual>
|
||||
<origin xyz="0.0 0.0 0.0" rpy="${pi} 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://mir_description/meshes/visual/sick_lms-100.stl" />
|
||||
</geometry>
|
||||
<!-- <xacro:insert_block name="material_yellow" /> -->
|
||||
<xacro:insert_block name="material_black" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0.0 0.0 0.0" rpy="${pi} 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://mir_description/meshes/visual/sick_lms-100.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:box_inertial x="${laser_x}" y="${laser_y}" z="${laser_z}" mass="${laser_mass}">
|
||||
<origin xyz="0 0 0" />
|
||||
</xacro:box_inertial>
|
||||
</link>
|
||||
|
||||
<gazebo reference="${prefix}${link}">
|
||||
<!-- <material value="Gazebo/Yellow" /> -->
|
||||
<material value="Gazebo/FlatBlack" />
|
||||
|
||||
<sensor type="ray" name="${prefix}${link}">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<visualize>false</visualize>
|
||||
<update_rate>12.5</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>541</samples>
|
||||
<resolution>1</resolution> <!-- has to be 1; actual resolution will be computed from number of samples + min_angle/max_angle -->
|
||||
<!-- <min_angle>-2.35619449615</min_angle>
|
||||
<max_angle>2.35619449615</max_angle> -->
|
||||
<min_angle>-2.094395102</min_angle>
|
||||
<max_angle>2.181661565</max_angle>
|
||||
</horizontal>
|
||||
</scan>
|
||||
<range>
|
||||
<min>0.05</min>
|
||||
<max>29.0</max>
|
||||
<resolution>0.01</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<!-- Noise parameters based on published spec for S300 achieving
|
||||
"+-29mm" accuracy at range < 3m (~0.01 of the range) at
|
||||
1 sigma. -->
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.01</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="gazebo_ros_${link}_controller" filename="libgazebo_ros_laser.so">
|
||||
<frameName>${prefix}${link}</frameName>
|
||||
<topicName>${topic}</topicName>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
28
mir_robot/mir_description/urdf/mir.urdf.xacro
Executable file
28
mir_robot/mir_description/urdf/mir.urdf.xacro
Executable file
@@ -0,0 +1,28 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro"
|
||||
name="mir" >
|
||||
|
||||
<!-- MiR base -->
|
||||
<xacro:include filename="$(find mir_description)/urdf/include/mir_v1.urdf.xacro" />
|
||||
<xacro:include filename="$(find mir_description)/urdf/include/common.gazebo.xacro" />
|
||||
|
||||
<xacro:arg name="tf_prefix" default="" />
|
||||
<xacro:property name="tf_prefix_" value="$(arg tf_prefix)" />
|
||||
<xacro:if value="${tf_prefix_ == ''}">
|
||||
<xacro:property name="prefix" value="" />
|
||||
</xacro:if>
|
||||
<xacro:unless value="${tf_prefix_ == ''}">
|
||||
<xacro:property name="prefix" value="${tf_prefix_}/" />
|
||||
</xacro:unless>
|
||||
|
||||
<xacro:mir prefix="${prefix}" />
|
||||
<xacro:controller_plugin_gazebo robot_namespace=""/>
|
||||
|
||||
<!-- instead of the controller_plugin_gazebo, you can use the diffdrive controller like this: -->
|
||||
<!-- <xacro:diff_controller_plugin_gazebo prefix=""
|
||||
left_wheel_joint="left_wheel_joint"
|
||||
right_wheel_joint="right_wheel_joint"
|
||||
wheel_separation="${2*mir_act_wheel_dy}"
|
||||
wheel_radius="${mir_act_wheel_radius}"/> -->
|
||||
|
||||
</robot>
|
||||
Reference in New Issue
Block a user