Home | Tutorials | Wiki | Issues
Ask Your Question
0

X4 laser sensor limited range

asked 2018-11-20 00:38:01 -0500

hari1234 gravatar image

After i run command "X4_SENSOR_CONFIG_4=1 roslaunch subt_example team.launch", the range of the laserscan in only coming less than than 1 as also shown by below screenshot: image description This was happening for the X2 robot also when i used command: "X2_SENSOR_CONFIG_3=1 roslaunch subt_example team.launch": image description But after i replaced the sensor part of the planar_lidar.urdf.xacro file with below code the range is coming fine for X2 robot:

<sensor type="ray" name="${name}">
  <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>
      <mean>0.0</mean>
      <stddev>0.01</stddev>
    </noise>
  </ray>
   <plugin name="gazebo_ros_planar_lidar" filename="libgazebo_ros_laser.so">
      <topicName>${topic}</topicName>
      <frameName>${name}</frameName>
      <robotNamespace>${robot_namespace}</robotNamespace>
    </plugin>
</sensor>

But still the range of X4 laser scan is under 1. I am running system with 8 gb ram, 300 gb free HD, ubuntu 18.04, and ros melodic with gazebo 9 as described in catkin install tutorial of this subt repository. But im not using any dedicated nvidia gpu, i'm using i5 3rd gen intel cpu.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-11-20 06:16:03 -0500

wentz gravatar image

Looks like the Laser detects a part of the robots collision (thus you can not see the object but the scanner does) I think there are two ways to fix it:

  1. Change <min>0.10</min> to maybe 0.2 or 0.3 or greater so it will start outside of the collision

    (1.1 or make the collision-Element of your robot smaller by changing the sdf/urdf)

  2. Change your sensor to gpu_ray <sensor type="gpu_ray" name="${name}"> and it will only detect visual elements in the simulation

If you have an graphic card i recommend the 2. way, it will increase the performance of the simulation a bit.

edit flag offensive delete link more

Comments

Ok thanks, as you mentioned, the cpu based lase sensor was detecting the collision element also, so after i changed the minimum range to 1 it is working.

hari1234 gravatar imagehari1234 ( 2018-11-20 09:35:39 -0500 )edit

Your welcome :), keep in mind that your laser will not detect objects within 1m.

wentz gravatar imagewentz ( 2018-11-21 03:59:04 -0500 )edit
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2018-11-20 00:38:01 -0500

Seen: 62 times

Last updated: Nov 20 '18