ros1/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  objFramePrefix_("object")
38  {
39  ros::NodeHandle pnh("~");
40  pnh.param("target_frame_id", targetFrameId_, targetFrameId_);
41  pnh.param("object_prefix", objFramePrefix_, objFramePrefix_);
42 
43  ros::NodeHandle nh;
44  subs_ = nh.subscribe("objectsStamped", 1, &TfExample::objectsDetectedCallback, this);
45  }
46 
47  // Here I synchronize with the ObjectsStamped topic to
48  // know when the TF is ready and for which objects
49  void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr & msg)
50  {
51  if(msg->objects.data.size())
52  {
53  std::string targetFrameId = targetFrameId_;
54  if(targetFrameId.empty())
55  {
56  targetFrameId = msg->header.frame_id;
57  }
58  char multiSubId = 'b';
59  int previousId = -1;
60  for(unsigned int i=0; i<msg->objects.data.size(); i+=12)
61  {
62  // get data
63  int id = (int)msg->objects.data[i];
64 
65  QString multiSuffix;
66  if(id == previousId)
67  {
68  multiSuffix = QString("_") + multiSubId++;
69  }
70  else
71  {
72  multiSubId = 'b';
73  }
74  previousId = id;
75 
76  // "object_1", "object_1_b", "object_1_c", "object_2"
77  std::string objectFrameId = QString("%1_%2%3").arg(objFramePrefix_.c_str()).arg(id).arg(multiSuffix).toStdString();
78 
80  try
81  {
82  // Get transformation from "object_#" frame to target frame
83  // The timestamp matches the one sent over TF
84  tfListener_.lookupTransform(targetFrameId, objectFrameId, msg->header.stamp, pose);
85  }
86  catch(tf::TransformException & ex)
87  {
88  ROS_WARN("%s",ex.what());
89  continue;
90  }
91 
92  // Here "pose" is the position of the object "id" in target frame.
93  ROS_INFO("%s [x,y,z] [x,y,z,w] in \"%s\" frame: [%f,%f,%f] [%f,%f,%f,%f]",
94  objectFrameId.c_str(), targetFrameId.c_str(),
95  pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z(),
96  pose.getRotation().x(), pose.getRotation().y(), pose.getRotation().z(), pose.getRotation().w());
97  }
98  }
99  }
100 
101 private:
102  std::string targetFrameId_;
103  std::string objFramePrefix_;
106 };
107 
108 int main(int argc, char * argv[])
109 {
110  ros::init(argc, argv, "tf_example_node");
111 
112  TfExample sync;
113  ros::spin();
114 }
tf::TransformListener tfListener_
void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr &msg)
Quaternion getRotation() const
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)
int main(int argc, char *argv[])
ros::Subscriber subs_
#define ROS_WARN(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string objFramePrefix_
#define ROS_INFO(...)
ROSCPP_DECL void spin()
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
std::string targetFrameId_
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Dec 12 2022 03:20:09