broadcaster_test.cpp
Go to the documentation of this file.
1 
2 #include <ros/ros.h>
3 #include <ros/time.h>
4 #include <rtt/os/main.h>
5 #include <rtt/RTT.hpp>
6 #include <ocl/DeploymentComponent.hpp>
7 #include <ocl/TaskBrowser.hpp>
8 #include "../rtt_tf-component.hpp"
9 #include <geometry_msgs/TransformStamped.h>
10 
12 public:
14  <void(const geometry_msgs::TransformStamped &)> broadcaster_;
15  geometry_msgs::TransformStamped tform_;
16 
17  BroadcasterComponent(const std::string &name) :
19  ,broadcaster_("broadcastTransform")
20  {
21  this->requires("tf")->addOperationCaller(broadcaster_);
22  }
23  virtual ~BroadcasterComponent() { }
24  bool configureHook() {
25  return true;
26  }
27  bool startHook() {
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;
35 
36  return true;
37  }
38  void updateHook() {
40  tform_.header.frame_id = "/world";
41  tform_.header.stamp = ros::Time(((double)RTT::os::TimeService::Instance()->getNSecs())*1E-9);
42  tform_.child_frame_id = "/rtt_tf_test";
43  tform_.transform.translation.x = cos(t);
44  tform_.transform.translation.y = sin(t);
45  broadcaster_(tform_);
46  tform_.header.frame_id = "/world";
47  tform_.header.stamp = ros::Time(((double)RTT::os::TimeService::Instance()->getNSecs())*1E-9);
48  tform_.child_frame_id = "rel_rtt_tf_test";
49  tform_.transform.translation.x = cos(t);
50  tform_.transform.translation.y = sin(t);
51  broadcaster_(tform_);
52  }
53  void stopHook() { }
54 };
55 
57 
58 int ORO_main(int argc, char** argv) {
59 
60  BroadcasterComponent bcaster("bcaster");
61 
62  {
63  // Create deployer
64  OCL::DeploymentComponent deployer;
65 
66  // initialize ROS and load typekits
67  deployer.import("rtt_rosnode");
68  deployer.import("rtt_std_msgs");
69  deployer.import("rtt_geometry_msgs");
70  deployer.import("rtt_tf2_msgs");
71 
72  // import and load our component
73  deployer.import("rtt_tf");
74  deployer.loadComponent("tf","rtt_tf::RTT_TF");
75 
76  RTT::TaskContext *tf_component = deployer.myGetPeer("tf");
77 
78  // Connect components and deployer
79  deployer.connectPeers(&bcaster);
80  deployer.setActivity("bcaster",0.02,0,ORO_SCHED_OTHER);
81 
82  // Connect services between the tf component and the broadcaster
83  bcaster.connectServices(tf_component);
84 
85  // Configure and start the components
86  tf_component->configure();
87  tf_component->start();
88 
89  bcaster.configure();
90  bcaster.start();
91 
92  // Create orocos taskbrowser for easy interaction
93  OCL::TaskBrowser task_browser(&deployer);
94  task_browser.loop();
95  }
96 
97 
98  bcaster.stop();
99 
100  return 0;
101 }
102 
ORO_CREATE_COMPONENT(BroadcasterComponent)
bool setActivity(const std::string &comp_name, double period, int priority, int scheduler)
virtual bool stop()
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()
virtual bool configure()
RTT::OperationCaller< void(const geometry_msgs::TransformStamped &)> broadcaster_
RTT::TaskContext * myGetPeer(std::string name)
ServiceRequester::shared_ptr requires()
BroadcasterComponent(const std::string &name)
int ORO_main(int argc, char **argv)
bool loadComponent(const std::string &name, const std::string &type)
virtual bool connectServices(TaskContext *peer)
#define ORO_SCHED_OTHER
virtual bool start()


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