ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Gazebo segfaults when Lidar senses an obstacle

asked 2019-03-02 11:39:10 -0500

viswa_1211 gravatar image

updated 2019-03-06 01:21:44 -0500

I am using Ros Kinetic on Ubuntu 16.04. I am trying to simulate a quadrotor with lidar attached to it.

I have found the Rotors_Simulator repository and manually added a Hokuyo lidar for simulation in Gazebo using the following code:

 <!-- Hokuyo Lidar Range Sensor -->
    <xacro:macro name="hokuyo_utm30lx" params="robot_namespace *origin update_rate ray_count min_angle max_angle">
      <link name="${robot_namespace}/laser_lidar_link12">
  <inertial>
    <mass value="0.001" />
    <origin xyz="0 0 0" rpy="0 0 0" />
    <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
  </inertial>
  <visual>
          <geometry>
            <!--<mesh filename="package://turtlebot_description/meshes/sensors/hokuyo_utm30lx/hokuyo_utm_30lx.dae"/> -->
            <box size="0.05 0.05 0.02"/>
          </geometry>
  </visual>
  <collision>
    <origin xyz="0 0 -0.0115" rpy="0 0 0" />
          <geometry>
            <box size="0.058 0.058 0.087" />
            <!--<mesh filename="package://hector_sensors_description/meshes/hokuyo_utm30lx/hokuyo_utm_30lx.stl"/>-->
          </geometry>
  </collision>
      </link>
      <joint name="laser_lidar_joint" type="fixed">
        <xacro:insert_block name="origin"/>
  <parent link="${robot_namespace}/base_link"/>
  <child link="${robot_namespace}/laser_lidar_link12"/>
      </joint>
      <gazebo reference="${robot_namespace}/laser_lidar_link12">
        <sensor type="ray" name="iris_laser_lidar">
            <pose>0 0 0 0 0 0</pose>
            <visualize>false</visualize>
            <update_rate>${update_rate}</update_rate>
      <ray>
      <scan>
        <horizontal>
          <samples>$(ray_count)</samples>
          <resolution>1</resolution>
          <min_angle>${min_angle}</min_angle>
          <max_angle>${max_angle}</max_angle>
        </horizontal>
      </scan>
      <range>
        <min>0.10</min>
        <max>20.0</max>
        <resolution>0.01</resolution>
      </range>
      <noise>
        <type>Gaussian</type>
        <mean>0.0</mean>
        <stddev>0.01</stddev>
      </noise>
      </ray>
      <plugin name="ray" filename="libgazebo_ros_laser.so">
      <topicName>/scan</topicName>
      <frameName>iris/laser_lidar_link12</frameName>
      <!-- <interface:laser name="gazebo_ros_${laser_suffix}_iface" /> -->
            </plugin>
        </sensor>
      </gazebo>
    </xacro:macro>
 <xacro:hokuyo_utm30lx robot_namespace="${namespace}" min_angle="-1.047" max_angle="1.047"
    update_rate="40" ray_count="120">
    <origin xyz="0 0 0.5" rpy="0 0 0"/>
  </xacro:hokuyo_utm30lx>

I could see the lidar in the simulation, and I did "rostopic echo /scan" to view the messages from the lidar. This happens only when I am using an empty world for simulation. When I am adding an obstacle in the world in lidar's range, the simulation stops with the following message:

Segmentation fault (core dumped) [gazebo-2] process has died [pid 2836, exit code 139, cmd /opt/ros/kinetic/lib/gazebo_ros/gzserver -u -e ode /home/viswa/rotors_pravin/src/rotors_gazebo/worlds/basic.world __name:=gazebo __log:=/home/viswa/.ros/log/d05c3eec-3cf8-11e9-b7d9-bc855666be67/gazebo-2.log]. log file: /home/viswa/.ros/log/d05c3eec-3cf8-11e9-b7d9-bc855666be67/gazebo-2*.log

Further I added a callback with a subscriber:

void callback(const sensor_msgs::LaserScan::ConstPtr& input)
{
  ROS_INFO("Laser Scan Message recieved");
}

The subscriber keeps displaying the following message:

[ INFO] [1551537504.870564767, 5.000000000]: Laser Scan Message recieved

The simulation stops when it detects an obstacle with the same Segmentation Fault.

What needs to be added to make this work?

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
1

answered 2019-03-05 02:38:40 -0500

Delb gravatar image

updated 2019-03-05 03:46:57 -0500

There is something wrong with your macro which prevent you from setting the parameters as desired. At the beginning you define parameters (*origin -> is that a typo ?) and then you don't actually use them.

For example this : <update_rate>1</update_rate>, should be <update_rate>${update_rate}</update_rate>.

So when you call your xacro here :

  <xacro:hokuyo_utm30lx robot_namespace="${namespace}" min_angle="-1.047" max_angle="1.047"
    update_rate="40" ray_count="10">

None of your parameters are actually set to those values (and why is it ${namespace} here ? It should be an actual value).

So you end up with a really odd configuration, I would suggest few things :

  • You tried to set the update rate to 40 which is better than 1 because this is an extremely low value for the update rate so just make sure you actually change the parmeter (as the example above).
  • You have samples set to 3 with a resolution of 10. The resolution is multiplied by the number of samples to define the number of range data points returned. Moreover, if the resolution is greater than 1 the range data is average so I would suggest to set the resolution to 1 and directly define the samples as the number of data you want. For example if you have a 360° lidar and you want a data every I would just set the samples to 360 and resolution to 1.

