component.cpp
Go to the documentation of this file.
00001 #include <rtt/RTT.hpp>
00002 #include <rtt/Component.hpp>
00003 
00004 #include <rtt_rosbuild_tests/typekit/String.h>
00005 #include <geometry_msgs/typekit/Pose.h>
00006 
00007 namespace rtt_rosbuild_tests {
00008 
00009 class Component : public RTT::TaskContext
00010 {
00011 public:
00012     Component(const std::string& name)
00013         : RTT::TaskContext(name)
00014     {
00015         this->addPort("string", port_string);
00016         this->addPort("pose", port_pose);
00017     }
00018 
00019     void updateHook()
00020     {
00021         rtt_rosbuild_tests::String string;
00022         string.data = "Hello from " ROS_PACKAGE_NAME "!";
00023         port_string.write(string);
00024     }
00025 
00026 private:
00027     RTT::OutputPort<rtt_rosbuild_tests::String> port_string;
00028     RTT::InputPort<geometry_msgs::Pose> port_pose;
00029 };
00030 
00031 } // namespace rtt_rosbuild_tests
00032 
00033 ORO_CREATE_COMPONENT(rtt_rosbuild_tests::Component)


rtt_rosbuild_tests
Author(s): Johannes Meyer
autogenerated on Tue Jan 19 2016 13:30:39