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>
7 
8 namespace rtt_tf
9 {
10  // Inherit from TaskContext and Transformer, the second is required in order to use tf_prefix
11  class RTT_TF: public RTT::TaskContext, protected tf2::BufferCore
12  {
13  static const int DEFAULT_BUFFER_SIZE = 100;
14 
17  std::string prop_tf_prefix;
18 
23 
24  void internalUpdate(
25  tf2_msgs::TFMessage& msg,
27  bool is_static);
28 
30  const std::string& target,
31  const std::string& source) const;
32 
33  bool canTransform(
34  const std::string& target,
35  const std::string& source) const;
36 
37  bool canTransformAtTime(
38  const std::string& target,
39  const std::string& source,
40  const ros::Time& common_time) const;
41 
42  geometry_msgs::TransformStamped lookupTransform(
43  const std::string& target,
44  const std::string& source) const;
45 
46  geometry_msgs::TransformStamped lookupTransformAtTime(
47  const std::string& target,
48  const std::string& source,
49  const ros::Time& common_time) const;
50 
51  void broadcastTransform(
52  const geometry_msgs::TransformStamped &tform);
53 
55  const std::vector<geometry_msgs::TransformStamped> &tforms);
56 
58  const geometry_msgs::TransformStamped &tform);
59 
61  const std::vector<geometry_msgs::TransformStamped> &tforms);
62 
64 
65  public:
66  RTT_TF(std::string const& name);
67 
68  bool configureHook();
69 
70  void updateHook();
71 
72  void cleanupHook();
73  };
74 }//namespace rtt_tf
75 #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
ros::Time getLatestCommonTime(const std::string &target, const std::string &source) const
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_static_out
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)
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


rtt_tf
Author(s): Ruben Smits
autogenerated on Sat Jun 8 2019 18:06:38