Transférer les fichiers vers 'Projet/pioneer_description/urdf'

This commit is contained in:
Hadrien 2020-06-27 10:21:51 +02:00
parent 9d8b2a1791
commit af0081f05b
4 changed files with 928 additions and 0 deletions

View file

@ -0,0 +1,56 @@
<?xml version="1.0"?>
<robot>
<material name="ChassisRed">
<color rgba="0.851 0.0 0.0 1.0"/>
</material>
<material name="SonarYellow">
<color rgba="0.715 0.583 0.210 1.0"/>
</material>
<material name="WheelBlack">
<color rgba="0.117 0.117 0.117 1.0"/>
</material>
<material name="HubcapYellow">
<color rgba="1.0 0.811 0.151 1.0"/>
</material>
<material name="TopBlack">
<color rgba="0.038 0.038 0.038 1.0"/>
</material>
<material name="swivel">
<color rgba="0.5 0.5 0.5 1"/>
</material>
<material name="HubcapGrey">
<color rgba="0.4 0.4 0.4 1"/>
</material>
<material name="CameraGreen">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="HatGrey">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<material name="PilierGrey">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<material name="PlaqueGrey">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<material name="OrbbecAstraGrey">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<material name="RplidarBlack">
<color rgba="0.117 0.117 0.117 1.0"/>
</material>
</robot>

View file

