Classes | Namespaces | Macros | Typedefs | Enumerations | Functions
serialization.h File Reference
#include "roscpp_serialization_macros.h"
#include <ros/types.h>
#include <ros/time.h>
#include "serialized_message.h"
#include "ros/message_traits.h"
#include "ros/builtin_message_traits.h"
#include "ros/exception.h"
#include "ros/datatypes.h"
#include <vector>
#include <map>
#include <boost/array.hpp>
#include <boost/call_traits.hpp>
#include <boost/utility/enable_if.hpp>
#include <boost/mpl/and.hpp>
#include <boost/mpl/or.hpp>
#include <boost/mpl/not.hpp>
#include <cstring>
Include dependency graph for serialization.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  ros::serialization::ArraySerializer< T, N, Enabled >
 Array serializer, default implementation does nothing. More...
 
struct  ros::serialization::ArraySerializer< T, N, typename boost::disable_if< mt::IsFixedSize< T > >::type >
 Array serializer, specialized for non-fixed-size, non-simple types. More...
 
struct  ros::serialization::ArraySerializer< T, N, typename boost::enable_if< mpl::and_< mt::IsFixedSize< T >, mpl::not_< mt::IsSimple< T > > > >::type >
 Array serializer, specialized for fixed-size, non-simple types. More...
 
struct  ros::serialization::ArraySerializer< T, N, typename boost::enable_if< mt::IsSimple< T > >::type >
 Array serializer, specialized for fixed-size, simple types. More...
 
struct  ros::serialization::IStream
 Input stream. More...
 
struct  ros::serialization::LStream
 Length stream. More...
 
struct  ros::serialization::OStream
 Output stream. More...
 
struct  ros::serialization::PreDeserialize< M >
 called by the SubscriptionCallbackHelper after a message is instantiated but before that message is deserialized More...
 
struct  ros::serialization::PreDeserializeParams< M >
 
struct  ros::serialization::Serializer< T >
 Templated serialization class. Default implementation provides backwards compatibility with old message types. More...
 
struct  ros::serialization::Serializer< bool >
 Serializer specialized for bool (serialized as uint8) More...
 
struct  ros::serialization::Serializer< ros::Duration >
 Serializer specialized for ros::Duration. More...
 
struct  ros::serialization::Serializer< ros::Time >
 Serializer specialized for ros::Time. More...
 
struct  ros::serialization::Serializer< std::basic_string< char, std::char_traits< char >, ContainerAllocator > >
 Serializer specialized for std::string. More...
 
struct  ros::serialization::Stream
 Stream base-class, provides common functionality for IStream and OStream. More...
 
class  ros::serialization::StreamOverrunException
 
struct  ros::serialization::VectorSerializer< T, ContainerAllocator, Enabled >
 Vector serializer. Default implementation does nothing. More...
 
struct  ros::serialization::VectorSerializer< T, ContainerAllocator, typename boost::disable_if< mt::IsFixedSize< T > >::type >
 Vector serializer, specialized for non-fixed-size, non-simple types. More...
 
struct  ros::serialization::VectorSerializer< T, ContainerAllocator, typename boost::enable_if< mpl::and_< mt::IsFixedSize< T >, mpl::not_< mt::IsSimple< T > > > >::type >
 Vector serializer, specialized for fixed-size non-simple types. More...
 
struct  ros::serialization::VectorSerializer< T, ContainerAllocator, typename boost::enable_if< mt::IsSimple< T > >::type >
 Vector serializer, specialized for fixed-size simple types. More...
 

Namespaces

 ros
 
 ros::serialization
 
 ros::serialization::stream_types
 Enum.
 

Macros

#define ROS_CREATE_SIMPLE_SERIALIZER(Type)
 
#define ROS_DECLARE_ALLINONE_SERIALIZER
 Declare your serializer to use an allInOne member instead of requiring 3 different serialization functions. More...
 
#define ROS_NEW_SERIALIZATION_API   1
 

Typedefs

typedef stream_types::StreamType ros::serialization::StreamType
 

Enumerations

enum  ros::serialization::stream_types::StreamType { ros::serialization::stream_types::Input, ros::serialization::stream_types::Output, ros::serialization::stream_types::Length }
 

