tf_example_node.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
29 #include <tf/transform_listener.h>
30 #include <find_object_2d/ObjectsStamped.h>
31 #include <QtCore/QString>
32 
33 class TfExample
34 {
35 public:
37  mapFrameId_("/map"),
38  objFramePrefix_("object")
39  {
40  ros::NodeHandle pnh("~");
41  pnh.param("map_frame_id", mapFrameId_, mapFrameId_);
42  pnh.param("object_prefix", objFramePrefix_, objFramePrefix_);
43 
44  ros::NodeHandle nh;
45  subs_ = nh.subscribe("objectsStamped", 1, &TfExample::objectsDetectedCallback, this);
46  }
47 
48  // Here I synchronize with the ObjectsStamped topic to
49  // know when the TF is ready and for which objects
50  void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr & msg)
51  {
52  if(msg->objects.data.size())
53  {
54  for(unsigned int i=0; i<msg->objects.data.size(); i+=12)
55  {
56  // get data
57  int id = (int)msg->objects.data[i];
58  std::string objectFrameId = QString("%1_%2").arg(objFramePrefix_.c_str()).arg(id).toStdString(); // "object_1", "object_2"
59 
61  tf::StampedTransform poseCam;
62  try
63  {
64  // Get transformation from "object_#" frame to target frame "map"
65  // The timestamp matches the one sent over TF
66  tfListener_.lookupTransform(mapFrameId_, objectFrameId, msg->header.stamp, pose);
67  tfListener_.lookupTransform(msg->header.frame_id, objectFrameId, msg->header.stamp, poseCam);
68  }
69  catch(tf::TransformException & ex)
70  {
71  ROS_WARN("%s",ex.what());
72  continue;
73  }
74 
75  // Here "pose" is the position of the object "id" in "/map" frame.
76  ROS_INFO("Object_%d [x,y,z] [x,y,z,w] in \"%s\" frame: [%f,%f,%f] [%f,%f,%f,%f]",
77  id, mapFrameId_.c_str(),
78  pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z(),
79  pose.getRotation().x(), pose.getRotation().y(), pose.getRotation().z(), pose.getRotation().w());
80  ROS_INFO("Object_%d [x,y,z] [x,y,z,w] in \"%s\" frame: [%f,%f,%f] [%f,%f,%f,%f]",
81  id, msg->header.frame_id.c_str(),
82  poseCam.getOrigin().x(), poseCam.getOrigin().y(), poseCam.getOrigin().z(),
83  poseCam.getRotation().x(), poseCam.getRotation().y(), poseCam.getRotation().z(), poseCam.getRotation().w());
84  }
85  }
86  }
87 
88 private:
89  std::string mapFrameId_;
90  std::string objFramePrefix_;
93 };
94 
95 int main(int argc, char * argv[])
96 {
97  ros::init(argc, argv, "tf_example_node");
98 
99  TfExample sync;
100  ros::spin();
101 }
tf::TransformListener tfListener_
void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string mapFrameId_
ros::Subscriber subs_
#define ROS_WARN(...)
ROSCPP_DECL void spin(Spinner &spinner)
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::string objFramePrefix_
TFSIMD_FORCE_INLINE const tfScalar & z() const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
int main(int argc, char *argv[])
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
Quaternion getRotation() const


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Jun 10 2019 13:21:31