00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <ros/ros.h>
00029 #include <tf/transform_listener.h>
00030 #include <find_object_2d/ObjectsStamped.h>
00031 #include <QtCore/QString>
00032
00033 class TfExample
00034 {
00035 public:
00036 TfExample() :
00037 mapFrameId_("/map"),
00038 objFramePrefix_("object")
00039 {
00040 ros::NodeHandle pnh("~");
00041 pnh.param("map_frame_id", mapFrameId_, mapFrameId_);
00042 pnh.param("object_prefix", objFramePrefix_, objFramePrefix_);
00043
00044 ros::NodeHandle nh;
00045 subs_ = nh.subscribe("objectsStamped", 1, &TfExample::objectsDetectedCallback, this);
00046 }
00047
00048
00049
00050 void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr & msg)
00051 {
00052 if(msg->objects.data.size())
00053 {
00054 for(unsigned int i=0; i<msg->objects.data.size(); i+=12)
00055 {
00056
00057 int id = (int)msg->objects.data[i];
00058 std::string objectFrameId = QString("%1_%2").arg(objFramePrefix_.c_str()).arg(id).toStdString();
00059
00060 tf::StampedTransform pose;
00061 tf::StampedTransform poseCam;
00062 try
00063 {
00064
00065
00066 tfListener_.lookupTransform(mapFrameId_, objectFrameId, msg->header.stamp, pose);
00067 tfListener_.lookupTransform(msg->header.frame_id, objectFrameId, msg->header.stamp, poseCam);
00068 }
00069 catch(tf::TransformException & ex)
00070 {
00071 ROS_WARN("%s",ex.what());
00072 continue;
00073 }
00074
00075
00076 ROS_INFO("Object_%d [x,y,z] [x,y,z,w] in \"%s\" frame: [%f,%f,%f] [%f,%f,%f,%f]",
00077 id, mapFrameId_.c_str(),
00078 pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z(),
00079 pose.getRotation().x(), pose.getRotation().y(), pose.getRotation().z(), pose.getRotation().w());
00080 ROS_INFO("Object_%d [x,y,z] [x,y,z,w] in \"%s\" frame: [%f,%f,%f] [%f,%f,%f,%f]",
00081 id, msg->header.frame_id.c_str(),
00082 poseCam.getOrigin().x(), poseCam.getOrigin().y(), poseCam.getOrigin().z(),
00083 poseCam.getRotation().x(), poseCam.getRotation().y(), poseCam.getRotation().z(), poseCam.getRotation().w());
00084 }
00085 }
00086 }
00087
00088 private:
00089 std::string mapFrameId_;
00090 std::string objFramePrefix_;
00091 ros::Subscriber subs_;
00092 tf::TransformListener tfListener_;
00093 };
00094
00095 int main(int argc, char * argv[])
00096 {
00097 ros::init(argc, argv, "tf_example_node");
00098
00099 TfExample sync;
00100 ros::spin();
00101 }