Strange wall appears to PointCloud in Rviz when using block_laser plug-in.
Hi friends,
I need your help about a wall displayed in Rvis when using block_laser GAZEBO plug-in.
I placed a sensor with block_laser plugin-in in URDF file as below.
The purpose was to check how it works when the sensor detects a cube.
When I displayed a PointCloud on Rviz, the result looks almost perfect. However, I found a strange huge wall far away.
I didn't place any obstacle there, but it looks like displaying the max distance which I inputted in URDF file.
For my understanding, PointCloud is displaying the reflection from the obstacle or ground. So, this result doesn't make sense to me.
Could any one please tell me what is this wall and how to delete from PointCloud?
Thanks,
ROS:kinetic
GAZEBO:7.11
GAZEBO looks like
Rviz looks like
URDF file is as below
<robot name="block_laser_test">
<property name="M_PI" value="3.14159274"/>
<link name="base_link">
<visual>
<origin xyz="-4.7 0 2.2" rpy="0 0 0"/>
<geometry>
<box size="9.4 4.2 4.4"/>
</geometry>
</visual>
<collision>
<origin xyz="-4.7 0 2.2" rpy="0 0 0" />
<geometry>
<box size="9.4 4.2 4.4"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 2.2" rpy="0 0 0" />
<mass value="0.03" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0" />
</inertial>
</link>
<!-- ground -->
<link name="base_footprint"/>
<joint name="base_link_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin xyz="0 0 0"/>
</joint>
<!-- cardboard box1 -->
<link name="cardboard_box">
<visual>
<origin xyz="8 0 0.25" rpy="0 0 0"/>
<geometry>
<box size="0.5 0.5 0.5"/>
</geometry>
</visual>
<collision>
<origin xyz="8 0 0.25" rpy="0 0 0" />
<geometry>
<box size="0.5 0.5 0.5"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="1.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0" />
</inertial>
</link>
<joint name="cardboard_box_joint" type="fixed">
<parent link="base_footprint"/>
<child link="cardboard_box"/>
<origin xyz="0 0 0"/>
</joint>
<!-- gazebo -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>block_laser_test</robotNamespace>
</plugin>
</gazebo>
<gazebo reference="base_link">
<selfCollide>true</selfCollide>
<mu1 value="0.5" />
<mu2 value="0.5" />
</gazebo>
<!-- Block laser sensor 1 -->
<link name="BLS_1_optical_frame" />
<link name="BLS_1_link">
<visual>
<geometry>
<box size="0.063 0.095 0.090"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.063 0.095 0.090"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<joint name="BLS_1_base_joint" type="fixed">
<origin xyz="0 0 1.0" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="BLS_1_optical_frame"/>
</joint>
<joint name="BLS_1_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="BLS_1_optical_frame"/>
<child link="BLS_1_link"/>
</joint>
<!-- gazebo Block laser sensor 1 ...