6 #include <ocl/DeploymentComponent.hpp> 7 #include <ocl/TaskBrowser.hpp> 8 #include "../rtt_tf-component.hpp" 9 #include <geometry_msgs/TransformStamped.h> 15 geometry_msgs::TransformStamped
tform_;
28 tform_.transform.translation.x = 0;
29 tform_.transform.translation.y = 0;
30 tform_.transform.translation.z = 0;
31 tform_.transform.rotation.x = 0;
32 tform_.transform.rotation.y = 0;
33 tform_.transform.rotation.z = 0;
34 tform_.transform.rotation.w = 1;
40 tform_.header.frame_id =
"/world";
42 tform_.child_frame_id =
"/rtt_tf_test";
43 tform_.transform.translation.x = cos(t);
44 tform_.transform.translation.y = sin(t);
46 tform_.header.frame_id =
"/world";
48 tform_.child_frame_id =
"rel_rtt_tf_test";
49 tform_.transform.translation.x = cos(t);
50 tform_.transform.translation.y = sin(t);
67 deployer.
import(
"rtt_rosnode");
68 deployer.
import(
"rtt_std_msgs");
69 deployer.
import(
"rtt_geometry_msgs");
70 deployer.
import(
"rtt_tf2_msgs");
87 tf_component->
start();
ORO_CREATE_COMPONENT(BroadcasterComponent)
bool setActivity(const std::string &comp_name, double period, int priority, int scheduler)
Seconds secondsSince(ticks relativeTime) const
bool import(const std::string &package)
geometry_msgs::TransformStamped tform_
friend friend class TaskContext
bool connectPeers(const std::string &one, const std::string &other)
static TimeService * Instance()
RTT::OperationCaller< void(const geometry_msgs::TransformStamped &)> broadcaster_
RTT::TaskContext * myGetPeer(std::string name)
ServiceRequester::shared_ptr requires()
BroadcasterComponent(const std::string &name)
virtual ~BroadcasterComponent()
int ORO_main(int argc, char **argv)
bool loadComponent(const std::string &name, const std::string &type)
virtual bool connectServices(TaskContext *peer)