tf_interface.h
Go to the documentation of this file.
1 #ifndef __RTT_TF_TF_INTERFACE_H
2 #define __RTT_TF_TF_INTERFACE_H
3 
4 #include <ros/ros.h>
5 #include <string>
6 #include <vector>
7 #include <rtt/RTT.hpp>
8 #include <geometry_msgs/TransformStamped.h>
9 
10 namespace rtt_tf {
11 
13  class TFInterface {
14  public:
17  lookupTransform("lookupTransform"),
18  lookupTransformAtTime("lookupTransformAtTime"),
19  broadcastTransform("broadcastTransform"),
20  broadcastTransforms("broadcastTransforms"),
21  broadcastStaticTransform("broadcastStaticTransform"),
22  broadcastStaticTransforms("broadcastStaticTransforms"),
23  canTransform("canTransform"),
24  canTransformAtTime("canTransformAtTime")
25  {
26  owner->requires("tf")->addOperationCaller(lookupTransform);
27  owner->requires("tf")->addOperationCaller(lookupTransformAtTime);
28  owner->requires("tf")->addOperationCaller(broadcastTransform);
29  owner->requires("tf")->addOperationCaller(broadcastTransforms);
30  owner->requires("tf")->addOperationCaller(broadcastStaticTransform);
31  owner->requires("tf")->addOperationCaller(broadcastStaticTransforms);
32  owner->requires("tf")->addOperationCaller(canTransform);
33  owner->requires("tf")->addOperationCaller(canTransformAtTime);
34  }
35 
37  bool ready() {
38  return
45  canTransform.ready() &&
47  }
48 
57  };
58 }
59 
60 #endif // ifndef __RTT_TF_TF_INTERFACE_H
RTT::OperationCaller< geometry_msgs::TransformStamped(const std::string &, const std::string &, const ros::Time &)> lookupTransformAtTime
Definition: tf_interface.h:50
bool ready() const
RTT::OperationCaller< bool(const std::string &, const std::string &, const ros::Time &)> canTransformAtTime
Definition: tf_interface.h:56
TFInterface(RTT::TaskContext *owner)
Add interfaces to a given taskcontext.
Definition: tf_interface.h:16
Class for using the TF component from C++.
Definition: tf_interface.h:13
ServiceRequester::shared_ptr requires()
RTT::OperationCaller< void(const geometry_msgs::TransformStamped &)> broadcastTransform
Definition: tf_interface.h:51
RTT::OperationCaller< geometry_msgs::TransformStamped(const std::string &, const std::string &)> lookupTransform
Definition: tf_interface.h:49
bool ready()
Check if the operations are ready.
Definition: tf_interface.h:37
RTT::OperationCaller< void(const geometry_msgs::TransformStamped &)> broadcastStaticTransform
Definition: tf_interface.h:53
RTT::OperationCaller< void(const std::vector< geometry_msgs::TransformStamped > &)> broadcastStaticTransforms
Definition: tf_interface.h:54
RTT::OperationCaller< bool(const std::string &, const std::string &)> canTransform
Definition: tf_interface.h:55
RTT::OperationCaller< void(const std::vector< geometry_msgs::TransformStamped > &)> broadcastTransforms
Definition: tf_interface.h:52


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