rtt_tf-component.hpp
Go to the documentation of this file.
1 #ifndef OROCOS_RTT_TF_COMPONENT_HPP
2 #define OROCOS_RTT_TF_COMPONENT_HPP
3 
4 #include <rtt/RTT.hpp>
5 #include <tf2_msgs/TFMessage.h>
6 #include <tf2/buffer_core.h>
8 
9 #include <boost/shared_ptr.hpp>
10 
11 namespace rtt_tf
12 {
13  // Inherit from TaskContext and Transformer, the second is required in order to use tf_prefix
14  class RTT_TF: public RTT::TaskContext, protected tf2::BufferCore
15  {
19 
20  static const int DEFAULT_BUFFER_SIZE = 100;
21 
24  std::string prop_tf_prefix;
25 
30  std::map<std::pair<std::string, std::string>, OutputPortGeometryTransfromStampedPtr> ports_trackers;
31  BufferCorePtr buffer_core;
32  TransformListenerPtr transform_listener;
33 
34  void internalUpdate(
35  tf2_msgs::TFMessage& msg,
37  bool is_static);
38 
40  const std::string& target,
41  const std::string& source) const;
42 
43  bool canTransform(
44  const std::string& target,
45  const std::string& source) const;
46 
47  bool canTransformAtTime(
48  const std::string& target,
49  const std::string& source,
50  const ros::Time& common_time) const;
51 
52  geometry_msgs::TransformStamped lookupTransform(
53  const std::string& target,
54  const std::string& source) const;
55 
56  geometry_msgs::TransformStamped lookupTransformAtTime(
57  const std::string& target,
58  const std::string& source,
59  const ros::Time& common_time) const;
60 
61  void broadcastTransform(
62  const geometry_msgs::TransformStamped &tform);
63 
65  const std::vector<geometry_msgs::TransformStamped> &tforms);
66 
68  const geometry_msgs::TransformStamped &tform);
69 
71  const std::vector<geometry_msgs::TransformStamped> &tforms);
72 
74 
75  bool subscribeTransfrom(
76  const std::string& target,
77  const std::string& source);
78 
79  void listTrackers();
80 
81  public:
82  RTT_TF(std::string const& name);
83 
84  bool configureHook();
85 
86  bool startHook();
87 
88  void updateHook();
89 
90  void stopHook();
91 
92  void cleanupHook();
93  };
94 }//namespace rtt_tf
95 #endif
bool canTransform(const std::string &target, const std::string &source) const
void addTFOperations(RTT::Service::shared_ptr service)
geometry_msgs::TransformStamped lookupTransform(const std::string &target, const std::string &source) const
boost::shared_ptr< tf2_ros::TransformListener > TransformListenerPtr
boost::shared_ptr< tf2::BufferCore > BufferCorePtr
ros::Time getLatestCommonTime(const std::string &target, const std::string &source) const
TransformListenerPtr transform_listener
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_static_out
std::map< std::pair< std::string, std::string >, OutputPortGeometryTransfromStampedPtr > ports_trackers
bool subscribeTransfrom(const std::string &target, const std::string &source)
static const int DEFAULT_BUFFER_SIZE
bool canTransformAtTime(const std::string &target, const std::string &source, const ros::Time &common_time) const
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_out
void broadcastTransform(const geometry_msgs::TransformStamped &tform)
RTT::InputPort< tf2_msgs::TFMessage > port_tf_static_in
RTT::InputPort< tf2_msgs::TFMessage > port_tf_in
void internalUpdate(tf2_msgs::TFMessage &msg, RTT::InputPort< tf2_msgs::TFMessage > &port, bool is_static)
void broadcastTransforms(const std::vector< geometry_msgs::TransformStamped > &tforms)
void broadcastStaticTransforms(const std::vector< geometry_msgs::TransformStamped > &tforms)
BufferCorePtr buffer_core
void broadcastStaticTransform(const geometry_msgs::TransformStamped &tform)
RTT_TF(std::string const &name)
geometry_msgs::TransformStamped lookupTransformAtTime(const std::string &target, const std::string &source, const ros::Time &common_time) const
std::string prop_tf_prefix
boost::shared_ptr< RTT::OutputPort< geometry_msgs::TransformStamped > > OutputPortGeometryTransfromStampedPtr


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