Closed machinekoder closed 4 years ago
I can indeed reproduce the issue, it crashes with the following stack:
Thread 1 "ros" received signal SIGSEGV, Segmentation fault.
0x000000000049d733 in RosLidar::publishPointCloud (this=0x1d46e70)
at RosLidar.cpp:132
132 point.z = pointCloud[i].z;
(gdb) where
#0 0x000000000049d733 in RosLidar::publishPointCloud (this=0x1d46e70)
at RosLidar.cpp:132
#1 0x000000000049d0cf in RosLidar::publishAuxiliaryValue (this=0x1d46e70)
at RosLidar.cpp:97
#2 0x00000000004c883b in RosSensor::publishValues (this=0x1d46e70, step=0)
at RosSensor.cpp:84
#3 0x00000000005a8257 in Ros::run (this=0x1d2e730, argc=1,
argv=0x7ffc48afa5b8) at Ros.cpp:454
#4 0x00000000005d90c5 in main (argc=1, argv=0x7ffc48afa5b8) at main.cpp:19
Here are the ros command to reproduce:
rosservice call /robot_5563_cyberbotics_david/lidar/enable "{value: 32}"
rosservice call /robot_5563_cyberbotics_david/lidar/enable_point_cloud "{value: true}"
# already crashed
rostopic echo /robot_5563_cyberbotics_david/lidar/laser_scan/layer0
We have been able to isolate the problem in a simpler controller not related with ROS:
#include <webots/robot.h>
#include <webots/lidar.h>
#include <stdio.h>
#define TIME_STEP 64
int main(int argc, char **argv) {
wb_robot_init();
WbDeviceTag lidar = wb_robot_get_device("lidar");
wb_lidar_enable(lidar, TIME_STEP);
wb_lidar_enable_point_cloud(lidar);
while (wb_robot_step(TIME_STEP) != -1) {
int i = 0;
const WbLidarPoint *point_cloud = wb_lidar_get_point_cloud(lidar);
for (i = 0; i < wb_lidar_get_number_of_points(lidar); ++i)
printf("%d %lf\n", i, point_cloud[i].x);
};
wb_robot_cleanup();
return 0;
}
With this simple world file:
#VRML_SIM R2019b utf8
WorldInfo {
}
Viewpoint {
orientation -0.6931032800836722 0.6931032800836722 0.1980295085953349 0.75
position 1.2 1.6 2.3
}
TexturedBackground {
}
TexturedBackgroundLight {
}
RectangleArena {
}
Robot {
children [
Lidar {
translation 0 0.12 0
horizontalResolution 224
verticalFieldOfView 1.6
numberOfLayers 171
}
]
controller "my_controller_lidar"
controllerArgs "--name=robot"
}
I have the same crash on macOS.
This is due to a recent regression introduced in the migration to the POSIX shared memory #872 .
https://github.com/cyberbotics/webots/blob/revision/src/lib/Controller/api/abstract_camera.c#L54 does the wrong assumption that the shared memory is identical in every devices. For the lidar, the point cloud is concatenated.
Computing this size correctly should fix the issue.
@machinekoder Meanwhile we provide a good fix, you could certainly revert to R2019b.rev0 to solve this issue.
well spotted @fabienrohrer !
@machinekoder This bug has been fixed in #1091. The patch will be included in the revision
nightly build of tomorrow: https://github.com/cyberbotics/webots/releases
Any feedback is welcome.
Describe the Bug I would like to simulate a 3D/ToF camera. For this purpose I've set up a sim with with a Lidar device. The ToF cam has a resolution of 224x171 and FOV of 62x45deg, I've entered that in Webots. So far so good.
When I now try to use the sim with a ros controller, the controller just crashes. I suspect that this is due to the high number of layers since it doesn't crash when I reduce the layers.
Steps to Reproduce
horizontalCameraResolution
to 224 andnumberOfLayers
to 171.ros
enable_point_cloud
ros
controller crashes.Expected behavior The
ros
controller works as expected or gives an appropriate error message.Screenshots none
System
OpenGL version string: 4.6.0 NVIDIA 410.104 OpenGL shading language version string: 4.60 NVIDIA OpenGL context flags: (none) OpenGL profile mask: (none)
OpenGL ES profile version string: OpenGL ES 3.2 NVIDIA 410.104 OpenGL ES profile shading language version string: OpenGL ES GLSL ES 3.20