Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Multiple Lidar Instances Crash when spawned #370

Closed
retinfai opened this issue Jul 31, 2023 · 2 comments
Closed

Multiple Lidar Instances Crash when spawned #370

retinfai opened this issue Jul 31, 2023 · 2 comments
Assignees
Labels
bug Something isn't working

Comments

@retinfai
Copy link

Environment

  • OS Version: Ubuntu Jammy
  • Source build: commit 28089ab

Description

Expected behavior:

The simulation doesn't crash

A key thing to note here, is that the simulation crashes when trying to spawn two lidar instances (robots with lidar).

When the two lidar instances are a part of the world being launched - there is no problem here.
This situation is very similar to an issue I brought up about the gazebo reset: gazebosim/gz-sim#1904

Same situation where the crash happens when spawning the robot in but works fine when a part of the world sdf; I think this points to some sort of difference in handling the systems/sensors when it's being dynamically produced.

Actual Behaviour

The simulation Crashed

Steps to reproduce

Here is the car.sdf

<?xml version="1.0" ?>

<sdf version="1.6">
	<model name='vehicle_blue'>
	<pose>0 2 0.325 0 -0 0</pose>
        <link name="link">
        <pose>0.05 0.05 0.05 0 0 0</pose>
        <inertial>
          <mass>0.1</mass>
          <inertia>
            <ixx>0.000166667</ixx>
            <iyy>0.000166667</iyy>
            <izz>0.000166667</izz>
          </inertia>
        </inertial>
        <collision name="collision">
          <geometry>
            <box>
              <size>0.1 0.1 0.1</size>
            </box>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <box>
              <size>0.1 0.1 0.1</size>
            </box>
          </geometry>
        </visual>

        <sensor name='gpu_lidar' type='gpu_lidar'>
          <topic>/lidar</topic>
          <update_rate>10</update_rate>
          <lidar>
            <scan>
              <horizontal>
                <samples>640</samples>
                <resolution>1</resolution>
                <min_angle>-1.396263</min_angle>
                <max_angle>1.396263</max_angle>
              </horizontal>
              <vertical>
                <samples>16</samples>
                <resolution>1</resolution>
                <min_angle>-0.261799</min_angle>
                <max_angle>0.261799</max_angle>
              </vertical>
            </scan>
            <range>
              <min>0.08</min>
              <max>10.0</max>
              <resolution>0.01</resolution>
            </range>
          </lidar>
          <alwaysOn>1</alwaysOn>
          <visualize>true</visualize>
          
        </sensor>
      </link>
      <link name='chassis'>
        <pose>-0.151427 -0 0.175 0 -0 0</pose>
        <inertial>
          <mass>1.14395</mass>
          <inertia>
            <ixx>0.126164</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.416519</iyy>
            <iyz>0</iyz>
            <izz>0.481014</izz>
          </inertia>
        </inertial>
        <visual name='visual'>
          <geometry>
            <box>
              <size>2.01142 1 0.568726</size>
            </box>
          </geometry>
          <material>
            <ambient>0.5 0.5 1.0 1</ambient>
            <diffuse>0.5 0.5 1.0 1</diffuse>
            <specular>0.0 0.0 1.0 1</specular>
          </material>
        </visual>
        <collision name='collision'>
          <geometry>
            <box>
              <size>2.01142 1 0.568726</size>
            </box>
          </geometry>
        </collision>
      </link>

      <link name='front_left_wheel'>
        <pose>0.554283 0.625029 -0.025 -1.5707 0 0</pose>
        <inertial>
          <mass>2</mass>
          <inertia>
            <ixx>0.145833</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.145833</iyy>
            <iyz>0</iyz>
            <izz>0.125</izz>
          </inertia>
        </inertial>
        <visual name='visual'>
          <geometry>
            <cylinder>
              <length>0.15</length>
              <radius>0.3</radius>
            </cylinder>
          </geometry>
          <material>
            <ambient>0.2 0.2 0.2 1</ambient>
            <diffuse>0.2 0.2 0.2 1</diffuse>
            <specular>0.2 0.2 0.2 1</specular>
          </material>
        </visual>
        <collision name='collision'>
          <geometry>
            <cylinder>
              <length>0.15</length>
              <radius>0.3</radius>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode>
                <mu>0.5</mu>
                <mu2>1.0</mu2>
                <fdir1>0 0 1</fdir1>
              </ode>
              <bullet>
                <friction>0.5</friction>
                <friction2>1</friction2>
                <rolling_friction>0.1</rolling_friction>
              </bullet>
            </friction>
          </surface>
        </collision>
      </link>

      <link name='rear_left_wheel'>
        <pose>-0.957138 0.625029 -0.025 -1.5707 0 0</pose>
        <inertial>
          <mass>2</mass>
          <inertia>
            <ixx>0.145833</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.145833</iyy>
            <iyz>0</iyz>
            <izz>0.125</izz>
          </inertia>
        </inertial>
        <visual name='visual'>
          <geometry>
            <cylinder>
              <length>0.15</length>
              <radius>0.3</radius>
            </cylinder>
          </geometry>
          <material>
            <ambient>0.2 0.2 0.2 1</ambient>
            <diffuse>0.2 0.2 0.2 1</diffuse>
            <specular>0.2 0.2 0.2 1</specular>
          </material>
        </visual>
        <collision name='collision'>
          <geometry>
            <cylinder>
              <length>0.15</length>
              <radius>0.3</radius>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode>
                <mu>0.5</mu>
                <mu2>1.0</mu2>
                <fdir1>0 0 1</fdir1>
              </ode>
              <bullet>
                <friction>0.5</friction>
                <friction2>1</friction2>
                <rolling_friction>0.5</rolling_friction>
              </bullet>
            </friction>
          </surface>
        </collision>
      </link>

      <link name='front_right_wheel'>
        <pose>0.554282 -0.625029 -0.025 -1.5707 0 0</pose>
        <inertial>
          <mass>2</mass>
          <inertia>
            <ixx>0.145833</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.145833</iyy>
            <iyz>0</iyz>
           <izz>0.125</izz>
          </inertia>
        </inertial>
        <visual name='visual'>
          <geometry>
            <cylinder>
              <length>0.15</length>
              <radius>0.3</radius>
            </cylinder>
          </geometry>
          <material>
            <ambient>0.2 0.2 0.2 1</ambient>
            <diffuse>0.2 0.2 0.2 1</diffuse>
            <specular>0.2 0.2 0.2 1</specular>
          </material>
        </visual>
        <collision name='collision'>
          <geometry>
            <cylinder>
              <length>0.15</length>
              <radius>0.3</radius>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode>
                <mu>0.5</mu>
                <mu2>1.0</mu2>
                <fdir1>0 0 1</fdir1>
              </ode>
              <bullet>
                <friction>0.5</friction>
                <friction2>1</friction2>
                <rolling_friction>0.1</rolling_friction>
              </bullet>
            </friction>
          </surface>
        </collision>
      </link>

      <link name='rear_right_wheel'>
        <pose>-0.957138 -0.625029 -0.025 -1.5707 0 0</pose>
        <inertial>
          <mass>2</mass>
          <inertia>
            <ixx>0.145833</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.145833</iyy>
            <iyz>0</iyz>
            <izz>0.125</izz>
          </inertia>
        </inertial>
        <visual name='visual'>
          <geometry>
            <cylinder>
              <length>0.15</length>
              <radius>0.3</radius>
            </cylinder>
          </geometry>
          <material>
            <ambient>0.2 0.2 0.2 1</ambient>
            <diffuse>0.2 0.2 0.2 1</diffuse>
            <specular>0.2 0.2 0.2 1</specular>
          </material>
        </visual>
        <collision name='collision'>
          <geometry>
            <cylinder>
              <length>0.15</length>
              <radius>0.3</radius>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode>
                <mu>0.5</mu>
                <mu2>1.0</mu2>
                <fdir1>0 0 1</fdir1>
              </ode>
              <bullet>
                <friction>0.5</friction>
                <friction2>1</friction2>
                <rolling_friction>0.5</rolling_friction>
              </bullet>
            </friction>
          </surface>
        </collision>
      </link>

      <link name="front_left_wheel_steering_link">
        <pose>0.554283 0.5 0.02 0 0 0</pose>
        <inertial>
          <mass>0.5</mass>
          <inertia>
            <ixx>0.0153</ixx>
            <iyy>0.025</iyy>
            <izz>0.0153</izz>
          </inertia>
        </inertial>
        <visual name="steering_link_visual">
          <pose>0 0 0 0 0 0</pose>
          <geometry>
            <cylinder>
              <length>0.1</length>
              <radius>0.03</radius>
            </cylinder>
          </geometry>
          <material>
            <ambient>1 1 1</ambient>
            <diffuse>1 1 1</diffuse>
          </material>
        </visual>
      </link>

      <link name="front_right_wheel_steering_link">
        <pose>0.554283 -0.5 0.02 0 0 0</pose>
        <inertial>
          <mass>0.5</mass>
          <inertia>
            <ixx>0.0153</ixx>
            <iyy>0.025</iyy>
            <izz>0.0153</izz>
          </inertia>
        </inertial>
        <visual name="steering_link_visual">
          <pose>0 0 0 0 0 0</pose>
          <geometry>
            <cylinder>
              <length>0.1</length>
              <radius>0.03</radius>
            </cylinder>
          </geometry>
          <material>
            <ambient>1 1 1</ambient>
            <diffuse>1 1 1</diffuse>
          </material>
        </visual>
      </link>

      <joint name="front_left_wheel_steering_joint" type="revolute">
        <child>front_left_wheel_steering_link</child>
        <parent>chassis</parent>
        <axis>
          <xyz>0 0 1</xyz>
          <limit>
            <lower>-0.6</lower>
            <upper>+0.6</upper>
            <velocity>1.0</velocity>
            <effort>25</effort>
          </limit>
          <use_parent_model_frame>1</use_parent_model_frame>
        </axis>
      </joint>

      <joint name="front_right_wheel_steering_joint" type="revolute">
        <parent>chassis</parent>
        <child>front_right_wheel_steering_link</child>
        <axis>
          <xyz>0 0 1</xyz>
          <limit>
            <lower>-0.6</lower>
            <upper>+0.6</upper>
            <velocity>1.0</velocity>
            <effort>25</effort>
          </limit>
        </axis>
      </joint>

      <joint name='front_left_wheel_joint' type='revolute'>
        <parent>front_left_wheel_steering_link</parent>
        <child>front_left_wheel</child>
        <axis>
          <xyz>0 0 1</xyz>
          <limit>
            <lower>-1.79769e+308</lower>
            <upper>1.79769e+308</upper>
          </limit>
        </axis>
      </joint>

      <joint name='front_right_wheel_joint' type='revolute'>
        <parent>front_right_wheel_steering_link</parent>
        <child>front_right_wheel</child>
        <axis>
          <xyz>0 0 1</xyz>
          <limit>
            <lower>-1.79769e+308</lower>
            <upper>1.79769e+308</upper>
          </limit>
        </axis>
      </joint>

      <joint name='rear_left_wheel_joint' type='revolute'>
        <parent>chassis</parent>
        <child>rear_left_wheel</child>
        <axis>
          <xyz>0 0 1</xyz>
          <limit>
            <lower>-1.79769e+308</lower>
            <upper>1.79769e+308</upper>
          </limit>
        </axis>
      </joint>

      <joint name='rear_right_wheel_joint' type='revolute'>
        <parent>chassis</parent>
        <child>rear_right_wheel</child>
        <axis>
          <xyz>0 0 1</xyz>
          <limit>
            <lower>-1.79769e+308</lower>
            <upper>1.79769e+308</upper>
          </limit>
        </axis>
      </joint>

      <plugin
        filename="gz-sim-ackermann-steering-system"
        name="gz::sim::systems::AckermannSteering">
        <left_joint>front_left_wheel_joint</left_joint>
        <left_joint>rear_left_wheel_joint</left_joint>
        <right_joint>front_right_wheel_joint</right_joint>
        <right_joint>rear_right_wheel_joint</right_joint>
        <left_steering_joint>front_left_wheel_steering_joint</left_steering_joint>
        <right_steering_joint>front_right_wheel_steering_joint</right_steering_joint>
        <kingpin_width>1.0</kingpin_width>
        <steering_limit>0.5</steering_limit>
        <wheel_base>1.0</wheel_base>
        <wheel_separation>1.25</wheel_separation>
        <wheel_radius>0.3</wheel_radius>
        <min_velocity>-1</min_velocity>
        <max_velocity>3</max_velocity>
        <min_acceleration>-3</min_acceleration>
        <max_acceleration>3</max_acceleration>
      </plugin>
      
      <plugin
        filename="gz-sim-pose-publisher-system"
        name="gz::sim::systems::PosePublisher">
        <publish_link_pose>false</publish_link_pose>
        <publish_collision_pose>false</publish_collision_pose>
        <publish_visual_pose>false</publish_visual_pose>
        <publish_nested_model_pose>true</publish_nested_model_pose>
      </plugin>
        <plugin
        filename="gz-sim-sensors-system"
        name="gz::sim::systems::Sensors">
        <render_engine>ogre2</render_engine>
      </plugin>
    </model> 
