rtt_tf-component.cpp
Go to the documentation of this file.
1 /*
2  * (C) 2011, Ruben Smits, ruben.smits@mech.kuleuven.be
3  * Department of Mechanical Engineering,
4  * Katholieke Universiteit Leuven, Belgium.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions
8  * are met:
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * 3. Neither the name of the copyright holder nor the names of its contributors
15  * may be used to endorse or promote products derived from this software
16  * without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
21  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
22  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
23  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
27  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
28  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #include "rtt_tf-component.hpp"
33 #include <rtt/Component.hpp>
34 #include <rtt/Logger.hpp>
35 #include <ros/ros.h>
36 
37 #include <tf/tf.h>
38 #include <tf2/exceptions.h>
39 
40 #include <geometry_msgs/TransformStamped.h>
41 
42 #include <algorithm>
43 
44 namespace rtt_tf
45 {
46  // Functor for resolving the tf prefix when broadcasting multiple transforms.
48  {
49  public:
50  PrefixResolver(const std::string& prefix) : prefix_(prefix) { }
51 
52  geometry_msgs::TransformStamped operator()(const geometry_msgs::TransformStamped& elem)
53  {
54  geometry_msgs::TransformStamped result = elem;
55  result.header.frame_id = tf::resolve(prefix_, result.header.frame_id);
56  result.child_frame_id = tf::resolve(prefix_, result.child_frame_id);
57  return result;
58  }
59 
60  private:
61  const std::string& prefix_;
62  };
63 
64  tf2_msgs::TFMessage transformsToMessage(const std::vector<geometry_msgs::TransformStamped>& tforms, const std::string& prefix)
65  {
66  tf2_msgs::TFMessage msg;
67  // resolve names and copy transforms to message
68  msg.transforms.resize(tforms.size());
69  std::transform(tforms.begin(), tforms.end(), msg.transforms.begin(), PrefixResolver(prefix));
70  return msg;
71  }
72 
73  using namespace RTT;
74 
75  RTT_TF::RTT_TF(const std::string& name) :
76  TaskContext(name, PreOperational),
77  tf2::BufferCore( ros::Duration(BufferCore::DEFAULT_CACHE_TIME) ),
78  prop_cache_time( BufferCore::DEFAULT_CACHE_TIME ),
79  prop_buffer_size(DEFAULT_BUFFER_SIZE)
80  {
81  this->addProperty("cache_time", prop_cache_time);
82  this->addProperty("buffer_size", prop_buffer_size);
83  this->addProperty("tf_prefix", prop_tf_prefix);
84  this->addEventPort("tf_in", port_tf_in);
85  this->addEventPort("tf_static_in", port_tf_static_in);
86  this->addPort("tf_out", port_tf_out);
87 
88  this->addTFOperations(this->provides());
89  this->addTFOperations(this->provides("tf"));
90  }
91 
93  {
94  service->addOperation("lookupTransform", &RTT_TF::lookupTransform, this)
95  .doc("Lookup the most recent transform from source to target.")
96  .arg("target", "target frame")
97  .arg("source", "source frame");
98 
99  service->addOperation("lookupTransformAtTime", &RTT_TF::lookupTransformAtTime, this)
100  .doc("Lookup the most recent transform from source to target at a specific time.")
101  .arg("target", "Target frame")
102  .arg("source", "Source frame")
103  .arg("common_time", "[ros::Time] The common time at which the transform should be computed");
104 
105  service->addOperation("broadcastTransform", &RTT_TF::broadcastTransform, this, RTT::OwnThread)
106  .doc("Broadcast a stamped transform immediately.")
107  .arg("transform", "[geometry_msgs::TransformStamped]");
108 
109  service->addOperation("broadcastTransforms", &RTT_TF::broadcastTransforms, this, RTT::OwnThread)
110  .doc("Broadcast stamped transforms immediately.")
111  .arg("transforms", "[std::vector<geometry_msgs::TransformStamped>]");
112 
113  service->addOperation("broadcastStaticTransform", &RTT_TF::broadcastStaticTransform, this, RTT::OwnThread)
114  .doc("Broadcast a stamped transform as a static transform immediately.")
115  .arg("transform", "[geometry_msgs::TransformStamped]");
116 
117  service->addOperation("broadcastStaticTransforms", &RTT_TF::broadcastStaticTransforms, this, RTT::OwnThread)
118  .doc("Broadcast stamped transforms as static transforms immediately.")
119  .arg("transforms", "[std::vector<geometry_msgs::TransformStamped>]");
120 
121  service->addOperation("canTransform", &RTT_TF::canTransform, this)
122  .doc("Check if the transform from source to target can be resolved.")
123  .arg("target", "Target frame")
124  .arg("source", "Source frame");
125 
126  service->addOperation("canTransformAtTime", &RTT_TF::canTransformAtTime, this)
127  .doc("Check if the transform from source to target can be resolved for a given common time.")
128  .arg("target", "Target frame")
129  .arg("source", "Source frame")
130  .arg("common_time", "[ros::Time] The common time for which the transform would resolve");
131 
132  service->addOperation("subscribeTransform", &RTT_TF::subscribeTransfrom, this)
133  .doc("Tracks a transformation and reprots the new transforms via a port")
134  .arg("target", "Target frame id")
135  .arg("source", "Source frame id");
136 
137  service->addOperation("listTrackers", &RTT_TF::listTrackers, this)
138  .doc("Lists the TF trackers added via subscribeTransfrom()");
139  }
140 
142  {
143  Logger::In(this->getName());
144 
145  // Get tf prefix rosparam
146  ros::NodeHandle nh("~");
147  std::string tf_prefix_param_key;
148  if(nh.searchParam("tf_prefix",tf_prefix_param_key)) {
149  nh.getParam(tf_prefix_param_key, prop_tf_prefix);
150  }
151 
152  // Connect to tf topic
154  cp.transport = 3; //3=ROS
155  cp.name_id = "/tf";
156 
157  // Connect to tf_static topic
159  cp_static.transport = 3; //3=ROS
160  cp_static.name_id = "/tf_static";
161 
162  bool configured = port_tf_static_in.createStream(cp_static)
163  && port_tf_in.createStream(cp)
165  && port_tf_static_out.createStream(cp_static);
166 
167  if (!configured) {
168  cleanupHook();
169  }
170 
171  return configured;
172  }
173 
174  void RTT_TF::internalUpdate(tf2_msgs::TFMessage& msg, RTT::InputPort<tf2_msgs::TFMessage>& port, bool is_static)
175  {
176  // tf2::BufferCore::setTransform (see #68) has a non-defaulted authority argument,
177  // but there is no __connection_header to extract it from.
178  const std::string authority = "unknown_authority";
179 
180  while (port.read(msg) == NewData) {
181  for (std::size_t i = 0; i < msg.transforms.size(); ++i) {
182  try {
183  this->setTransform(msg.transforms[i], authority, is_static);
184  } catch (tf2::TransformException& ex) {
185  log(Error) << "Failure to set received transform from "
186  << msg.transforms[i].child_frame_id << " to "
187  << msg.transforms[i].header.frame_id
188  << " with error: " << ex.what() << endlog();
189  }
190  }
191  }
192  // Publish the geometry messages obtained from the lookupTransform on
193  // tracked transformations
194  // Range for not supported in ISO pre-C++ 11
195  // for (const auto& tracker : ports_trackers) {
196  // auto msg = lookupTransform(tracker.first.first, tracker.first.second);
197  // tracker.second->write(msg);
198  // }
199  for(std::map<std::pair<std::string, std::string>, OutputPortGeometryTransfromStampedPtr>::iterator
200  it_tracker = ports_trackers.begin(); it_tracker != ports_trackers.end(); ++it_tracker) {
201  geometry_msgs::TransformStamped msg = lookupTransform(it_tracker->first.first, it_tracker->first.second);
202  it_tracker->second->write(msg);
203  }
204  }
205 
207  {
208  if (0 == getPeriod()) {
209  RTT::log(RTT::Warning) << "The period of the component is 0 (zero), so no"
210  " updates form TF will be published automatically" << RTT::endlog();
211  }
212  buffer_core.reset(new tf2::BufferCore());
214  return true;
215  }
216 
218  {
219  Logger::In(this->getName());
220 #ifndef NDEBUG
221  //log(Debug) << "In update" << endlog();
222 #endif
223  try
224  {
225  tf2_msgs::TFMessage msg_in;
226  internalUpdate(msg_in, port_tf_in, false);
227  internalUpdate(msg_in, port_tf_static_in, true);
228  }
229  catch (std::exception& ex)
230  {
231  log(Error) << ex.what() << endlog();
232  }
233  }
234 
236  {
237  transform_listener.reset();
238  buffer_core.reset();
239  }
240 
242  {
247  }
248 
250  const std::string& target,
251  const std::string& source) const
252  {
253  ros::Time common_time;
254 
255  tf2::CompactFrameID target_id = _lookupFrameNumber(target);
256  tf2::CompactFrameID source_id = _lookupFrameNumber(source);
257 
258  _getLatestCommonTime(source_id, target_id, common_time, NULL);
259 
260  return common_time;
261  }
262 
263  geometry_msgs::TransformStamped RTT_TF::lookupTransform(
264  const std::string& target,
265  const std::string& source) const
266  {
267  return tf2::BufferCore::lookupTransform(target, source, ros::Time());
268  }
269 
271  const std::string& target,
272  const std::string& source) const
273  {
274  return tf2::BufferCore::canTransform(target, source, ros::Time());
275  }
276 
278  const std::string& target,
279  const std::string& source,
280  const ros::Time& common_time) const
281  {
282  return tf2::BufferCore::canTransform(target, source, common_time);
283  }
284 
285  geometry_msgs::TransformStamped RTT_TF::lookupTransformAtTime(
286  const std::string& target,
287  const std::string& source,
288  const ros::Time& common_time) const
289  {
290  return tf2::BufferCore::lookupTransform(target, source, common_time);
291  }
292 
293  void RTT_TF::broadcastTransform(const geometry_msgs::TransformStamped& tform)
294  {
295  const std::vector<geometry_msgs::TransformStamped> tforms(1, tform);
296  tf2_msgs::TFMessage msg_out = transformsToMessage(tforms, prop_tf_prefix);
297  port_tf_out.write(msg_out);
298  }
299 
300  void RTT_TF::broadcastTransforms(const std::vector<geometry_msgs::TransformStamped>& tform)
301  {
302  tf2_msgs::TFMessage msg_out = transformsToMessage(tform, prop_tf_prefix);
303  port_tf_out.write(msg_out);
304  }
305 
306  void RTT_TF::broadcastStaticTransform(const geometry_msgs::TransformStamped& tform)
307  {
308  const std::vector<geometry_msgs::TransformStamped> tforms(1, tform);
309  tf2_msgs::TFMessage msg_out = transformsToMessage(tforms, prop_tf_prefix);
310  port_tf_static_out.write(msg_out);
311  }
312 
313  void RTT_TF::broadcastStaticTransforms(const std::vector<geometry_msgs::TransformStamped>& tform)
314  {
315  tf2_msgs::TFMessage msg_out = transformsToMessage(tform, prop_tf_prefix);
316  port_tf_static_out.write(msg_out);
317  }
318 
319  bool RTT_TF::subscribeTransfrom(const std::string& target, const std::string& source)
320  {
321  Logger::In(this->getName());
322  const std::pair<std::string, std::string> transfrom_pair(target, source);
323  const std::string name_transform = source + "_" + target;
324  const std::string name_port = "tracker_tf_" + name_transform;
325  if (ports_trackers.find(transfrom_pair) != ports_trackers.end()) {
326  RTT::log(RTT::Warning) << "The transfrom from " << source << " to " << target <<
327  " is already tracked." << RTT::endlog();
328  return false;
329  }
330  if (!canTransform(target, source)) {
331  RTT::log(RTT::Warning) << "The transformation from " << source <<
332  " to " << target << " cannot yet be performed" << RTT::endlog();
333  }
334  ports_trackers[transfrom_pair] =
335  boost::make_shared<RTT::OutputPort<geometry_msgs::TransformStamped> >(name_port);
336  this->addPort(*ports_trackers[transfrom_pair])
337  .doc("Port generated by " + getName() + " for the transformation: " + name_transform);
338  return true;
339  }
340 
342 {
343  Logger::In(this->getName());
344  const RTT::Logger::LogLevel config_level = RTT::Logger::Instance()->getLogLevel();
346  RTT::log() << "Listing existing trackers" << RTT::endlog();
347  RTT::log(RTT::Info) << "(Source) <-> (Target) : [PortName]" << RTT::endlog();
348  RTT::log(RTT::Info) << "----------------------------------" << RTT::endlog();
349  // ISO C++ doesnt allow the next for, so need to use iterator
350  // for (const auto& entry : ports_trackers) {
351  // RTT::log(RTT::Info) << entry.first.second << " <-> " << entry.first.first <<
352  // " : [" <<entry.second->getName() << "]" << RTT::endlog();
353  // }
354  for(std::map<std::pair<std::string, std::string>, OutputPortGeometryTransfromStampedPtr>::iterator
355  it = ports_trackers.begin(); it != ports_trackers.end(); ++it) {
356  RTT::log(RTT::Info) << it->first.second << " <-> " << it->first.first <<
357  " : [" << it->second->getName() << "]" << RTT::endlog();
358  }
359  RTT::Logger::Instance()->setLogLevel(config_level);
360 }
361 }//namespace
362 
363 /*
364  * Using this macro, only one component may live
365  * in one library *and* you may *not* link this library
366  * with another component library. Use
367  * ORO_CREATE_COMPONENT_TYPE()
368  * ORO_LIST_COMPONENT_TYPE(Rtt_tf)
369  * In case you want to link with another library that
370  * already contains components.
371  *
372  * If you have put your component class
373  * in a namespace, don't forget to add it here too:
374  */
Property< T > & addProperty(const std::string &name, T &attr)
bool canTransform(const std::string &target, const std::string &source) const
void addTFOperations(RTT::Service::shared_ptr service)
uint32_t CompactFrameID
geometry_msgs::TransformStamped lookupTransform(const std::string &target, const std::string &source) const
ORO_CREATE_COMPONENT(BroadcasterComponent)
boost::shared_ptr< tf2_ros::TransformListener > TransformListenerPtr
Service::shared_ptr provides()
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
base::InputPortInterface & addEventPort(const std::string &name, base::InputPortInterface &port, SlotFunction callback=SlotFunction())
LogLevel getLogLevel() const
static Logger * Instance(std::ostream &str=std::cerr)
ros::Time getLatestCommonTime(const std::string &target, const std::string &source) const
TransformListenerPtr transform_listener
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_static_out
FlowStatus read(base::DataSourceBase::shared_ptr source)
std::map< std::pair< std::string, std::string >, OutputPortGeometryTransfromStampedPtr > ports_trackers
std::string resolve(const std::string &prefix, const std::string &frame_name)
bool subscribeTransfrom(const std::string &target, const std::string &source)
virtual Seconds getPeriod() const
bool searchParam(const std::string &key, std::string &result) const
bool canTransformAtTime(const std::string &target, const std::string &source, const ros::Time &common_time) const
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_out
base::PortInterface & addPort(const std::string &name, base::PortInterface &port)
virtual bool createStream(ConnPolicy const &policy)
void broadcastTransform(const geometry_msgs::TransformStamped &tform)
const std::string & prefix_
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
static ConnPolicy buffer(int size, int lock_policy=LOCK_FREE, bool init_connection=false, bool pull=false)
WriteStatus write(const T &sample)
RTT::InputPort< tf2_msgs::TFMessage > port_tf_static_in
CompactFrameID _lookupFrameNumber(const std::string &frameid_str) const
RTT::InputPort< tf2_msgs::TFMessage > port_tf_in
void internalUpdate(tf2_msgs::TFMessage &msg, RTT::InputPort< tf2_msgs::TFMessage > &port, bool is_static)
PrefixResolver(const std::string &prefix)
int _getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
void broadcastTransforms(const std::vector< geometry_msgs::TransformStamped > &tforms)
void broadcastStaticTransforms(const std::vector< geometry_msgs::TransformStamped > &tforms)
bool getParam(const std::string &key, std::string &s) const
BufferCorePtr buffer_core
void broadcastStaticTransform(const geometry_msgs::TransformStamped &tform)
tf2_msgs::TFMessage transformsToMessage(const std::vector< geometry_msgs::TransformStamped > &tforms, const std::string &prefix)
PortInterface & doc(const std::string &desc)
geometry_msgs::TransformStamped operator()(const geometry_msgs::TransformStamped &elem)
std::string name_id
RTT_TF(std::string const &name)
static Logger & log()
geometry_msgs::TransformStamped lookupTransformAtTime(const std::string &target, const std::string &source, const ros::Time &common_time) const
std::string prop_tf_prefix
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const
virtual bool createStream(ConnPolicy const &policy)
static Logger::LogFunction endlog()
virtual const std::string & getName() const
void setLogLevel(LogLevel ll)


rtt_tf
Author(s): Ruben Smits
autogenerated on Mon May 10 2021 02:46:04