Laser Scanner Gazebo Plugin Crashes on Contact
Hello,
I have the attached urdf and xacro files for a small differential drive robot. I am able to launch the model in rviz, see the laser scanner beams and get the topic. However when any other model touches the beams gazebo segfaults with:
Thread 35 "gzserver" received signal SIGSEGV, Segmentation fault. [Switching to Thread 0x7fff597b9700 (LWP 29332)] 0x00007ffff684ca38 in gazebo::sensors::Noise::Apply(double) () from /usr/lib/x86_64-linux-gnu/libgazebo_sensors.so.7
Any ideas on what could be the issue? I tried disabling GPU acceleration but the problem persists.
Any help would be appreciated. For reference I am running Kinetic on Ubuntu 16.04 with Gazebo 7
Robot xacro file
<robot name="innobuggy" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- PROPERTY LIST -->
<!--All units in m-kg-s-radians unit system -->
<xacro:property name="M_PI" value="3.1415926535897931"/>
<xacro:property name="footprint_vertical_offset" value="-0.05"/>
<!-- Chassis -->
<xacro:property name="base_height" value="0.12"/>
<xacro:property name="base_width" value="0.195"/>
<xacro:property name="base_length" value="0.29"/>
<xacro:property name="base_mass" value="1"/> <!-- in kg-->
<xacro:property name="wheel_mass" value="1"/> <!-- in kg-->
<!-- Wheels -->
<xacro:property name="wheel_horizontal_separation" value="0.075"/>
<xacro:property name="wheel_vertical_separation" value="0.11"/>
<xacro:property name="wheel_vertical_offset" value="-0.13"/>
<xacro:property name="wheel_radius" value="0.05"/>
<xacro:property name="wheel_width" value="0.045"/>
<!-- BASE-FOOTPRINT -->
<!-- base_footprint is a fictitious link(frame) that is on the ground right below base_link origin -->
<link name="base_footprint">
<inertial>
<mass value="0.0001"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0"
izz="0.0001"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<gazebo reference="base_footprint">
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="base_link_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="base_footprint"/>
<child link="base_link"/>
</joint>
<link name="base_link">
<visual>
<origin xyz="0 0 ${footprint_vertical_offset}" rpy="0 0 0"/>
<geometry>
<!--<mesh filename="package://simple_robot_description_4wheels/meshes/inno_sim.stl"/>-->
<box size="${base_length} ${base_width} ${base_height}"/>
</geometry>
<material name="Black"/>
</visual>
<collision>
<origin xyz="0 0 ${footprint_vertical_offset}"/>
<geometry>
<box size="${base_length} ${base_width} ${base_height}"/>
</geometry>
</collision>
<inertial>
<!-- Center of mass -->
<origin xyz="0.012 0.002 0.067" rpy="0 0 0"/>
<!--<mass value="16.523"/>-->
<mass value="5.523"/>
<!-- Moments of inertia: ( base without wheels ) -->
<inertia
ixx="0.3136" ixy="-0.0008" ixz="0.0164"
iyy="0.3922" iyz="-0.0009"
izz="0.4485"/>
</inertial>
</link>
<gazebo reference="base_link">
<material>Gazebo/Black</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<!-- Start of Wheels
-->
<xacro:macro name="wheel" params="prefix trans_x trans_y trans_z">
<link name="${prefix}_wheel">
<visual>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
</geometry>
<material name="Red"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.477"/>
<inertia
ixx="0.0013" ixy="0 ...