@ -0,0 +1,213 @@
<?xml version="1.0"?>
<robot>
<!-- ros_control plugin -->
<!--<gazebo>
<plugin name="differential_drive_controller" filename="libDiffDrivePlugin.so">
<updateRate>100.0</updateRate>
<robotNamespace>pioneer</robotNamespace>
<left_joint>base_left_wheel_joint</left_joint>
<right_joint>base_right_wheel_joint</right_joint>
<torque>200</torque>
<topicName>cmd_vel</topicName>
</plugin>
</gazebo>-->
<!-- START: Not sure if I need this, may allow for rosservice calls to gazebo joint manager -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>pioneer</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
<!-- END: Not sure if I need this -->
<gazebo>
<plugin filename="libgazebo_ros_diff_drive.so" name="differential_drive_controller">
<alwaysOn>true</alwaysOn>
<updateRate>100</updateRate>
<leftJoint>base_left_wheel_joint</leftJoint>
<rightJoint>base_right_wheel_joint</rightJoint>
<torque>5</torque>
<wheelSeparation>0.39</wheelSeparation>
<wheelDiameter>0.15</wheelDiameter>
<commandTopic>pioneer/cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<odometrySource>world</odometrySource>
<robotBaseFrame>base_link</robotBaseFrame>
<publishTf>true</publishTf>
<publishOdomTF>true</publishOdomTF>
<publishWheelTF>true</publishWheelTF>
<publishWheelJointState>true</publishWheelJointState>
<wheelAcceleration>0</wheelAcceleration>
<wheelTorque>5</wheelTorque>
<rosDebugLevel>na</rosDebugLevel>
<legacyMode>true</legacyMode>
</plugin>
</gazebo>
<!--<gazebo>
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
<updateRate>100.0</updateRate>
<robotNamespace>/pioneer</robotNamespace>
<leftFrontJoint>base_left_wheel_joint</leftFrontJoint>
<rightFrontJoint>base_right_wheel_joint</rightFrontJoint>
<leftRearJoint>base_left_wheel_joint</leftRearJoint>
<rightRearJoint>base_right_wheel_joint</rightRearJoint>
<wheelSeparation>0.39</wheelSeparation>
<wheelDiameter>0.15</wheelDiameter>
<robotBaseFrame>base_link</robotBaseFrame>
<torque>200</torque>
<topicName>cmd_vel</topicName>
</plugin>
</gazebo>-->
<!-- Chassis -->
<gazebo reference="chassis">
<material value="Gazebo/Red"/>
</gazebo>
<!-- Top -->
<gazebo reference="top_plate">
<material value="Gazebo/Black"/>
</gazebo>
<!-- Swivel -->
<gazebo reference="swivel">
<material value="Gazebo/Grey"/>
</gazebo>
<!-- Center Wheel + Hubcap -->
<gazebo reference="center_hubcap">
<material value="Gazebo/Grey"/>
</gazebo>
<gazebo reference="center_wheel">
<material value="Gazebo/Black"/>
</gazebo>
<gazebo reference="left_hub">
<material value="Gazebo/Yellow"/>
</gazebo>
<gazebo reference="left_wheel">
<material value="Gazebo/Black"/>
</gazebo>
<gazebo reference="right_hub">
<material value="Gazebo/Yellow"/>
</gazebo>
<gazebo reference="right_wheel">
<material value="Gazebo/Black"/>
</gazebo>
<!-- Front + Back Sonar -->
<gazebo reference="front_sonar">
<material value="Gazebo/Yellow"/>
</gazebo>
<gazebo reference="back_sonar">
<material value="Gazebo/Yellow"/>
</gazebo>
<!-- pilier -->
<gazebo reference="pilier_link">
<material value="Gazebo/Grey"/>
</gazebo>
<!-- plaque suport RPLIDAR -->
<gazebo reference="plaque_link">
<material value="Gazebo/Grey"/>
</gazebo>
<!-- OrbbecAstra -->
<gazebo reference="OrbbecAstra_link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material value="Gazebo/Grey"/>
</gazebo>
<!-- RPLIDAR-A2 -->
<gazebo reference="laser">
<material value="Gazebo/Black"/>
</gazebo>
<gazebo reference="laser">
<sensor type="ray" name="RPlidar_A2">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>40.0</update_rate>
<ray>
<scan>
<horizontal>
<samples>550</samples>
<resolution>1</resolution>
<min_angle>-3.1415</min_angle>
<max_angle>3.1415</max_angle>
</horizontal>
</scan>
<range>
<min>0.15</min>
<max>12.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<!-- Noise parameters based on published spec for Hokuyo laser achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
stddev of 0.01m will put 99.7% of samples within 0.03m of the true reading. -->
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>base_scan</topicName>
<frameName>laser</frameName>
</plugin>
</sensor>
</gazebo>
<!-- OrbbecAstra -->
<gazebo reference="OrbbecAstra_link">
<sensor name="camera" type="depth">
<update_rate>30</update_rate>
<camera>
<horizontal_fov>1.047198</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.6</near>
<far>8</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_openni_kinect.so">
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>1.0</updateRate>
<cameraName>camera_ir</cameraName>
<imageTopicName>/camera/color/image_raw</imageTopicName>
<cameraInfoTopicName>/camera/color/camera_info</cameraInfoTopicName>
<depthImageTopicName>/camera/depth/image_raw</depthImageTopicName>
<depthImageInfoTopicName>/camera/depth/camera_info</depthImageInfoTopicName>
<pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
<frameName>OrbbecAstra_link</frameName>
<pointCloudCutoff>0.6</pointCloudCutoff>
<pointCloudCutoffMax>8.0</pointCloudCutoffMax>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>
</robot>

View file

