17 #include <std_msgs/Duration.h> 18 #include <std_msgs/Time.h> 25 #include <rtt/types/TransportPlugin.hpp> 31 STD_MSGS_DEFINE_BUILTIN_TRAITS(::
ros::Time, Time, 0xcd7166c74c552c31ULL, 0x1fbcc2fe5a7bc289ULL)
36 template <
class ContainerAllocator>
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; }
82 return "ros-primitives";
85 return "rtt-ros-primitives-transport";
#define ORO_TYPEKIT_PLUGIN(TYPEKIT)
#define ORO_ROS_PROTOCOL_ID
bool registerTransport(std::string name, types::TypeInfo *ti)
std_msgs::VectorMultiArrayAdapter< double, ContainerAllocator > RosType
std::vector< double, ContainerAllocator > OrocosType
std::string getTransportName() const
#define STD_MSGS_DEFINE_BUILTIN_TRAITS(builtin, msg, static_md5sum1, static_md5sum2)
bool addProtocol(int protocol_id, TypeTransporter *tt)
static const OrocosType & fromRos(const RosType &t)
std::string getName() const
std::string getTypekitName() const
static RosType toRos(const OrocosType &t)