ros2/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 <rclcpp/rclcpp.hpp>
30 #include <tf2_ros/buffer.h>
31 #include <find_object_2d/msg/objects_stamped.hpp>
32 #include <geometry_msgs/msg/transform_stamped.hpp>
33 #include <QtCore/QString>
34 
35 class TfExample : public rclcpp::Node
36 {
37 public:
39  Node("tf_example_node"),
40  objFramePrefix_("object")
41  {
42  tfBuffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
43  //auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
44  // this->get_node_base_interface(),
45  // this->get_node_timers_interface());
46  //tfBuffer_->setCreateTimerInterface(timer_interface);
47  tfListener_ = std::make_shared<tf2_ros::TransformListener>(*tfBuffer_);
48 
49  targetFrameId_ = this->declare_parameter("target_frame_id", targetFrameId_);
50  objFramePrefix_ = this->declare_parameter("object_prefix", objFramePrefix_);
51 
52  subs_ = create_subscription<find_object_2d::msg::ObjectsStamped>("objectsStamped", rclcpp::QoS(5).reliability((rmw_qos_reliability_policy_t)1), std::bind(&TfExample::objectsDetectedCallback, this, std::placeholders::_1));
53  }
54 
55  // Here I synchronize with the ObjectsStamped topic to
56  // know when the TF is ready and for which objects
57  void objectsDetectedCallback(const find_object_2d::msg::ObjectsStamped::ConstSharedPtr msg)
58  {
59  if(msg->objects.data.size())
60  {
61  std::string targetFrameId = targetFrameId_;
62  if(targetFrameId.empty())
63  {
64  targetFrameId = msg->header.frame_id;
65  }
66  char multiSubId = 'b';
67  int previousId = -1;
68  for(unsigned int i=0; i<msg->objects.data.size(); i+=12)
69  {
70  // get data
71  int id = (int)msg->objects.data[i];
72 
73  QString multiSuffix;
74  if(id == previousId)
75  {
76  multiSuffix = QString("_") + multiSubId++;
77  }
78  else
79  {
80  multiSubId = 'b';
81  }
82  previousId = id;
83 
84  // "object_1", "object_1_b", "object_1_c", "object_2"
85  std::string objectFrameId = QString("%1_%2%3").arg(objFramePrefix_.c_str()).arg(id).arg(multiSuffix).toStdString();
86 
87  geometry_msgs::msg::TransformStamped pose;
88  try
89  {
90  // Get transformation from "object_#" frame to target frame
91  // The timestamp matches the one sent over TF
92  pose = tfBuffer_->lookupTransform(targetFrameId, objectFrameId, tf2_ros::fromMsg(msg->header.stamp));
93  }
94  catch(tf2::TransformException & ex)
95  {
96  RCLCPP_WARN(this->get_logger(), "%s",ex.what());
97  continue;
98  }
99 
100  // Here "pose" is the position of the object "id" in target frame.
101  RCLCPP_INFO(this->get_logger(), "%s [x,y,z] [x,y,z,w] in \"%s\" frame: [%f,%f,%f] [%f,%f,%f,%f]",
102  objectFrameId.c_str(), targetFrameId.c_str(),
103  pose.transform.translation.x, pose.transform.translation.y, pose.transform.translation.z,
104  pose.transform.rotation.x, pose.transform.rotation.y, pose.transform.rotation.z, pose.transform.rotation.w);
105  }
106  }
107  }
108 
109 private:
110  std::string targetFrameId_;
111  std::string objFramePrefix_;
112  rclcpp::Subscription<find_object_2d::msg::ObjectsStamped>::SharedPtr subs_;
113  std::shared_ptr<tf2_ros::Buffer> tfBuffer_;
114  std::shared_ptr<tf2_ros::TransformListener> tfListener_;
115 };
116 
117 int main(int argc, char * argv[])
118 {
119  rclcpp::init(argc, argv);
120  rclcpp::spin(std::make_shared<TfExample>());
121  rclcpp::shutdown();
122 }
tf::TransformListener tfListener_
void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr &msg)
void objectsDetectedCallback(const find_object_2d::msg::ObjectsStamped::ConstSharedPtr msg)
rclcpp::Subscription< find_object_2d::msg::ObjectsStamped >::SharedPtr subs_
ros::Subscriber subs_
int main(int argc, char *argv[])
std::shared_ptr< tf2_ros::Buffer > tfBuffer_
std::string objFramePrefix_
std::shared_ptr< tf2_ros::TransformListener > tfListener_
std::string targetFrameId_


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