Go to the documentation of this file.
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);
53 bool hasHeader(const ::topic_tools::ShapeShifter& msg);
64 ::cras::optional<::std_msgs::Header>
getHeader(const ::topic_tools::ShapeShifter& msg);
105 template<
typename T,
typename EnableT = ::std::enable_if_t<::ros::message_traits::IsMessage<::std::decay_t<T>>::value>>
108 #if ROS_VERSION_MINIMUM(1, 15, 0)
109 using ::topic_tools::ShapeShifter;
121 explicit ShapeShifter(const ::topic_tools::ShapeShifter& other);
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...
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,...
void copyShapeShifter(const ::topic_tools::ShapeShifter &in, ::topic_tools::ShapeShifter &out)
Copy in ShapeShifter to out.
void msgToShapeShifter(const T &msg, ::topic_tools::ShapeShifter &shifter)
Copy the message instance into the given ShapeShifter.
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.
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 Tue Nov 26 2024 03:49:18