Commit 13d10e3b authored by Capp's avatar Capp

[urdf] add laser link with hokuyo lidar

parent de6b61fd
......@@ -5,6 +5,7 @@
<xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_common_library.urdf.xacro" />
<xacro:include filename="$(find kobuki_description)/urdf/kobuki.urdf.xacro" />
<xacro:include filename="$(find turtlebot_description)/urdf/stacks/hexagons.urdf.xacro"/>
<xacro:include filename="$(find sensor_training)/urdf/spinning_joint.urdf.xacro"/>
<kobuki/>
<stack_hexagons parent="base_link"/>
......@@ -80,85 +81,64 @@
</sensor>
</gazebo>
<joint name="laser_joint" type="continuous">
<axis xyz="0 1 0" />
<origin xyz="0 0 0.3" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="laser_link"/>
<!--limit lower="-1.0" upper="1.0" effort="100.0" velocity="10.0"/-->
<joint name="hokuyo_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="laser_link"/>
<child link="hokuyo_link"/>
</joint>
<link name="laser_link">
<!-- Hokuyo Laser -->
<link name="hokuyo_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${sensor_size} ${sensor_size} ${sensor_size}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${sensor_size} ${sensor_size} ${sensor_size}"/>
</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"/>
<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>
<gazebo reference="laser_link">
<sensor type="ray" name="laser_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>40</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.570796</min_angle>
<max_angle>1.570796</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>30.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_laser" filename="libgazebo_ros_laser.so">
<topicName>scan</topicName>
<frameName>laser_link</frameName>
</plugin>
</sensor>
</gazebo>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"/>
</gazebo>
<transmission name="laser_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="laser_joint">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="laser_motor">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- hokuyo -->
<gazebo reference="hokuyo_link">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>40</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.570796</min_angle>
<max_angle>1.570796</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>30.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>/rrbot/laser/scan</topicName>
<frameName>hokuyo_link</frameName>
</plugin>
</sensor>
</gazebo>
</robot>
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment