00001 #include <sensor_msgs/NavSatStatus.h> 00002 #include <sensor_msgs/JointState.h> 00003 #include <sensor_msgs/CameraInfo.h> 00004 #include <sensor_msgs/PointCloud2.h> 00005 #include <sensor_msgs/Imu.h> 00006 #include <sensor_msgs/NavSatFix.h> 00007 #include <sensor_msgs/LaserScan.h> 00008 #include <sensor_msgs/PointCloud.h> 00009 #include <sensor_msgs/Range.h> 00010 #include <sensor_msgs/PointField.h> 00011 #include <sensor_msgs/Image.h> 00012 #include <sensor_msgs/RegionOfInterest.h> 00013 #include <sensor_msgs/CompressedImage.h> 00014 #include <sensor_msgs/ChannelFloat32.h> 00015 00016 #include <rtt/types/TypekitPlugin.hpp> 00017 #include <rtt/types/StructTypeInfo.hpp> 00018 00019 namespace ros_integration { 00020 using namespace RTT; 00021 00023 void rtt_ros_addType_NavSatStatus(); 00024 void rtt_ros_addType_JointState(); 00025 void rtt_ros_addType_CameraInfo(); 00026 void rtt_ros_addType_PointCloud2(); 00027 void rtt_ros_addType_Imu(); 00028 void rtt_ros_addType_NavSatFix(); 00029 void rtt_ros_addType_LaserScan(); 00030 void rtt_ros_addType_PointCloud(); 00031 void rtt_ros_addType_Range(); 00032 void rtt_ros_addType_PointField(); 00033 void rtt_ros_addType_Image(); 00034 void rtt_ros_addType_RegionOfInterest(); 00035 void rtt_ros_addType_CompressedImage(); 00036 void rtt_ros_addType_ChannelFloat32(); 00037 00038 00042 class ROSsensor_msgsTypekitPlugin 00043 : public types::TypekitPlugin 00044 { 00045 public: 00046 virtual std::string getName(){ 00047 return std::string("ros-")+"sensor_msgs"; 00048 } 00049 00050 virtual bool loadTypes() { 00051 // call all factory functions 00052 rtt_ros_addType_NavSatStatus(); // factory function for adding TypeInfo. 00053 rtt_ros_addType_JointState(); // factory function for adding TypeInfo. 00054 rtt_ros_addType_CameraInfo(); // factory function for adding TypeInfo. 00055 rtt_ros_addType_PointCloud2(); // factory function for adding TypeInfo. 00056 rtt_ros_addType_Imu(); // factory function for adding TypeInfo. 00057 rtt_ros_addType_NavSatFix(); // factory function for adding TypeInfo. 00058 rtt_ros_addType_LaserScan(); // factory function for adding TypeInfo. 00059 rtt_ros_addType_PointCloud(); // factory function for adding TypeInfo. 00060 rtt_ros_addType_Range(); // factory function for adding TypeInfo. 00061 rtt_ros_addType_PointField(); // factory function for adding TypeInfo. 00062 rtt_ros_addType_Image(); // factory function for adding TypeInfo. 00063 rtt_ros_addType_RegionOfInterest(); // factory function for adding TypeInfo. 00064 rtt_ros_addType_CompressedImage(); // factory function for adding TypeInfo. 00065 rtt_ros_addType_ChannelFloat32(); // factory function for adding TypeInfo. 00066 00067 return true; 00068 } 00069 virtual bool loadOperators() { return true; } 00070 virtual bool loadConstructors() { return true; } 00071 }; 00072 } 00073 00074 ORO_TYPEKIT_PLUGIN( ros_integration::ROSsensor_msgsTypekitPlugin ) 00075