Hokuyo laser intermittent and not scanning entire area
I added 2 lasers to my robot, one on the left and the other on the right with the intention of combining both scans into one to perform gmapping. Both lasers are positioned near the base of the robot to detect the presence of street kerbs in the mapping process. I am aware gmapping is used for indoors mapping but I'm experimenting with this approach.
The following is the xacro code that generates the right side hokuyo laser:
<xacro:macro name="laser_right">
<gazebo reference="hokuyo_link_right">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>20</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>10.0</max>
<resolution>0.05</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/scan_right</topicName>
<frameName>hokuyo_link_right</frameName>
</plugin>
</sensor>
</gazebo>
<!-- Hokuyo Laser -->
<link name="hokuyo_link_right">
<collision>
<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>
<mesh filename="package://rrbot_description/meshes/hokuyo.dae"/>
</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="laser_joint_right" type="fixed">
<origin xyz="0.0 -0.27 -0.20" rpy="0 0 0"/>
<parent link="chasis"/>
<child link="hokuyo_link_right"/>
</joint>
</xacro:macro>
The scan as visualized in rviz shows the laser from both hukoyos as very intermitent and do not span the space on the right side of the robot. Shown below is the scan from the right side laser:
I experiemted with the RPY values of the laser joint (perhaps the x-axis of the joint needed to be turned in the direction of the scan area), but that did not work.
I would appreciate some help.
Since your field of view is set to +/- pi/2, I would guess that you do want the x-axis pointed to the right as you said (set yaw = -pi/2 in
laser_joint_right
). What happened when you tried that?@tryan: Thank you for your response. Using pi/2 as the yaw value as you suggested gives me a full semi-circle of laser scans on the right-hand side of the robot