On Tue, Dec 21, 2010 at 4:16 PM, Rodrigo Baravalle wrote: > Hi! > > Here are the lines of code of the callback, when an amcl pose arrives.. > > I used the same frame_id, but, is the timestamp correct? I used the > same as in the tutorial: > http://www.ros.org/wiki/tf/Tutorials/tf%20and%20Time%20(C%2B%2B) > > void MergePC::callback(const geometry_msgs::PoseWithCovarianceStampedPtr& > o) { > ... > // Read data from the Camera > pc_current.header.frame_id = "swissranger"; > dev_->readData(pc_current,pc2_current,image_d_, image_i_, > image_c_, image_d16_); > > // I put 100.0, but is the same if I put 20.0, 3.0, or whatever > tlistener.waitForTransform("/map", "/swissranger", > ros::Time(0), ros::Duration(100.0)); > > // pc_current is the point cloud arriving from the camera, so it > has the "swissranger" frame_id > // here is where it fails.. > tlistener.transformPointCloud("/map", pc_current, pc_tf); > ... > } > > Thanks in advance! > Hi Rodrigo, Your call to wait for transform is going to wait until any transform between "/map" and "/swissranger". Time(0) is special and will match anything. you want to waitForTransform betwen "/map" and pc_current.header.frame_id at time pc_current.header.stamp, as that is what you are about to call with transformPointCloud. Tully > 2010/12/21 Wim Meeussen : > >> The problem is that I always get an error message like this: > >> > >> "You requested a transform that is 12.571 miliseconds in the past, > >> but the most recent transform in the tf buffer is 49.194 miliseconds > old. > >> When trying to transform between /swissranger and /map." > > > >> I have already tried with "waitForTransform" between the two frames, > >> but nothing seems to happen. I can see by using "rosrun tf > >> view_frames" that amcl is publishing things in the future: " > >> Broadcaster: /amcl ... Most recent transform: -0.086 sec old ... ". > > > > Based on this information your tf tree looks fine. You are just > > requesting a transformation before that information is in the tf > > buffer. Calling waitForTransform before you request the actual > > transform should work. Did you call waitForTransform with the same > > frame id's and timestamp as the actual transform? Could you show the > > few lines of code where you do the tf calls? > > > > Wim > > > > > > -- > > -- > > Wim Meeussen > > Willow Garage Inc. > > > _______________________________________________ > > ros-users mailing list > > ros-users@code.ros.org > > https://code.ros.org/mailman/listinfo/ros-users > > > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users > -- Tully Foote Systems Engineer Willow Garage, Inc. tfoote@willowgarage.com (650) 475-2827