ros_primitives_transport_plugin.cpp
Go to the documentation of this file.
1 // required for ROS_STATIC_ASSERT(), not included in <std_msgs/builtin_string.h>
2 #include <ros/assert.h>
3 
10 #include <std_msgs/builtin_int64.h>
12 #include <std_msgs/builtin_uint8.h>
16 
17 #include <std_msgs/Duration.h>
18 #include <std_msgs/Time.h>
19 #include <ros/time.h>
20 
22 
24 #include <rtt_roscomm/rostopic.h>
25 #include <rtt/types/TransportPlugin.hpp>
27 #include <rtt/rt_string.hpp>
28 
29 // There are no message_traits for ros::Time and ros::Duration, so we define it here.
30 STD_MSGS_DEFINE_BUILTIN_TRAITS(::ros::Duration, Duration, 0x3e286caf4241d664ULL, 0xe55f3ad380e2ae46ULL)
31 STD_MSGS_DEFINE_BUILTIN_TRAITS(::ros::Time, Time, 0xcd7166c74c552c31ULL, 0x1fbcc2fe5a7bc289ULL)
32 
33 // Adapt std::vector<double> to std_msgs/Float64MultiArray
34 namespace rtt_roscomm {
35 
36  template <class ContainerAllocator>
37  struct RosMessageAdapter<std::vector<double, ContainerAllocator> >
38  {
39  typedef std::vector<double, ContainerAllocator> OrocosType;
41  static RosType toRos(const OrocosType &t) { return RosType(t); }
42  static const OrocosType &fromRos(const RosType &t) { return *t; }
43  };
44 
45 } // namespace rtt_roscomm
46 
47 
48 namespace rtt_std_msgs {
49  using namespace RTT;
51 
53  : public types::TransportPlugin
54  {
55  bool registerTransport(std::string name, types::TypeInfo* ti)
56  {
57  if (name == "array") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<std::vector<double> >());} else
58  if (name == "bool") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<bool>());} else
59  if (name == "duration") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<ros::Duration>());} else
60  if (name == "float32") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<float>());} else
61  if (name == "float64") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<double>());} else
62  if (name == "int8") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<int8_t>());} else
63  if (name == "int16") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<int16_t>());} else
64  if (name == "int32") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<int32_t>());} else
65  if (name == "int64") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<int64_t>());} else
66  if (name == "string") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<std::string>());} else
67  if (name == "rt_string") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<RTT::rt_string>());} else
68  if (name == "time") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<ros::Time>());} else
69  if (name == "uint8") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<uint8_t>());} else
70  if (name == "uint16") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<uint16_t>());} else
71  if (name == "uint32") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<uint32_t>());} else
72  if (name == "uint64") { return ti->addProtocol(ORO_ROS_PROTOCOL_ID, new RosMsgTransporter<uint64_t>());} else
73  { }
74  return false;
75  }
76 
77  std::string getTransportName() const {
78  return "ros";
79  }
80 
81  std::string getTypekitName() const {
82  return "ros-primitives";
83  }
84  std::string getName() const {
85  return "rtt-ros-primitives-transport";
86  }
87 
88  };
89 }
90 
#define ORO_TYPEKIT_PLUGIN(TYPEKIT)
#define ORO_ROS_PROTOCOL_ID
bool registerTransport(std::string name, types::TypeInfo *ti)
std_msgs::VectorMultiArrayAdapter< double, ContainerAllocator > RosType
#define STD_MSGS_DEFINE_BUILTIN_TRAITS(builtin, msg, static_md5sum1, static_md5sum2)
bool addProtocol(int protocol_id, TypeTransporter *tt)


rtt_std_msgs
Author(s):
autogenerated on Mon May 10 2021 02:45:14