Classes | Namespaces | Macros | Functions
message_traits.h File Reference
#include "message_forward.h"
#include <ros/time.h>
#include <string>
#include <boost/utility/enable_if.hpp>
#include <boost/type_traits/remove_const.hpp>
#include <boost/type_traits/remove_reference.hpp>
Include dependency graph for message_traits.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  ros::message_traits::DataType< M >
 Specialize to provide the datatype for a message. More...
 
struct  ros::message_traits::Definition< M >
 Specialize to provide the definition for a message. More...
 
struct  ros::message_traits::FalseType
 Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this type are false values. More...
 
struct  ros::message_traits::FrameId< M, Enable >
 FrameId trait. In the default implementation pointer() returns &m.header.frame_id if HasHeader<M>::value is true, otherwise returns NULL. value() does not exist, and causes a compile error. More...
 
struct  ros::message_traits::FrameId< M, typename boost::enable_if< HasHeader< M > >::type >
 
struct  ros::message_traits::HasHeader< M >
 HasHeader informs whether or not there is a header that gets serialized as the first thing in the message. More...
 
struct  ros::message_traits::Header< M, Enable >
 Header trait. In the default implementation pointer() returns &m.header if HasHeader<M>::value is true, otherwise returns NULL. More...
 
struct  ros::message_traits::Header< M, typename boost::enable_if< HasHeader< M > >::type >
 
struct  ros::message_traits::IsFixedSize< M >
 A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings. More...
 
struct  ros::message_traits::IsMessage< M >
 Am I message or not. More...
 
struct  ros::message_traits::IsSimple< M >
 A simple datatype is one that can be memcpy'd directly in array form, i.e. it's a POD, fixed-size type and sizeof(M) == sum(serializationLength(M:a...)) More...
 
struct  ros::message_traits::MD5Sum< M >
 Specialize to provide the md5sum for a message. More...
 
struct  ros::message_traits::TimeStamp< M, Enable >
 TimeStamp trait. In the default implementation pointer() returns &m.header.stamp if HasHeader<M>::value is true, otherwise returns NULL. value() does not exist, and causes a compile error. More...
 
struct  ros::message_traits::TimeStamp< M, typename boost::enable_if< HasHeader< M > >::type >
 
struct  ros::message_traits::TrueType
 Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this type are true values. More...
 

Namespaces

 ros
 
 ros::message_traits
 
 std_msgs
 

Macros

#define ROS_IMPLEMENT_SIMPLE_TOPIC_TRAITS(msg, md5sum, datatype, definition)
 

Functions

template<typename M >
const char * ros::message_traits::datatype ()
 returns DataType<M>::value(); More...
 
template<typename M >
const char * ros::message_traits::datatype (const M &m)
 returns DataType<M>::value(m); More...
 
template<typename M >
const char * ros::message_traits::definition ()
 returns Definition<M>::value(); More...
 
template<typename M >
const char * ros::message_traits::definition (const M &m)
 returns Definition<M>::value(m); More...
 
template<typename M >
std::string * ros::message_traits::frameId (M &m)
 returns FrameId<M>::pointer(m); More...
 
template<typename M >
std::string const * ros::message_traits::frameId (const M &m)
 returns FrameId<M>::pointer(m); More...
 
template<typename M >
bool ros::message_traits::hasHeader ()
 returns HasHeader<M>::value; More...
 
template<typename M >
std_msgs::Header * ros::message_traits::header (M &m)
 returns Header<M>::pointer(m); More...
 
template<typename M >
std_msgs::Header const * ros::message_traits::header (const M &m)
 returns Header<M>::pointer(m); More...
 
template<typename M >
bool ros::message_traits::isFixedSize ()
 returns IsFixedSize<M>::value; More...
 
template<typename M >
bool ros::message_traits::isSimple ()
 returns IsSimple<M>::value; More...
 
template<typename M >
const char * ros::message_traits::md5sum ()
 returns MD5Sum<M>::value(); More...
 
template<typename M >
const char * ros::message_traits::md5sum (const M &m)
 returns MD5Sum<M>::value(m); More...
 
template<typename M >
ros::Timeros::message_traits::timeStamp (M &m)
 returns TimeStamp<M>::pointer(m); More...
 
template<typename M >
ros::Time const * ros::message_traits::timeStamp (const M &m)
 returns TimeStamp<M>::pointer(m); More...
 

Macro Definition Documentation

#define ROS_IMPLEMENT_SIMPLE_TOPIC_TRAITS (   msg,
  md5sum,
  datatype,
  definition 
)
Value:
namespace ros \
{ \
namespace message_traits \
{ \
template<> struct MD5Sum<msg> \
{ \
static const char* value() { return md5sum; } \
static const char* value(const msg&) { return value(); } \
}; \
template<> struct DataType<msg> \
{ \
static const char* value() { return datatype; } \
static const char* value(const msg&) { return value(); } \
}; \
template<> struct Definition<msg> \
{ \
static const char* value() { return definition; } \
static const char* value(const msg&) { return value(); } \
}; \
} \
}
const char * definition(const M &m)
returns Definition<M>::value(m);
const char * datatype(const M &m)
returns DataType<M>::value(m);
const char * md5sum(const M &m)
returns MD5Sum<M>::value(m);

Definition at line 45 of file message_traits.h.



roscpp_traits
Author(s): Josh Faust
autogenerated on Sat Apr 6 2019 02:52:23