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

PointCloud library publishing

asked 2012-05-31 07:15:59 -0500

allenh1 gravatar image

updated 2012-06-01 08:51:39 -0500

I have a pcl::PointCloud<pointxyz> cloud and I need to publish it. It is NOT a kinect camera. Does anyone know how to do this? Is there some good sample code out there? I really need help here....

Thanks in advance, -Hunter A.

int main(int argc, char **argv)
{
    ros::init(argc , argv , "laser_ReadOut");

    ros::NodeHandle handler;

    ros::Subscriber laserReader = handler.subscribe("scan", 10000, scanCallBack);
    ros::Publisher  laserOutput = handler.advertise<pcl::PointCloud<pcl::PointXYZ> >("/cloud_pcl", 100);

    laserOutput.publish(correctedCloud.makeShared());
    ros::spin();

    return 0;
}//end main.

correctedCloud is declared above. It is modified after the scan call back is called.

This is the RVIZ error

This is the output for rostopic echo cloud_pcl

I am publishing the topic here (This is my research, so I'm afraid the whole code cannot be posted publicly)

    void makeOneCloud()
{
    PointCloud combined;
    //matchSlopes();

    for (unsigned int x = 0; x < scans.size(); ++x)
    {
        PointCloud currentCorrected = scans.at(x).getCorrections();
        for (unsigned int y = 0; y < currentCorrected.points.size(); ++y)
        {
            double py = currentCorrected.points.at(y).y;
            double px = currentCorrected.points.at(y).x;
            double pZ = Z;

            pcl::PointXYZ toPush;
            toPush.x = px; toPush.y = py; toPush.z = pZ;

            combined.points.push_back(toPush);
        }//end for y
    }//end for x.

    correctedCloud = combined;
    combined.height = 1;
    combined.width = combined.points.size();

    pcl::PCDWriter writer;
    writer.write<pcl::PointXYZ> ("FinalCorrections.pcd", combined, false);
    laserOutput.publish(combined.makeShared());
    ROS_INFO("Corrections Saved!");

    scans.clear();
}//this method combines all the corrected shapes to a single point cloud.
edit retag flag offensive close merge delete

Comments

Do you ever set the frame_id of the cloud? You'll need to set it to something in order for rviz to display it.

Eric Perko gravatar image Eric Perko  ( 2012-06-01 09:03:04 -0500 )edit

Thank you! It works now!

allenh1 gravatar image allenh1  ( 2012-06-01 09:14:40 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
6

answered 2012-05-31 07:33:33 -0500

DimitriProsser gravatar image

I use the following code for this...

1) Include the following:

#include <pcl_ros/point_cloud.h>

2) Set up your publisher:

typedef pcl::PointCloud<pcl::PointXYZ> PCLCloud;
ros::Publisher output_pub_ = node_.advertise<PCLCloud> (output_topic_name.c_str(), 100);

3) Publish your cloud:

pcl::PointCloud<pcl::PointXYZ> my_cloud;
output_pub_.publish(my_cloud.makeShared());

NOTE: When you attempt to publish the cloud, you must publish it as a pcl::PointCloud<pcl::pointxyz>::Ptr (that's the purpose of the makeShared() function.

edit flag offensive delete link more

Comments

Why can't I visualize this in RVIZ?

allenh1 gravatar image allenh1  ( 2012-05-31 08:20:36 -0500 )edit

It is visualized as the sensor_msgs/PointCloud2 datatype.

DimitriProsser gravatar image DimitriProsser  ( 2012-05-31 08:47:38 -0500 )edit

Yes, but I'm not getting messages... I see the topic, but I don't get the data.

allenh1 gravatar image allenh1  ( 2012-05-31 08:53:11 -0500 )edit

Could you post a minimal example of your publisher? Is the publisher object long-lived or do you destruct it right after calling .publish?

Eric Perko gravatar image Eric Perko  ( 2012-05-31 09:09:58 -0500 )edit

I added the code to my post. It isn't part of a class. That could be the reason it's troubled.

allenh1 gravatar image allenh1  ( 2012-05-31 09:20:17 -0500 )edit

What are you exactly trying to do here? The way you have your publish call setup, it will be called once before scanCallback has a chance of getting called (through spin()). You might be publishing an empty cloud only once. Perhaps you want the publish call inside the scan callback function?

piyushk gravatar image piyushk  ( 2012-05-31 10:26:53 -0500 )edit

Yes. Could you help me with that?

allenh1 gravatar image allenh1  ( 2012-05-31 10:28:50 -0500 )edit
1

Take a look at this example: http://cs.utexas.edu/~piyushk/share/messenger.cpp This example extends the basic talker/listener roscpp tutorial (http://www.ros.org/wiki/roscpp_tutorials/Tutorials/WritingPublisherSubscriber) in the way you want, by republishing the string message.

piyushk gravatar image piyushk  ( 2012-05-31 11:00:10 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2012-05-31 07:15:59 -0500

Seen: 6,006 times

Last updated: Jun 01 '12