Edit :

I found from here that we could insert a block by * prefix

You're right it's possible to do that but when you choose to do this you need to insert the block like this :

<xacro:insert_block name="origin" />

Also there might be another thing wrong here when you call the xacro :

<xacro:hokuyo_utm30lx robot_namespace="${namespace}" min_angle="-1.047" max_angle="1.047"
    update_rate="40" ray_count="10">
    <origin xyz="0 0 0.5" rpy="0 0 0"/>
  </xacro:hokuyo_utm30lx>

I'm not sure what will happen and where the origin tag will end up but following the wiki I would call the xacro like this and define the origin inside the macro :

<xacro:hokuyo_utm30lx robot_namespace="${namespace}" min_angle="-1.047" max_angle="1.047"
update_rate="40" ray_count="10" />
edit flag offensive delete link more

Comments

Thanks Delb for the reply. About the *origin, I found from here http://wiki.ros.org/xacro that we could insert a block by * prefix. About $namespace, I had created a property, but I hadn't mentioned it here. Also, I chose small values for resolution just for debug purpose. It still doesn't work.

viswa_1211 gravatar image viswa_1211  ( 2019-03-05 03:12:58 -0500 )edit

It still doesn't work

Do you still have the segfault or another error ? Also can you edit your question to show the modifications you've made ?

Delb gravatar image Delb  ( 2019-03-05 03:48:09 -0500 )edit

I finally found out what was wrong with the code. It was the <noise> block. It looks like I had given wrong values. Without noise block, it works fine.

viswa_1211 gravatar image viswa_1211  ( 2019-03-05 03:51:42 -0500 )edit

Glad it works. But have you checked if the data is correct ? By setting <visualize>true</visualize> you can easliy see that in Gazebo. (I ask you that because with your parameters I have incorrect laser data)

Delb gravatar image Delb  ( 2019-03-05 04:01:03 -0500 )edit

Thanks for the update but I see you've just changed the update_rate meaning your min and max angles won't have the value +/- 1.047 (but 1 instead). Same for your ray_count param.

Delb gravatar image Delb  ( 2019-03-05 04:04:41 -0500 )edit

I have updated that, please check. As mentioned earlier, the model is working fine, if I add the <noise> block. Can you help me with that?

viswa_1211 gravatar image viswa_1211  ( 2019-03-05 04:36:09 -0500 )edit

I don't understand your question, is there still an issue ? For me the noise block isn't problematic I have the same one in an URDF and it doesn't create issues.

Delb gravatar image Delb  ( 2019-03-05 04:45:01 -0500 )edit

Ya. I still have that issue. If I remove the <noise> block, it works fine.

viswa_1211 gravatar image viswa_1211  ( 2019-03-05 05:14:19 -0500 )edit
1

answered 2019-06-11 02:46:01 -0500

dingningyang gravatar image

Same issue here. In my case, gzserver crashes with the following stack trace:

> #0  gazebo::sensors::Noise::Apply (this=0x0,
> _in=_in@entry=1.527150313825224) at /build/gazebo-nhSAPd/gazebo-7.0.0+dfsg/gazebo/sensors/Noise.cc:108                                                                                                                            
> #1  0x00007f1376924cf7 in gazebo::sensors::RaySensor::UpdateImpl
> (this=0x7f12e20f3e70) at
> /build/gazebo-nhSAPd/gazebo-7.0.0+dfsg/gazebo/sensors/RaySensor.cc:574
> 
> #2  0x00007f137692c984 in gazebo::sensors::Sensor::Update
> (this=0x7f12e20f3e70,
> _force=_force@entry=false) at /build/gazebo-nhSAPd/gazebo-7.0.0+dfsg/gazebo/sensors/Sensor.cc:250
> 
> #3  0x00007f1376933195 in gazebo::sensors::SensorManager::SensorContainer::Update
> (this=0x2e3d240, _force=<optimized
> out>) at
> /build/gazebo-nhSAPd/gazebo-7.0.0+dfsg/gazebo/sensors/SensorManager.cc:579
> 
> #4  0x00007f1376936d4b in gazebo::sensors::SensorManager::SensorContainer::RunLoop
> (this=0x2e3d240) at
> /build/gazebo-nhSAPd/gazebo-7.0.0+dfsg/gazebo/sensors/SensorManager.cc:534
> 
> #5  0x00007f13741805d5 in ?? () from /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0
> 
> #6  0x00007f13766956ba in start_thread (arg=0x7f12fe8ba700) at
> pthread_create.c:333                  
> 
> #7  0x00007f1376c9741d in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:109

After some digging into various sources, it turns out the type specification of <noise> block was causing the problem: in Gazebo's official documentation, its type property is spelled gaussian, not capitalized Gaussian as found in some tutorials. After making this change, I was able to run the simulated 2d sensor without a problem. Hope this will help you out.

edit flag offensive delete link more

Comments

By the way, my setup is Gazebo 7.0.0 with ROS Kinetic running on Ubuntu 16.04.

dingningyang gravatar image dingningyang  ( 2019-06-11 02:48:30 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-03-02 11:39:10 -0500

Seen: 655 times

Last updated: Mar 06 '19