@ -0,0 +1,548 @@
<?xml version="1.0"?>
<!-- Adapted from the p2os package, see http://wiki.ros.org/p2os -->
<!-- Git repository at https://github.com/allenh1/p2os -->
<robot name="pioneer3dx" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find pioneer_description)/urdf/pioneer3dx_wheel.xacro"/>
<xacro:include filename="$(find pioneer_description)/urdf/materials.xacro" />
<xacro:include filename="$(find pioneer_description)/urdf/pioneer.gazebo" />
<!-- Base link to interface with gmapping and move_base -->
<link name="base_link"/>
<!-- Chassis -->
<joint name="chassis_joint" type="fixed">
<origin xyz="-0.045 0 0.148" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="chassis"/>
</joint>
<link name="chassis">
<visual name="chassis_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="pioneer_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/chassis.stl"/>
</geometry>
<material name="ChassisRed"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/chassis.stl"/>
<!--box size="0.43 0.277 0.17"/-->
</geometry>
</collision>
<inertial>
<mass value="5.67"/>
<inertia ixx="0.07" ixy="0" ixz="0"
iyy="0.08" iyz="0"
izz="0.10"
/>
</inertial>
</link>
<!-- Top -->
<joint name="base_top_joint" type="fixed">
<origin xyz="-0.045 0 0.234" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="top_plate"/>
</joint>
<link name="top_plate">
<visual>
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0"/>
<inertia ixx="1" ixy="0" ixz="0"
iyy="1" iyz="0"
izz="1"/>
</inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="top_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/top.stl"/>
</geometry>
<material name="TopBlack"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/top.stl"/>
<!--box size="0.44 0.38 0.005"/-->
</geometry>
</collision>
</link>
<!-- Swivel -->
<joint name="base_swivel_joint" type="continuous">
<origin xyz="-0.185 0 0.055" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<!--<anchor xyz="0 0 0"/>
<limit effort="100" velocity="100" k_velocity="0" />
<joint_properties damping="0.0" friction="0.0" />-->
<parent link="base_link"/>
<child link="swivel"/>
</joint>
<link name="swivel">
<inertial>
<mass value="0.1"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.01" ixy="0" ixz="0"
iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="pioneer_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/swivel.stl"/>
</geometry>
<material name="swivel"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/swivel.stl"/>
</geometry>
</collision>
</link>
<!-- Center Wheel + Hubcap -->
<link name="center_hubcap">
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="pioneer_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/center_hubcap.stl"/>
</geometry>
<material name="HubcapGrey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/center_hubcap.stl"/>
</geometry>
</collision>
</link>
<joint name="swivel_hubcap_joint" type="continuous">
<origin xyz="-0.026 0 -0.016" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<!--<anchor xyz="0 0 0"/>
<limit effort="1000" velocity="1000" k_velocity="0" />
<joint_properties damping="0.0" friction="0.0" />-->
<parent link="swivel"/>
<child link="center_wheel"/>
</joint>
<link name="center_wheel">
<inertial>
<mass value="0.1"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="pioneer_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/center_wheel.stl"/>
</geometry>
<material name="WheelBlack"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/center_wheel.stl"/>
<!--<cylinder radius="0.0375" length="0.03"/>-->
</geometry>
</collision>
</link>
<joint name="center_wheel_joint" type="fixed">
<origin xyz="-0.0035 0 -0.001" rpy="0 0 0"/>
<parent link="center_wheel"/>
<child link="center_hubcap"/>
</joint>
<!-- Left Wheel -->
<joint name="base_left_wheel_joint" type="continuous">
<origin xyz="0 0.155 0.093" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<!--<anchor xyz="0 0 0"/>
<limit effort="1000" velocity="1000" k_velocity="0" />
<joint_properties damping="0.0" friction="0.0" />-->
<parent link="base_link"/>
<child link="left_wheel"/>
</joint>
<link name="left_wheel">
<inertial>
<mass value="0.1"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/left_wheel.stl"/>
</geometry>
<material name="WheelBlack"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/left_wheel.stl"/>
<!--<cylinder radius="0.092" length="0.04"/>-->
</geometry>
</collision>
</link>
<joint name="left_wheel_hub_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="left_wheel"/>
<child link="left_hub"/>
</joint>
<link name="left_hub">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/left_hubcap.stl"/>
</geometry>
<material name="HubcapYellow"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/left_hubcap.stl"/>
</geometry>
</collision>
</link>
<!-- Right Wheel -->
<joint name="base_right_wheel_joint" type="continuous">
<origin xyz="0 -0.155 0.093" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<!--<anchor xyz="0 0 0"/>
<limit effort="1000" velocity="1000" k_velocity="0" />
<joint_properties damping="0.0" friction="0.0" />-->
<parent link="base_link"/>
<child link="right_wheel"/>
</joint>
<link name="right_wheel">
<inertial>
<mass value="0.1"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/right_wheel.stl"/>
</geometry>
<material name="WheelBlack"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/right_wheel.stl"/>
<!--<cylinder radius="0.092" length="0.04"/>-->
</geometry>
</collision>
</link>
<joint name="right_wheel_hub_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="right_wheel"/>
<child link="right_hub"/>
</joint>
<link name="right_hub">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/right_hubcap.stl"/>
</geometry>
<material name="HubcapYellow"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/right_hubcap.stl"/>
</geometry>
</collision>
</link>
<!-- Front + Back Sonar -->
<link name="front_sonar">
<inertial>
<mass value="0.0001"/>
<origin xyz="0 0 0"/>
<inertia ixx="1" ixy="0" ixz="0"
iyy="1" iyz="0" izz="1"/>
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="pioneer_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/front_sonar.stl"/>
</geometry>
<material name="SonarYellow"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/front_sonar.stl"/>
</geometry>
</collision>
</link>
<joint name="base_front_joint" type="fixed">
<origin xyz="-0.198 0 0.208" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="front_sonar"/>
</joint>
<link name="back_sonar">
<inertial>
<mass value="0.0001"/>
<origin xyz="0 0 0"/>
<inertia ixx="1" ixy="0" ixz="0"
iyy="1" iyz="0" izz="1"/>
</inertial>
<visual name="back_sonar_vis">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="pioneer_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/back_sonar.stl"/>
</geometry>
<material name="SonarYellow"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/back_sonar.stl"/>
</geometry>
</collision>
</link>
<joint name="base_back_joint" type="fixed">
<origin xyz="0.109 0 0.209" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="back_sonar"/>
</joint>
<!-- pilier -->
<joint name="pilier_joint" type="fixed">
<origin xyz="-0.076 0 0.102" rpy="0 0 0"/>
<parent link="top_plate"/>
<child link="pilier_link"/>
</joint>
<link name="pilier_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.15 0.143 0.197"/>
</geometry>
</collision>
<visual>
<origin xyz="0.065 0.0615 0" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.02 0.197"/>
</geometry>
<material name="PilierGrey"/>
</visual>
<visual>
<origin xyz="-0.065 0.0615 0" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.02 0.197"/>
</geometry>
<material name="PilierGrey"/>
</visual>
<visual>
<origin xyz="0.065 -0.0615 0" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.02 0.197"/>
</geometry>
<material name="PilierGrey"/>
</visual>
<visual>
<origin xyz="-0.065 -0.0615 0" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.02 0.197"/>
</geometry>
<material name="PilierGrey"/>
</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>
<!-- plaque suport RPLIDAR -->
<joint name="plaque_joint" type="fixed">
<origin xyz="0 0 0.10" rpy="0 0 0"/>
<parent link="pilier_link"/>
<child link="plaque_link"/>
</joint>
<link name="plaque_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.15 0.143 0.003"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.15 0.143 0.003"/>
</geometry>
<material name="PlaqueGrey"/>
</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>
<!-- OrbbecAstra -->
<joint name="OrbbecAstra_joint" type="fixed">
<origin xyz="0.206 0 0.0375" rpy="0 0 0"/>
<!-- <origin xyz="0.14 0.085 0.0025" rpy="0 0 -1.5708"/>-->
<parent link="top_plate"/>
<child link="OrbbecAstra_link"/>
</joint>
<link name="OrbbecAstra_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="package://pioneer_description/meshes/OrbbecAstra.stl"/>
<!-- <box size="0.05 0.07 0.10"/> -->
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="package://pioneer_description/meshes/OrbbecAstra.stl"/>
</geometry>
<material name="OrbbecAstraGrey"/>
</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>
<!-- RPLIDAR-A2-->
<joint name="rplidarA2_joint" type="fixed">
<origin xyz="0 0 0.0265" rpy="0 0 0"/>
<parent link="plaque_link"/>
<child link="laser"/>
</joint>
<link name="laser">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="package://pioneer_description/meshes/rplidar-a2m4-r1.stl"/>
<!-- <box size="0.05 0.07 0.10"/> -->
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="package://pioneer_description/meshes/rplidar-a2m4-r1.stl"/>
<!-- <box size="0.05 0.07 0.10"/> -->
</geometry>
<material name="RplidarBlack"/>
</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>
<!-- Hat -->
<!-- <joint name="hat_joint" type="fixed">-->
<!-- <origin xyz="0.0 0 0.0255" rpy="0 0 0"/>-->
<!-- <parent link="top_plate"/>-->
<!-- <child link="hat_link"/>-->
<!-- </joint>-->
<!-- <link name="hat_link">-->
<!-- <collision>-->
<!-- <origin xyz="0 0 0" rpy="0 0 0"/>-->
<!-- <geometry>-->
<!-- <box size="0.15 0.2 0.4"/>-->
<!-- </geometry>-->
<!-- </collision>-->
<!-- <visual>-->
<!-- <origin xyz="0 0 0" rpy="0 0 0"/>-->
<!-- <geometry>-->
<!-- <box size="0.15 0.2 0.4"/>-->
<!-- </geometry>-->
<!-- <material name="HatGrey"/>-->
<!-- </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>-->
<!-- START: Not sure if I need this, may allow for rosservice calls to gazebo joint manager -->
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_left_wheel_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="tran2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_right_wheel_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor2">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- END: Not sure if I need this -->
</robot>

