ros_primitives_transport_plugin.cpp
Go to the documentation of this file.
00001 // required for ROS_STATIC_ASSERT(), not included in <std_msgs/builtin_string.h>
00002 #include <ros/assert.h>
00003 
00004 #include <std_msgs/builtin_bool.h>
00005 #include <std_msgs/builtin_double.h>
00006 #include <std_msgs/builtin_float.h>
00007 #include <std_msgs/builtin_int8.h>
00008 #include <std_msgs/builtin_int16.h>
00009 #include <std_msgs/builtin_int32.h>
00010 #include <std_msgs/builtin_int64.h>
00011 #include <std_msgs/builtin_string.h>
00012 #include <std_msgs/builtin_uint8.h>
00013 #include <std_msgs/builtin_uint16.h>
00014 #include <std_msgs/builtin_uint32.h>
00015 #include <std_msgs/builtin_uint64.h>
00016 
00017 #include <std_msgs/Duration.h>
00018 #include <std_msgs/Time.h>
00019 #include <ros/time.h>
00020 
00021 #include <std_msgs/vector_multi_array_adapter.h>
00022 
00023 #include <rtt_roscomm/rtt_rostopic_ros_msg_transporter.hpp>
00024 #include <rtt_roscomm/rtt_rostopic.h>
00025 #include <rtt/types/TransportPlugin.hpp>
00026 #include <rtt/types/TypekitPlugin.hpp>
00027 #include <rtt/rt_string.hpp>
00028 
00029 // There are no message_traits for ros::Time and ros::Duration, so we define it here.
00030 STD_MSGS_DEFINE_BUILTIN_TRAITS(::ros::Duration, Duration, 0x3e286caf4241d664ULL, 0xe55f3ad380e2ae46ULL)
00031 STD_MSGS_DEFINE_BUILTIN_TRAITS(::ros::Time, Time, 0xcd7166c74c552c31ULL, 0x1fbcc2fe5a7bc289ULL)
00032 
00033 // Adapt std::vector<double> to std_msgs/Float64MultiArray
00034 namespace rtt_roscomm {
00035 
00036   template <class ContainerAllocator>
00037   struct RosMessageAdapter<std::vector<double, ContainerAllocator> >
00038   {
00039     typedef std::vector<double, ContainerAllocator> OrocosType;
00040     typedef std_msgs::VectorMultiArrayAdapter<double, ContainerAllocator> RosType;
00041     static RosType toRos(const OrocosType &t) { return RosType(t); }
00042     static const OrocosType &fromRos(const RosType &t) { return *t; }
00043   };
00044 
00045 } // namespace rtt_roscomm
00046 
00047 
00048 namespace rtt_std_msgs {
00049   using namespace RTT;
00050   using rtt_roscomm::RosMsgTransporter;
00051 
00052   struct ROSPrimitivesPlugin
00053     : public types::TransportPlugin
00054   {
00055     bool registerTransport(std::string name, types::TypeInfo* ti)
00056     {
00057       if (name == "array") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<std::vector<double> >());} else
00058       if (name == "bool") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<bool>());} else
00059       if (name == "duration") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<ros::Duration>());} else
00060       if (name == "float32") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<float>());} else
00061       if (name == "float64") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<double>());} else
00062       if (name == "int8") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<int8_t>());} else
00063       if (name == "int16") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<int16_t>());} else
00064       if (name == "int32") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<int32_t>());} else
00065       if (name == "int64") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<int64_t>());} else
00066       if (name == "string") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<std::string>());} else
00067       if (name == "rt_string") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<RTT::rt_string>());} else
00068       if (name == "time") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<ros::Time>());} else
00069       if (name == "uint8") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<uint8_t>());} else
00070       if (name == "uint16") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<uint16_t>());} else
00071       if (name == "uint32") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<uint32_t>());} else
00072       if (name == "uint64") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<uint64_t>());} else
00073       { }
00074       return false;
00075     }
00076 
00077     std::string getTransportName() const {
00078         return "ros";
00079     }
00080 
00081     std::string getTypekitName() const {
00082         return "ros-primitives";
00083     }
00084     std::string getName() const {
00085         return "rtt-ros-primitives-transport";
00086     }
00087 
00088   };
00089 }
00090 
00091 ORO_TYPEKIT_PLUGIN( rtt_std_msgs::ROSPrimitivesPlugin )


rtt_std_msgs
Author(s):
autogenerated on Thu Jun 6 2019 18:06:17