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...
#include <shape_shifter.h>
Public Member Functions | |
ShapeShifter & | operator= (::topic_tools::ShapeShifter &&other) noexcept |
ShapeShifter & | operator= (const ::topic_tools::ShapeShifter &other) |
ShapeShifter & | operator= (const ShapeShifter &other) |
ShapeShifter & | operator= (ShapeShifter &&other) noexcept |
ShapeShifter () | |
ShapeShifter (::topic_tools::ShapeShifter &&other) noexcept | |
ShapeShifter (const ::topic_tools::ShapeShifter &other) | |
ShapeShifter (const ShapeShifter &other) | |
ShapeShifter (ShapeShifter &&other) noexcept | |
~ShapeShifter () override | |
Public Member Functions inherited from topic_tools::ShapeShifter | |
ros::Publisher | advertise (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size_, bool latch=false, const ros::SubscriberStatusCallback &connect_cb=ros::SubscriberStatusCallback()) const |
std::string const & | getDataType () const |
std::string const & | getMD5Sum () const |
std::string const & | getMessageDefinition () const |
boost::shared_ptr< M > | instantiate () const |
void | morph (const std::string &md5sum, const std::string &datatype, const std::string &msg_def, const std::string &latching) |
void | read (Stream &stream) |
ShapeShifter () | |
uint32_t | size () const |
void | write (Stream &stream) const |
Additional Inherited Members | |
Public Types inherited from topic_tools::ShapeShifter | |
typedef boost::shared_ptr< ShapeShifter const > | ConstPtr |
typedef boost::shared_ptr< ShapeShifter > | Ptr |
Static Public Attributes inherited from topic_tools::ShapeShifter | |
static bool | uses_old_API_ |
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
;
Definition at line 116 of file shape_shifter.h.
|
default |
|
overridevirtualdefault |
Reimplemented from topic_tools::ShapeShifter.
|
explicit |
|
explicitnoexcept |
cras::ShapeShifter::ShapeShifter | ( | const ShapeShifter & | other | ) |
Definition at line 226 of file shape_shifter.cpp.
|
noexcept |
Definition at line 241 of file shape_shifter.cpp.
|
noexcept |
ShapeShifter& cras::ShapeShifter::operator= | ( | const ::topic_tools::ShapeShifter & | other | ) |
ShapeShifter & cras::ShapeShifter::operator= | ( | const ShapeShifter & | other | ) |
Definition at line 257 of file shape_shifter.cpp.
|
noexcept |
Definition at line 287 of file shape_shifter.cpp.