Functions

template<typename T , typename Stream >
void ros::serialization::deserialize (Stream &stream, T &t)
 Deserialize an object. Stream here should normally be a ros::serialization::IStream. More...
 
template<typename T , class ContainerAllocator , typename Stream >
void ros::serialization::deserialize (Stream &stream, std::vector< T, ContainerAllocator > &t)
 deserialize version for std::vector More...
 
template<typename T , size_t N, typename Stream >
void ros::serialization::deserialize (Stream &stream, boost::array< T, N > &t)
 deserialize version for boost::array More...
 
template<typename M >
void ros::serialization::deserializeMessage (const SerializedMessage &m, M &message)
 Deserialize a message. If includes_length is true, skips the first 4 bytes. More...
 
template<typename T >
uint32_t ros::serialization::serializationLength (const T &t)
 Determine the serialized length of an object. More...
 
template<typename T , class ContainerAllocator >
uint32_t ros::serialization::serializationLength (const std::vector< T, ContainerAllocator > &t)
 serializationLength version for std::vector More...
 
template<typename T , size_t N>
uint32_t ros::serialization::serializationLength (const boost::array< T, N > &t)
 serializationLength version for boost::array More...
 
template<typename T , typename Stream >
void ros::serialization::serialize (Stream &stream, const T &t)
 Serialize an object. Stream here should normally be a ros::serialization::OStream. More...
 
template<typename T , class ContainerAllocator , typename Stream >
void ros::serialization::serialize (Stream &stream, const std::vector< T, ContainerAllocator > &t)
 serialize version for std::vector More...
 
template<typename T , size_t N, typename Stream >
void ros::serialization::serialize (Stream &stream, const boost::array< T, N > &t)
 serialize version for boost::array More...
 
template<typename M >
SerializedMessage ros::serialization::serializeMessage (const M &message)
 Serialize a message. More...
 
template<typename M >
SerializedMessage ros::serialization::serializeServiceResponse (bool ok, const M &message)
 Serialize a service response. More...
 
ROSCPP_SERIALIZATION_DECL void ros::serialization::throwStreamOverrun ()
 

Macro Definition Documentation

◆ ROS_CREATE_SIMPLE_SERIALIZER

#define ROS_CREATE_SIMPLE_SERIALIZER (   Type)
Value:
template<> struct Serializer<Type> \
{ \
template<typename Stream> inline static void write(Stream& stream, const Type v) \
{ \
memcpy(stream.advance(sizeof(v)), &v, sizeof(v) ); \
} \
\
template<typename Stream> inline static void read(Stream& stream, Type& v) \
{ \
memcpy(&v, stream.advance(sizeof(v)), sizeof(v) ); \
} \
\
inline static uint32_t serializedLength(const Type&) \
{ \
return sizeof(Type); \
} \
};

Definition at line 175 of file serialization.h.

◆ ROS_DECLARE_ALLINONE_SERIALIZER

#define ROS_DECLARE_ALLINONE_SERIALIZER
Value:
template<typename Stream, typename T> \
inline static void write(Stream& stream, const T& t) \
{ \
allInOne<Stream, const T&>(stream, t); \
} \
\
template<typename Stream, typename T> \
inline static void read(Stream& stream, T& t) \
{ \
allInOne<Stream, T&>(stream, t); \
} \
\
template<typename T> \
inline static uint32_t serializedLength(const T& t) \
{ \
LStream stream; \
allInOne<LStream, const T&>(stream, t); \
return stream.getLength(); \
}

Declare your serializer to use an allInOne member instead of requiring 3 different serialization functions.

The allinone method has the form:

template<typename Stream, typename T>
inline static void allInOne(Stream& stream, T t)
{
  stream.next(t.a);
  stream.next(t.b);
  ...
}

The only guarantee given is that Stream::next(T) is defined.

Definition at line 73 of file serialization.h.

◆ ROS_NEW_SERIALIZATION_API

#define ROS_NEW_SERIALIZATION_API   1

Definition at line 54 of file serialization.h.



roscpp_serialization
Author(s): Josh Faust
autogenerated on Mon Feb 28 2022 23:31:39