12 #include <type_traits>    15 #include <std_msgs/Header.h>    16 #include <topic_tools/shape_shifter.h>    37 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);
   107 template<
typename T, 
typename EnableT = ::std::enable_if_t<::ros::message_traits::IsMessage<::std::decay_t<T>>::value>>
   110 #if ROS_VERSION_MINIMUM(1, 15, 0)   111 using ::topic_tools::ShapeShifter;
   123   explicit ShapeShifter(const ::topic_tools::ShapeShifter& other);
 void copyShapeShifter(const ::topic_tools::ShapeShifter &in, ::topic_tools::ShapeShifter &out)
Copy in ShapeShifter to out. 
uint8_t * getBuffer(::topic_tools::ShapeShifter &msg)
Get the internal buffer with serialized message data. 
ShapeShifter & operator=(const ::topic_tools::ShapeShifter &other)
::cras::optional<::std_msgs::Header > getHeader(const ::topic_tools::ShapeShifter &msg)
Get the header field of the given message, if it has any. 
void msgToShapeShifter(const T &msg, ::topic_tools::ShapeShifter &shifter)
Copy the message instance into the given ShapeShifter. 
Tools for more convenient working with ShapeShifter objects (implementation details, do not include directly). 
bool setHeader(::topic_tools::ShapeShifter &msg, ::std_msgs::Header &header)
Change the header field of the given message, if it has any. 
size_t getBufferLength(const ::topic_tools::ShapeShifter &msg)
Get the length of the internal buffer with serialized message data. 
void resizeBuffer(::topic_tools::ShapeShifter &msg, size_t newLength)
Resize the internal buffer of the message. 
ShapeShifter class with fixed behavior on copy/move on Melodic. Use this class everywhere possible to...
bool hasHeader(const ::topic_tools::ShapeShifter &msg)
Tell whether the given message has header field.