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

Error: Invalid argument passed to canTransform argument source_frame

asked 2015-03-17 09:41:16 -0600

RosFan19 gravatar image

updated 2015-03-17 10:53:25 -0600

gvdhoorn gravatar image

Hi,

I'm using the Euclidean Clustering and trying to publish a certain cluster which has 3500- 4500 points in it, but iI'm getting a weird error when trying to visualize it in rviz.

[WARN] [1426601373.806774699]: Invalid argument passed to canTransform argument source_frame in tf2 frame_ids cannot be empty

It works fine when I use the original cloud, the problem seems to be with the cloudCluster. Here is the code:

pcl::PointCloud<pcl::PointXYZ> cloudCluster;
for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
{
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>);
  for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); ++pit)
  {
    cloud_cluster->points.push_back (cloud_filtered->points[*pit]);
  }

  cloud_cluster->width = cloud_cluster->points.size ();
  cloud_cluster->height = 1;
  cloud_cluster->is_dense = true;


  if (cloud_cluster->points.size() > 3500 && cloud_cluster->points.size() < 4500) {
    cloudCluster = *cloud_cluster;
  }
  j++;
}
sensor_msgs::PointCloud2 cloud2;
pcl::toROSMsg(cloudCluster, cloud2);

pub_.publish(cloud2);
edit retag flag offensive close merge delete

Comments

It would probably help if you updated your question with what "a weird error" actually is.

gvdhoorn gravatar image gvdhoorn  ( 2015-03-17 10:07:13 -0600 )edit

For some reason it did not show up, removed [] from WARN and now it shows

RosFan19 gravatar image RosFan19  ( 2015-03-17 10:29:06 -0600 )edit

In the future, format console copy/pastes as code.

gvdhoorn gravatar image gvdhoorn  ( 2015-03-17 10:54:17 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-03-17 10:53:09 -0600

gvdhoorn gravatar image
[WARN] [1426601373.806774699]: Invalid argument passed to canTransform argument source_frame in tf2 frame_ids cannot be empty

The error tells you what the problem is: RViz needs properly initialised Headers to be able to visualise something like a PointCloud2, as it cannot transform the points into their correct location without them.

It would appear that cloud2 does not have its frame_id field set in its header (see the std_msgs/Header documentation). You can probably copy it from the original (input) cloud. If not, set it to another valid frame id and things should start working.

edit flag offensive delete link more

Comments

I tried adding:

cloudCluster.header = filtered_cloud.header;

But I still got the error. However when i use:

void    swap (PointCloud< PointT > &rhs)
    Swap a point cloud with another cloud

Then it works.

RosFan19 gravatar image RosFan19  ( 2015-03-17 15:57:42 -0600 )edit
1

I had the same error, but doing how you said:

cloudCluster.header = filtered_cloud.header

It was working correctly for me.

Caba gravatar image Caba  ( 2015-07-23 09:22:31 -0600 )edit

hello, when i used this commend "cloudCluster.header = filtered_cloud.header" i did not get any error in rviz, but it does not show anything. where exactly you put this commend before the "sensor_msgs::PointCloud2 cloud2;" or inside the loop. thanks in advance.

kerollosghobrial gravatar image kerollosghobrial  ( 2015-10-25 19:01:50 -0600 )edit
1

I have the code right here: https://github.com/Jyrks/visual_servo...

I solved it by using the swap method, since using just the header doesn't change all the necessary fields.

Look for the part:

cloud_filtered->swap(*filtered_cloud_cluster);

RosFan19 gravatar image RosFan19  ( 2015-10-26 03:30:09 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2015-03-17 09:41:16 -0600

Seen: 6,908 times

Last updated: Mar 17 '15