Range sensor does not detect objects in gazebo
Hi,
I am new to ROS and try to create an urdf file to represent my robot in rviz and gazebo, but I can't get the range sensor to detect objects in the simulator. The message at /arduino/sensor/ir_left always reports 3.75 as range, which is the maximum. For test, I added a gpu_ray scanner and that shows the object just fine in rviz. Spinning the robot in place doesn't help either, so it's doesn't seem to be the sensor angle.
What's wrong? Or any suggestion on how to debug this further?
The sensor definition is below.
Thanks,
Joep
<gazebo reference="ir_left">
<sensor type="ray" name="ir_leftabc">
<pose>0 0 0 0 0 0</pose>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.0</resolution>
<min_angle>-0.01</min_angle>
<max_angle>0.01</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>-0.01</min_angle>
<max_angle>0.01</max_angle>
</vertical>
</scan>
<range>
<min>0.01</min>
<max>3.75</max>
<resolution>0.02</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>5</updateRate>
<topicName>/arduino/sensor/ir_left</topicName>
<frameName>ir_left</frameName>
<visualize>true</visualize>
<radiation>infrared</radiation>
<fov>0.02</fov>
</plugin>
</sensor>
</gazebo>
If you want to use GPU laser plugin the filename of this plugin is called
libgazebo_ros_gpu_laser.so
IMO instead oflibgazebo_ros_range.so
. The library should be saved in/opt/ros/kinetic/lib
location. Try to run gazebo in verbose mode to see if the plugin is loaded or not.Btw this is ROS related forum. For the future post Gazebo related questions here.
Also the type of sensor should be
gpu_ray
instead ofray
.@i4ncelot - thanks for your reply! I'm trying to create a sensor_msgs/Range topic, not laserscan. Laserscan works okay. Tried to check the gazebo log at the location shown in the launch window. There are a few logfiles there, but none with gazebo in the name or with 'laser' or 'ray' in it.
My bad, I thought you wanted to use the
gpu_ray
sensor. I've tried your model and it works for me just fine when I subscribe to/arduino/sensor/ir_left
topic. Can you edit your question with the launch file you use? Have you tried to launch gazebo withverbose
option?