</sdf>
  1. gz sim empty.sdf
  2. gz service -s /world/empty/create --reqtype gz.msgs.EntityFactory --reptype gz.msgs.Boolean --timeout 1000 --req 'sdf_filename: "./car.sdf", name: "car_1", pose: {position: {x: 0}}'
  3. gz service -s /world/empty/create --reqtype gz.msgs.EntityFactory --reptype gz.msgs.Boolean --timeout 1000 --req 'sdf_filename: "./car.sdf", name: "car_2", pose: {position: {x: 10}}'

Output

Stack Trace

anyone@bob-the-not-so-plumber:~/hello$ gz sim empty.sdf
\libEGL warning: DRI2: failed to create dri screen
libEGL warning: DRI2: failed to create dri screen
libEGL warning: DRI2: failed to create dri screen
libEGL warning: DRI2: failed to create dri screen
Warning [Utils.cc:130] [/sdf/model[@name="vehicle_blue"]/link[@name="link"]/sensor[@name="gpu_lidar"]/alwaysOn:./car.sdf:L55]: XML Element[alwaysOn], child of element[sensor], not defined in SDF. Copying[alwaysOn] as children of [sensor].
libEGL warning: DRI2: failed to create dri screen
libEGL warning: DRI2: failed to create dri screen
libEGL warning: DRI2: failed to create dri screen
libEGL warning: DRI2: failed to create dri screen
Warning [Utils.cc:130] [/sdf/model[@name="vehicle_blue"]/link[@name="link"]/sensor[@name="gpu_lidar"]/alwaysOn:./car.sdf:L55]: XML Element[alwaysOn], child of element[sensor], not defined in SDF. Copying[alwaysOn] as children of [sensor].
[Err] [SceneManager.cc:223] Visual: [ground_plane] already exists
[Err] [SceneManager.cc:223] Visual: [cool_lidar] already exists
[Err] [SceneManager.cc:223] Visual: [cool_car] already exists
[Err] [BaseStorage.hh:927] Another item already exists with name: sun
Stack trace (most recent call last) in thread 1098722:
#7    Object "[0xffffffffffffffff]", at 0xffffffffffffffff, in 
#6    Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fb9619269ff, in 
#5    Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fb961894b42, in 
#4    Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7fb95d0dc252, in 
#3    Object "/home/anyone/gz-sim-fork/install/lib/gz-sim-7/plugins/libgz-sim-sensors-system.so", at 0x7fb8ccd300b7, in gz::sim::v7::systems::SensorsPrivate::RenderThread()
#2    Object "/home/anyone/gz-sim-fork/install/lib/gz-sim-7/plugins/libgz-sim-sensors-system.so", at 0x7fb8ccd2f9eb, in gz::sim::v7::systems::SensorsPrivate::RunOnce()
#1    Object "/home/anyone/gz-sim-fork/install/lib/libgz-sim7-rendering.so.7", at 0x7fb8ccc565c4, in gz::sim::v7::RenderUtil::Update()
#0    Object "/home/anyone/gz-sim-fork/install/lib/libgz-sim7-rendering.so.7", at 0x7fb8cccb39b8, in gz::sim::v7::SceneManager::CreateLight(unsigned long, sdf::v13::Light const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, unsigned long)
Segmentation fault (Address not mapped to object [(nil)])

@retinfai retinfai added the bug Something isn't working label Jul 31, 2023
@retinfai retinfai changed the title Multiple Lidar Instances Multiple Lidar Instances Crash when spawned Jul 31, 2023
@azeey
Copy link
Contributor

azeey commented Aug 1, 2023

I noticed that you're including the Sensor system in your model. That system is meant to be used in the <world> tag, just like the Physics system. Does it crash if you remove it from your models and put just one Sensor system in the world?

@azeey azeey self-assigned this Aug 1, 2023
@retinfai
Copy link
Author

retinfai commented Aug 2, 2023

Ahh yes, that was the issue thank you. This may also be the cause of the issue that I linked previously with the Reset – we're using a similar approach. I'll check and update that issue too

@retinfai retinfai closed this as completed Aug 2, 2023
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

No branches or pull requests

2 participants