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

frame issue with PointCloud2 and rviz

asked 2015-09-21 18:07:25 -0500

jeremya gravatar image

updated 2015-09-22 16:52:50 -0500

After reviewing the source for Velodyne I see that:

  1. the velodyne_packets topic is published with "velodyne" frame id in the ROS header
  2. the velodyne_points topic is published with "odom" frame id in the ROS header
  3. when I run with a PCAP file and visualize in rviz, I launch rviz by passing the fixed frame ID as in "rosrun rviz rviz -f velodyne"
  4. rviz display the fixed frame options as only velodyne and properly displays the PointCloud2 data

I have a similar LiDAR with a driver that has been using the PCL Point XYZI. I'm using pcl::toROSMsg to convert the PCL point cloud (Point XYZI) to sensor_msgs::PointCloud2. I format the header with a frame_id that I made up with a simple text string. I didn't broadcast a tf transform since I didn't see that the velodyne code did either.

When I run my ROS node and then rviz (e.g. "rosrun rviz rviz -f myframe" where "myframe" is the same string used in my header for the PointCloud2 message.), I get an error:

Transform [sender=unknown_publisher]
For frame []: Fixed Frame [myframe] does not exist

In the case of both the velodyne (using PCAP file) and my node, I checked the tf by running "rosrun tf tf_echo" but see no frames listed.

I'm a little confused why the velodyne driver works and mine doesn't since the velodyne code doesn't seem to broadcast the transforms. I've been alerted to that the text "For frame []:" in the error above is really stating that the translation is from from "" (empty string) to "myframe". Without a broadcast transform, how can having two frames (in the case of velodyne) for two different topics make any difference? The PointCloud2 status for Velodyne shows "OK" and the subitem under status, Transform also simply says OK for velodyne but gives the error above for my sensor.

I "rostopic echo ..." my topic and the PointCloud2 data looks well formed when compared to the velodyne PointCloud2 message so I think the error is simply a matter of tf frames and frame IDs.

In my code I'm not doing a tf::MessageFilter or pcl_ros::transformPointCloud like the velodyne code does in transform.cc. I don't have a second node for my data like velodyne so I don't suppose I really need the MessageFilter because I can't subscribe to anything getting the raw data. I'm curious if the ros::transformPointCloud would actually be of much use since I don't have two transform IDs like velodyne does (odom and velodyne).

Any help is greatly appreciated.

Here's the header: seq: 451713 stamp: secs: 83567 nsecs: 240980000 frame_id: '' height: 8 width: 4872 fields: - name: x offset: 0 datatype: 7 count: 1 - name: y offset: 4 datatype: 7 count: 1 - name: z offset: 8 datatype: 7 count: 1 - name: intensity offset: 16 datatype: 7 count: 1 is_bigendian: False point_step: 32 row_step: 155904

Here's the snippet:

  while(ros::ok())
  {
      //create and send ...
(more)
edit retag flag offensive close merge delete

Comments

Can you do rostopic echo /<topic you're subscribed to in rviz> and just post the header part of the output?

William gravatar image William  ( 2015-09-21 18:19:06 -0500 )edit

I noticed two problems. The frame_id is an empty string even though I'm adding the string in my code. I also noticed the time stamps seem to reflect miliseconds and not seconds. Header below.

jeremya gravatar image jeremya  ( 2015-09-22 14:07:56 -0500 )edit

Is it possible for you to post the snippet of your code which does the publishing. I'd say the only way this could happen is a mistake in the publishing code.

William gravatar image William  ( 2015-09-22 15:01:11 -0500 )edit

I added the snippet. (and removed the answer section. Thanks for the tip)

jeremya gravatar image jeremya  ( 2015-09-22 16:54:47 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2015-09-22 17:18:32 -0500

William gravatar image

The issue is that the pcl::toROSMsg(const pcl::PointCloud<...>, sensor_msgs::PointCloud2) function overwrites the header in the destination sensor_msgs::PointCloud2 object with the header in the pcl::PointCloud<...> object, effective overwriting the values you set in the first few lines of your loop:

http://docs.pointclouds.org/1.7.0/con...

You can simply move the setting of the timestamp and frame id to after you call pcl::toROSMsg.

edit flag offensive delete link more

Comments

That was it. Thanks for the help.

jeremya gravatar image jeremya  ( 2015-09-22 17:29:40 -0500 )edit

No problem, happy to help.

William gravatar image William  ( 2015-09-22 17:56:52 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-09-21 18:07:25 -0500

Seen: 4,210 times

Last updated: Sep 22 '15