Tools for more convenient working with ShapeShifter objects. More...
#include <type_traits>
#include <ros/message_traits.h>
#include <std_msgs/Header.h>
#include <topic_tools/shape_shifter.h>
#include <cras_cpp_common/optional.hpp>
#include "impl/shape_shifter.hpp"
Go to the source code of this file.
Classes | |
class | cras::ShapeShifter |
ShapeShifter class with fixed behavior on copy/move on Melodic. Use this class everywhere possible to prevent memory corruption. It seamlessly converts to topic_tools::ShapeShifter ; More... | |
Namespaces | |
cras | |
Functions | |
void | cras::copyShapeShifter (const ::topic_tools::ShapeShifter &in, ::topic_tools::ShapeShifter &out) |
Copy in ShapeShifter to out . More... | |
uint8_t * | cras::getBuffer (::topic_tools::ShapeShifter &msg) |
Get the internal buffer with serialized message data. More... | |
const uint8_t * | cras::getBuffer (const ::topic_tools::ShapeShifter &msg) |
Get the internal buffer with serialized message data. More... | |
size_t | cras::getBufferLength (const ::topic_tools::ShapeShifter &msg) |
Get the length of the internal buffer with serialized message data. More... | |
::cras::optional<::std_msgs::Header > | cras::getHeader (const ::topic_tools::ShapeShifter &msg) |
Get the header field of the given message, if it has any. More... | |
bool | cras::hasHeader (const ::topic_tools::ShapeShifter &msg) |
Tell whether the given message has header field. More... | |
template<typename T , typename EnableT > | |
void | cras::msgToShapeShifter (const T &msg, ::topic_tools::ShapeShifter &shifter) |
Copy the message instance into the given ShapeShifter. More... | |
void | cras::resizeBuffer (::topic_tools::ShapeShifter &msg, size_t newLength) |
Resize the internal buffer of the message. More... | |
bool | cras::setHeader (::topic_tools::ShapeShifter &msg, ::std_msgs::Header &header) |
Change the header field of the given message, if it has any. More... | |
Tools for more convenient working with ShapeShifter objects.
Definition in file shape_shifter.h.