shape_shifter.h
Go to the documentation of this file.
1 #pragma once
2 
3 // SPDX-License-Identifier: BSD-3-Clause
4 // SPDX-FileCopyrightText: Czech Technical University in Prague
5 
12 #include <type_traits>
13 
14 #include <ros/message_traits.h>
15 #include <std_msgs/Header.h>
16 #include <topic_tools/shape_shifter.h>
17 
19 
20 namespace cras
21 {
22 
29 uint8_t* getBuffer(::topic_tools::ShapeShifter& msg);
30 
37 const uint8_t* getBuffer(const ::topic_tools::ShapeShifter& msg);
38 
45 size_t getBufferLength(const ::topic_tools::ShapeShifter& msg);
46 
53 bool hasHeader(const ::topic_tools::ShapeShifter& msg);
54 
64 ::cras::optional<::std_msgs::Header> getHeader(const ::topic_tools::ShapeShifter& msg);
65 
77 bool setHeader(::topic_tools::ShapeShifter& msg, ::std_msgs::Header& header);
78 
88 void resizeBuffer(::topic_tools::ShapeShifter& msg, size_t newLength);
89 
96 void copyShapeShifter(const ::topic_tools::ShapeShifter& in, ::topic_tools::ShapeShifter& out);
97 
105 template<typename T, typename EnableT = ::std::enable_if_t<::ros::message_traits::IsMessage<::std::decay_t<T>>::value>>
106 void msgToShapeShifter(const T& msg, ::topic_tools::ShapeShifter& shifter);
107 
108 #if ROS_VERSION_MINIMUM(1, 15, 0)
109 using ::topic_tools::ShapeShifter;
110 #else
111 
117 {
118 public:
119  ShapeShifter();
120  ~ShapeShifter() override;
121  explicit ShapeShifter(const ::topic_tools::ShapeShifter& other);
122  explicit ShapeShifter(::topic_tools::ShapeShifter && other) noexcept;
123  ShapeShifter& operator=(const ::topic_tools::ShapeShifter& other);
124  ShapeShifter& operator=(::topic_tools::ShapeShifter && other) noexcept;
125  ShapeShifter(const ShapeShifter& other);
126  ShapeShifter(ShapeShifter&& other) noexcept;
127  ShapeShifter& operator=(const ShapeShifter& other);
128  ShapeShifter& operator=(ShapeShifter&& other) noexcept;
129 };
130 #endif
131 
132 }
133 
134 #include "impl/shape_shifter.hpp"
optional.hpp
cras
cras::hasHeader
bool hasHeader(const ::topic_tools::ShapeShifter &msg)
Tell whether the given message has header field.
cras::ShapeShifter
ShapeShifter class with fixed behavior on copy/move on Melodic. Use this class everywhere possible to...
Definition: shape_shifter.h:116
message_traits.h
cras::getBufferLength
size_t getBufferLength(const ::topic_tools::ShapeShifter &msg)
Get the length of the internal buffer with serialized message data.
shape_shifter.hpp
Tools for more convenient working with ShapeShifter objects (implementation details,...
cras::copyShapeShifter
void copyShapeShifter(const ::topic_tools::ShapeShifter &in, ::topic_tools::ShapeShifter &out)
Copy in ShapeShifter to out.
cras::msgToShapeShifter
void msgToShapeShifter(const T &msg, ::topic_tools::ShapeShifter &shifter)
Copy the message instance into the given ShapeShifter.
Definition: shape_shifter.hpp:22
cras::getBuffer
uint8_t * getBuffer(::topic_tools::ShapeShifter &msg)
Get the internal buffer with serialized message data.
topic_tools::ShapeShifter
cras::ShapeShifter::ShapeShifter
ShapeShifter()
cras::getHeader
::cras::optional<::std_msgs::Header > getHeader(const ::topic_tools::ShapeShifter &msg)
Get the header field of the given message, if it has any.
cras::resizeBuffer
void resizeBuffer(::topic_tools::ShapeShifter &msg, size_t newLength)
Resize the internal buffer of the message.
cras::ShapeShifter::operator=
ShapeShifter & operator=(const ::topic_tools::ShapeShifter &other)
cras::ShapeShifter::~ShapeShifter
~ShapeShifter() override
cras::setHeader
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 Sun Jan 14 2024 03:48:28