Go to the documentation of this file.
   13 #include <type_traits> 
   16 #include <std_msgs/Header.h> 
   17 #include <topic_tools/shape_shifter.h> 
   38 const uint8_t* 
getBuffer(const ::topic_tools::ShapeShifter& msg);
 
   54 bool hasHeader(const ::topic_tools::ShapeShifter& msg);
 
   65 ::cras::optional<::std_msgs::Header> 
getHeader(const ::topic_tools::ShapeShifter& msg);
 
  106 template<
typename T, 
typename EnableT = ::std::enable_if_t<::ros::message_traits::IsMessage<::std::decay_t<T>>::value>>
 
  109 #if ROS_VERSION_MINIMUM(1, 15, 0) 
  110 using ::topic_tools::ShapeShifter;
 
  122   explicit ShapeShifter(const ::topic_tools::ShapeShifter& other);
 
  135 #if !ROS_VERSION_MINIMUM(1, 15, 0) 
  137 namespace message_traits {
 
  146   static const char* 
value() { 
return "*"; }
 
  153   static const char* 
value() { 
return "*"; }
 
  164 namespace serialization
 
  170   template<
typename Stream>
 
  175   template<
typename Stream>
 
  
static void notify(const PreDeserializeParams< cras::ShapeShifter > ¶ms)
static const char * value(const cras::ShapeShifter &m)
bool hasHeader(const ::topic_tools::ShapeShifter &msg)
Tell whether the given message has header field.
ShapeShifter class with fixed behavior on copy/move on Melodic. Use this class everywhere possible to...
static const char * value(const cras::ShapeShifter &m)
boost::shared_ptr< M > message
size_t getBufferLength(const ::topic_tools::ShapeShifter &msg)
Get the length of the internal buffer with serialized message data.
Tools for more convenient working with ShapeShifter objects (implementation details,...
static const char * value()
static const char * value()
void copyShapeShifter(const ::topic_tools::ShapeShifter &in, ::topic_tools::ShapeShifter &out)
Copy in ShapeShifter to out.
static void read(Stream &stream, cras::ShapeShifter &m)
boost::shared_ptr< std::map< std::string, std::string > > connection_header
void msgToShapeShifter(const T &msg, ::topic_tools::ShapeShifter &shifter)
Copy the message instance into the given ShapeShifter.
static uint32_t serializedLength(const cras::ShapeShifter &m)
uint8_t * getBuffer(::topic_tools::ShapeShifter &msg)
Get the internal buffer with serialized message data.
::cras::optional<::std_msgs::Header > getHeader(const ::topic_tools::ShapeShifter &msg)
Get the header field of the given message, if it has any.
static const char * value(const cras::ShapeShifter &m)
static void write(Stream &stream, const cras::ShapeShifter &m)
void resizeBuffer(::topic_tools::ShapeShifter &msg, size_t newLength)
Resize the internal buffer of the message.
ShapeShifter & operator=(const ::topic_tools::ShapeShifter &other)
bool setHeader(::topic_tools::ShapeShifter &msg, ::std_msgs::Header &header)
Change the header field of the given message, if it has any.
cras_topic_tools
Author(s): Martin Pecka 
autogenerated on Wed Apr 23 2025 02:48:56