Main Page
Namespaces
Classes
Files
File List
File Members
include
rtt_tf
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
:
16
TFInterface
(
RTT::TaskContext
*owner) :
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
39
lookupTransform
.
ready
() &&
40
lookupTransformAtTime
.
ready
() &&
41
broadcastTransform
.
ready
() &&
42
broadcastTransforms
.
ready
() &&
43
broadcastStaticTransform
.
ready
() &&
44
broadcastStaticTransforms
.
ready
() &&
45
canTransform
.
ready
() &&
46
canTransformAtTime
.
ready
();
47
}
48
49
RTT::OperationCaller<geometry_msgs::TransformStamped(const std::string&, const std::string&)>
lookupTransform
;
50
RTT::OperationCaller<geometry_msgs::TransformStamped(const std::string&, const std::string&, const ros::Time&)>
lookupTransformAtTime
;
51
RTT::OperationCaller<void(const geometry_msgs::TransformStamped&)>
broadcastTransform
;
52
RTT::OperationCaller<void(const std::vector<geometry_msgs::TransformStamped>
&)>
broadcastTransforms
;
53
RTT::OperationCaller<void(const geometry_msgs::TransformStamped&)>
broadcastStaticTransform
;
54
RTT::OperationCaller<void(const std::vector<geometry_msgs::TransformStamped>
&)>
broadcastStaticTransforms
;
55
RTT::OperationCaller<bool(const std::string&, const std::string&)>
canTransform
;
56
RTT::OperationCaller<bool(const std::string&, const std::string&, const ros::Time&)>
canTransformAtTime
;
57
};
58
}
59
60
#endif // ifndef __RTT_TF_TF_INTERFACE_H
rtt_tf::TFInterface::lookupTransformAtTime
RTT::OperationCaller< geometry_msgs::TransformStamped(const std::string &, const std::string &, const ros::Time &)> lookupTransformAtTime
Definition:
tf_interface.h:50
RTT::OperationCaller::ready
bool ready() const
rtt_tf
Definition:
tf_interface.h:10
rtt_tf::TFInterface::canTransformAtTime
RTT::OperationCaller< bool(const std::string &, const std::string &, const ros::Time &)> canTransformAtTime
Definition:
tf_interface.h:56
rtt_tf::TFInterface::TFInterface
TFInterface(RTT::TaskContext *owner)
Add interfaces to a given taskcontext.
Definition:
tf_interface.h:16
rtt_tf::TFInterface
Class for using the TF component from C++.
Definition:
tf_interface.h:13
RTT::TaskContext::requires
ServiceRequester::shared_ptr requires()
rtt_tf::TFInterface::broadcastTransform
RTT::OperationCaller< void(const geometry_msgs::TransformStamped &)> broadcastTransform
Definition:
tf_interface.h:51
RTT::OperationCaller< geometry_msgs::TransformStamped(const std::string &, const std::string &)>
rtt_tf::TFInterface::lookupTransform
RTT::OperationCaller< geometry_msgs::TransformStamped(const std::string &, const std::string &)> lookupTransform
Definition:
tf_interface.h:49
rtt_tf::TFInterface::ready
bool ready()
Check if the operations are ready.
Definition:
tf_interface.h:37
rtt_tf::TFInterface::broadcastStaticTransform
RTT::OperationCaller< void(const geometry_msgs::TransformStamped &)> broadcastStaticTransform
Definition:
tf_interface.h:53
ros.h
rtt_tf::TFInterface::broadcastStaticTransforms
RTT::OperationCaller< void(const std::vector< geometry_msgs::TransformStamped > &)> broadcastStaticTransforms
Definition:
tf_interface.h:54
RTT::TaskContext
rtt_tf::TFInterface::canTransform
RTT::OperationCaller< bool(const std::string &, const std::string &)> canTransform
Definition:
tf_interface.h:55
RTT.hpp
rtt_tf::TFInterface::broadcastTransforms
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