View file

@ -0,0 +1,111 @@
<?xml version="1.0"?>
<robot
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro"
>
<!--<xacro:include filename="$(find pioneer_description)/defs/materials.xacro"/>-->
<!-- Properties (Constants) -->
<xacro:property name="M_PI" value="3.14159"/>
<!-- Right/Left Hubcap + Wheel -->
<xacro:macro name="p3dx_wheel" params="suffix parent reflect">
<link name="p3dx_${suffix}_wheel">
<inertial>
<mass value="0.5"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="0" ixz="0"
iyy="0.015218160428" iyz="0" izz="0.011763977943"/>
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="pioneer_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/${suffix}_wheel.stl"/>
</geometry>
<material name="WheelBlack">
<color rgba="0.117 0.117 0.117 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${-3.1415927/2} 0 0"/>
<geometry>
<!--<mesh filename="package://pioneer_description/meshes/p3dx_meshes/${suffix}_wheel.stl"/>-->
<cylinder radius="0.09" length="0.01"/>
</geometry>
</collision>
</link>
<joint name="base_${suffix}_hubcap_joint" type="fixed">
<!--<origin xyz="0 ${reflect*0.158} 0.091" rpy="0 0 0"/>-->
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="p3dx_${suffix}_wheel"/>
<child link="p3dx_${suffix}_hubcap"/>
</joint>
<link name="p3dx_${suffix}_hubcap">
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="0" ixz="0"
iyy="0.015218160428" iyz="0" izz="0.011763977943"/>
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="pioneer_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/${suffix}_hubcap.stl"/>
</geometry>
<material name="HubcapYellow">
<color rgba="1.0 0.811 0.151 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0 0 0"/>
</geometry>
</collision>
</link>
<transmission type="pr2_mechanism_model/SimpleTransmission" name="${parent}_${suffix}_wheel_trans">
<actuator name="base_${suffix}_wheel_motor" />
<joint name="base_${suffix}_wheel_joint" />
<mechanicalReduction>${reflect * 624/35 * 80/19}</mechanicalReduction>
</transmission>
<joint name="base_${suffix}_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<anchor xyz="0 0 0"/>
<limit effort="100" velocity="100" />
<joint_properties damping="0.0" friction="0.0" />
<origin xyz="0 ${reflect*0.158} 0.091" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="p3dx_${suffix}_wheel"/>
</joint>
<gazebo reference="p3dx_${suffix}_hubcap">
<material value="Gazebo/Yellow"/>
</gazebo>
<gazebo reference="p3dx_${suffix}_wheel">
<material value="Gazebo/Black"/>
<elem key="mu1" value="0.5" />
<elem key="mu2" value="50.0" />
<elem key="kp" value="100000000.0" />
<elem key="kd" value="1.0" />
</gazebo>
</xacro:macro>
</robot>