00001 #include <sensor_msgs/boost/PointCloud2.h>
00002 #include <rtt/types/TypekitPlugin.hpp>
00003 #include <rtt/types/StructTypeInfo.hpp>
00004 #include <rtt/types/SequenceTypeInfo.hpp>
00005 #include <vector>
00006
00007
00008
00009 template class RTT_EXPORT RTT::internal::DataSourceTypeInfo< sensor_msgs::PointCloud2 >;
00010 template class RTT_EXPORT RTT::internal::DataSource< sensor_msgs::PointCloud2 >;
00011 template class RTT_EXPORT RTT::internal::AssignableDataSource< sensor_msgs::PointCloud2 >;
00012 template class RTT_EXPORT RTT::internal::AssignCommand< sensor_msgs::PointCloud2 >;
00013 template class RTT_EXPORT RTT::internal::ValueDataSource< sensor_msgs::PointCloud2 >;
00014 template class RTT_EXPORT RTT::internal::ConstantDataSource< sensor_msgs::PointCloud2 >;
00015 template class RTT_EXPORT RTT::internal::ReferenceDataSource< sensor_msgs::PointCloud2 >;
00016 template class RTT_EXPORT RTT::OutputPort< sensor_msgs::PointCloud2 >;
00017 template class RTT_EXPORT RTT::InputPort< sensor_msgs::PointCloud2 >;
00018 template class RTT_EXPORT RTT::Property< sensor_msgs::PointCloud2 >;
00019 template class RTT_EXPORT RTT::Attribute< sensor_msgs::PointCloud2 >;
00020 template class RTT_EXPORT RTT::Constant< sensor_msgs::PointCloud2 >;
00021
00022 namespace ros_integration {
00023 using namespace RTT;
00024
00025 void rtt_ros_addType_PointCloud2() { RTT::types::Types()->addType( new types::StructTypeInfo<sensor_msgs::PointCloud2>("/sensor_msgs/PointCloud2") ); RTT::types::Types()->addType( new types::SequenceTypeInfo<std::vector<sensor_msgs::PointCloud2> >("/sensor_msgs/PointCloud2[]") ); }
00026
00027
00028 }
00029