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

Generate PointCloud2 without sensor

asked 2018-09-24 04:20:05 -0500

S.Yildiz gravatar image

updated 2018-09-24 05:13:07 -0500

How can I construct a sensor_msgs::PointCloud2 message from scratch, in c++? I have looked up the structure and documentation of that message but I don't know how to build it up. Does someone have an example code with dummy data?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-09-24 06:18:48 -0500

If you're trying to publish points clouds with ROS that you're generating algorithmic-ally say then you just need to create a pcl::PointCloud object. You can publish these directly without needing to convert them into messages types. If you this isn't the question you're asking let me know and I'll post a different example for you.

The following C++ example publishes a point cloud of 1000 random points once a second on the topic "cloud_topic" Hope this helps.

#include <stdio.h>
#include <ros/ros.h>
#include <pcl_ros/point_cloud.h>

int main(int argc, char **argv)
{
    // setup ros for this node and get handle to ros system
    ros::init(argc, argv, "PCD file publisher");
    ros::start();

    // get node handle
    ros::NodeHandle n;
    ros::Rate loopRate(1.0);
    std::string topicName = "cloud_topic";

    ros::Publisher demoPublisher = n.advertise<pcl::PointCloud<pcl::PointXYZ> >(topicName.c_str(),10);

    ROS_INFO("Publishing point cloud on topic \"%s\" once every second.", topicName.c_str());

    while (ros::ok())
    {
        // create point cloud object
        pcl::PointCloud<pcl::PointXYZ> myCloud;

        // fill cloud with random points
        for (int v=0; v<1000; ++v)
        {
            pcl::PointXYZ newPoint;
            newPoint.x = (rand() * 100.0) / RAND_MAX;
            newPoint.y = (rand() * 100.0) / RAND_MAX;
            newPoint.z = (rand() * 100.0) / RAND_MAX;
            myCloud.points.push_back(newPoint);
        }

        // publish point cloud
        lidarScanPublisher.publish(myCloud.makeShared());

        // pause for loop delay
        loopRate.sleep();
    }

    return 1;
}
edit flag offensive delete link more

Question Tools

Stats

Asked: 2018-09-24 04:20:05 -0500

Seen: 2,906 times

Last updated: Sep 24 '18