Reworked Velodyne driver causes OctoMap segmentation fault

asked 2021-04-22 14:43:45 -0500

MarcoStb gravatar image

Hey, I am running Ubuntu 18 with ROS Melodic and with the Velodyne driver (since 1.6.0) and Velodyne simulator (since 1.0.10) rework, the message generated by a real or simulated Velodyne is not using PCL anymore as far as I understand.

When subscribing to this message (usually /velodyne_points) with an octomap_server, the octomap server node dies with a segmentation fault (I only tested this via simulation in gazebo 9.17.0).

The Velodyne is simulated in gazebo in an URDF:

       <xacro:include
            filename="$(find velodyne_description)/urdf/VLP-16.urdf.xacro" />
        <xacro:if value="${simulated_velodyne}">
            <xacro:VLP-16 parent="holder" name="velodyne"
                topic="velodyne_points" hz="10" samples="1875" gpu="true">
                <origin xyz="${velodyne_translation}" rpy="${velodyne_rotation}" />
            </xacro:VLP-16>
        </xacro:if>

And the OctoMap should be run from this roslaunch extract:

<!-- Octomap -->
<node pkg="octomap_server" type="octomap_server_node"
    name="octomap_server">
    <param name="resolution" value="$(arg oc_resolution)" />
    <param name="frame_id" type="string" value="map" />
    <param name="sensor_model/max_range" value="100.0" />
    <param name="latch" value="false" />
    <param name="filter_ground" value="false" />
    <remap from="cloud_in" to="velodyne_points" />
    <param name="publish_free_space" value="true" />
</node>

Unfortunately, this leads to the OctoMap server crashing with a segmentation fault as soon as the first message is received. But I found out, that when converting the Velodyne message to PointCloud and back to PointCloud2 which is then published in a node, OctoMap is running fine while subscribing to the converted message. The node to convert the message can be seen below:

#include "ros/ros.h"
#include <sensor_msgs/point_cloud_conversion.h>
#include <sensor_msgs/PointCloud2.h>
#include <string>

ros::Publisher cloud_publisher_;

void velodynePointsCallback(const sensor_msgs::PointCloud2 &cloud);

int main(int argc, char **argv) {
    ros::init(argc, argv, "velodynePointsConverterNode");
    ros::NodeHandle nh;
    ros::NodeHandle private_nh("~");
    std::string input_topic, output_topic;
    private_nh.param<std::string>("output_topic", output_topic,
            "velodyne_pointcloud");
    private_nh.param<std::string>("input_topic", input_topic,
            "velodyne_points");

    cloud_publisher_ = nh.advertise<sensor_msgs::PointCloud2>(output_topic, 1);
    ros::Subscriber cloud_subscriber_ = nh.subscribe(input_topic, 1,
            velodynePointsCallback);
    ros::spin();
    return 0;
}

void velodynePointsCallback(const sensor_msgs::PointCloud2 &cloud) {
    sensor_msgs::PointCloud cloudIn;
    sensor_msgs::convertPointCloud2ToPointCloud(cloud, cloudIn);
    sensor_msgs::PointCloud2 cloudSend;
    sensor_msgs::convertPointCloudToPointCloud2(cloudIn, cloudSend);
    cloud_publisher_.publish(cloudSend);
}

Has anyone else experienced similar issues or found a fix or workaround to use the Velodyne messages without converting them first?

Thank you and best regards Marco

edit retag flag offensive close merge delete