00001 00002 #include <sensor_msgs/NavSatStatus.h> 00003 #include <sensor_msgs/JointState.h> 00004 #include <sensor_msgs/CameraInfo.h> 00005 #include <sensor_msgs/PointCloud2.h> 00006 #include <sensor_msgs/Imu.h> 00007 #include <sensor_msgs/NavSatFix.h> 00008 #include <sensor_msgs/LaserScan.h> 00009 #include <sensor_msgs/PointCloud.h> 00010 #include <sensor_msgs/Range.h> 00011 #include <sensor_msgs/PointField.h> 00012 #include <sensor_msgs/Image.h> 00013 #include <sensor_msgs/RegionOfInterest.h> 00014 #include <sensor_msgs/CompressedImage.h> 00015 #include <sensor_msgs/ChannelFloat32.h> 00016 00017 #include "ros_msg_transporter.hpp" 00018 #include "RosLib.hpp" 00019 #include <rtt/types/TransportPlugin.hpp> 00020 #include <rtt/types/TypekitPlugin.hpp> 00021 00022 namespace ros_integration { 00023 using namespace RTT; 00024 struct ROSsensor_msgsPlugin 00025 : public types::TransportPlugin 00026 { 00027 bool registerTransport(std::string name, types::TypeInfo* ti) 00028 { 00029 if(name == "/sensor_msgs/NavSatStatus") 00030 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::NavSatStatus>()); 00031 if(name == "/sensor_msgs/JointState") 00032 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::JointState>()); 00033 if(name == "/sensor_msgs/CameraInfo") 00034 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::CameraInfo>()); 00035 if(name == "/sensor_msgs/PointCloud2") 00036 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::PointCloud2>()); 00037 if(name == "/sensor_msgs/Imu") 00038 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::Imu>()); 00039 if(name == "/sensor_msgs/NavSatFix") 00040 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::NavSatFix>()); 00041 if(name == "/sensor_msgs/LaserScan") 00042 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::LaserScan>()); 00043 if(name == "/sensor_msgs/PointCloud") 00044 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::PointCloud>()); 00045 if(name == "/sensor_msgs/Range") 00046 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::Range>()); 00047 if(name == "/sensor_msgs/PointField") 00048 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::PointField>()); 00049 if(name == "/sensor_msgs/Image") 00050 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::Image>()); 00051 if(name == "/sensor_msgs/RegionOfInterest") 00052 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::RegionOfInterest>()); 00053 if(name == "/sensor_msgs/CompressedImage") 00054 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::CompressedImage>()); 00055 if(name == "/sensor_msgs/ChannelFloat32") 00056 return ti->addProtocol(ORO_ROS_PROTOCOL_ID,new RosMsgTransporter<sensor_msgs::ChannelFloat32>()); 00057 00058 return false; 00059 } 00060 00061 std::string getTransportName() const { 00062 return "ros"; 00063 } 00064 00065 std::string getTypekitName() const { 00066 return std::string("ros-")+"sensor_msgs"; 00067 } 00068 std::string getName() const { 00069 return std::string("rtt-ros-") + "sensor_msgs" + "-transport"; 00070 } 00071 00072 }; 00073 } 00074 00075 ORO_TYPEKIT_PLUGIN( ros_integration::ROSsensor_msgsPlugin )