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

PCL Header timestamp

asked 2014-06-03 23:09:01 -0500

crpizarr gravatar image

updated 2014-06-03 23:14:07 -0500

The pcl_ros tutorial example doesn't work:

#include <ros/ros.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/point_types.h>

typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;

int main(int argc, char** argv)
{
    ros::init (argc, argv, "pub_pcl");
    ros::NodeHandle nh;
    ros::Publisher pub = nh.advertise<PointCloud> ("points2", 1);

    PointCloud::Ptr msg (new PointCloud);
    msg->header.frame_id = "some_tf_frame";
    msg->height = msg->width = 1;
    msg->points.push_back (pcl::PointXYZ(1.0, 2.0, 3.0));

    ros::Rate loop_rate(4);
    while (nh.ok())
    {
        msg->header.stamp = ros::Time::now ();
        pub.publish (msg);
        ros::spinOnce ();
        loop_rate.sleep ();
   } 
}

The compiler complains with the following:

error: no se puede convertir ‘ros::Time’ a ‘uint64_t {aka long unsigned int}’ en la asignación (it's in Spanish, I don't know how to change my compiler language)

which is something like:

error: 'ros::Time' cannot be converted to 'uint64_t {aka long unsigned int}' in assignment

Has somebody else faced this problem? I am running ROS Hydro, on Ubuntu 12.04.

Thanks

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
3

answered 2014-06-04 01:24:39 -0500

This is related to changes of the Timestamp type in PCL. See the hydro migration guide for instructions on how to solve this problem. You´ll probably find some more examples of this issue on ROS Answers, too (for example also this Q/A or this Q/A).

edit flag offensive delete link more
14

answered 2015-02-16 11:36:18 -0500

lucasw gravatar image

updated 2015-05-13 15:36:38 -0500

pcl_conversions has conversion functions : http://docs.ros.org/indigo/api/pcl_co...

To convert the time:

#include <pcl_conversions/pcl_conversions.h>
...
pcl_conversions::toPCL(ros::Time::now(), point_cloud_msg->header.stamp);

Or convert an entire header from a ros message:

pcl_conversions::toPCL(ros_msg->header, point_cloud_msg>header);
edit flag offensive delete link more

Comments

Thanks for noting this here, as the documentation for pcl_conversion seems to be non-existing (at least in the ROS wiki)...

luator gravatar image luator  ( 2015-03-20 10:42:11 -0500 )edit

I ran into this issue too, and a previous fix using point_cloud_msg->header.stamp = ros::Time::now().toNSec() stopped working recently. Hopefully this conversion will stay up to date between the two code bases.

stevenwaslander gravatar image stevenwaslander  ( 2015-07-03 07:24:41 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2014-06-03 23:09:01 -0500

Seen: 14,892 times

Last updated: May 13 '15