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 <string>
13 #include <type_traits>
14 
15 #include <ros/message_traits.h>
16 #include <std_msgs/Header.h>
17 #include <topic_tools/shape_shifter.h>
18 
20 
21 namespace cras
22 {
23 
30 uint8_t* getBuffer(::topic_tools::ShapeShifter& msg);
31 
38 const uint8_t* getBuffer(const ::topic_tools::ShapeShifter& msg);
39 
46 size_t getBufferLength(const ::topic_tools::ShapeShifter& msg);
47 
54 bool hasHeader(const ::topic_tools::ShapeShifter& msg);
55 
65 ::cras::optional<::std_msgs::Header> getHeader(const ::topic_tools::ShapeShifter& msg);
66 
78 bool setHeader(::topic_tools::ShapeShifter& msg, ::std_msgs::Header& header);
79 
89 void resizeBuffer(::topic_tools::ShapeShifter& msg, size_t newLength);
90 
97 void copyShapeShifter(const ::topic_tools::ShapeShifter& in, ::topic_tools::ShapeShifter& out);
98 
106 template<typename T, typename EnableT = ::std::enable_if_t<::ros::message_traits::IsMessage<::std::decay_t<T>>::value>>
107 void msgToShapeShifter(const T& msg, ::topic_tools::ShapeShifter& shifter);
108 
109 #if ROS_VERSION_MINIMUM(1, 15, 0)
110 using ::topic_tools::ShapeShifter;
111 #else
112 
118 {
119 public:
120  ShapeShifter();
121  ~ShapeShifter() override;
122  explicit ShapeShifter(const ::topic_tools::ShapeShifter& other);
123  explicit ShapeShifter(::topic_tools::ShapeShifter && other) noexcept;
124  ShapeShifter& operator=(const ::topic_tools::ShapeShifter& other);
125  ShapeShifter& operator=(::topic_tools::ShapeShifter && other) noexcept;
126  ShapeShifter(const ShapeShifter& other);
127  ShapeShifter(ShapeShifter&& other) noexcept;
128  ShapeShifter& operator=(const ShapeShifter& other);
129  ShapeShifter& operator=(ShapeShifter&& other) noexcept;
130 };
131 #endif
132 
133 }
134 
135 #if !ROS_VERSION_MINIMUM(1, 15, 0)
136 namespace ros {
137 namespace message_traits {
138 
139 template <> struct IsMessage<cras::ShapeShifter> : TrueType { };
140 template <> struct IsMessage<const cras::ShapeShifter> : TrueType { };
141 
142 template<>
143 struct MD5Sum<cras::ShapeShifter>
144 {
145  static const char* value(const cras::ShapeShifter& m) { return m.getMD5Sum().c_str(); }
146  static const char* value() { return "*"; }
147 };
148 
149 template<>
150 struct DataType<cras::ShapeShifter>
151 {
152  static const char* value(const cras::ShapeShifter& m) { return m.getDataType().c_str(); }
153  static const char* value() { return "*"; }
154 };
155 
156 template<>
157 struct Definition<cras::ShapeShifter>
158 {
159  static const char* value(const cras::ShapeShifter& m) { return m.getMessageDefinition().c_str(); }
160 };
161 
162 }
163 
164 namespace serialization
165 {
166 
167 template<>
168 struct Serializer<cras::ShapeShifter>
169 {
170  template<typename Stream>
171  inline static void write(Stream& stream, const cras::ShapeShifter& m) {
172  m.write(stream);
173  }
174 
175  template<typename Stream>
176  inline static void read(Stream& stream, cras::ShapeShifter& m)
177  {
178  m.read(stream);
179  }
180 
181  inline static uint32_t serializedLength(const cras::ShapeShifter& m) {
182  return m.size();
183  }
184 };
185 
186 
187 template<>
188 struct PreDeserialize<cras::ShapeShifter>
189 {
191  {
192  std::string md5 = (*params.connection_header)["md5sum"];
193  std::string datatype = (*params.connection_header)["type"];
194  std::string msg_def = (*params.connection_header)["message_definition"];
195  std::string latching = (*params.connection_header)["latching"];
196 
197  params.message->morph(md5, datatype, msg_def, latching);
198  }
199 };
200 
201 }
202 }
203 #endif
204 
205 #include "impl/shape_shifter.hpp"
optional.hpp
ros::message_traits::TrueType
topic_tools::ShapeShifter::getDataType
std::string const & getDataType() const
ros::serialization::PreDeserializeParams
ros::serialization::PreDeserialize< cras::ShapeShifter >::notify
static void notify(const PreDeserializeParams< cras::ShapeShifter > &params)
Definition: shape_shifter.h:190
ros::message_traits::MD5Sum< cras::ShapeShifter >::value
static const char * value(const cras::ShapeShifter &m)
Definition: shape_shifter.h:145
cras
cras::hasHeader
bool hasHeader(const ::topic_tools::ShapeShifter &msg)
Tell whether the given message has header field.
ros
ros::serialization::Stream
ros::message_traits::DataType
cras::ShapeShifter
ShapeShifter class with fixed behavior on copy/move on Melodic. Use this class everywhere possible to...
Definition: shape_shifter.h:117
ros::message_traits::DataType< cras::ShapeShifter >::value
static const char * value(const cras::ShapeShifter &m)
Definition: shape_shifter.h:152
ros::serialization::PreDeserialize
topic_tools::ShapeShifter::read
void read(Stream &stream)
message_traits.h
topic_tools::ShapeShifter::write
void write(Stream &stream) const
ros::serialization::PreDeserializeParams::message
boost::shared_ptr< M > message
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,...
ros::message_traits::MD5Sum
topic_tools::ShapeShifter::getMD5Sum
std::string const & getMD5Sum() const
ros::message_traits::DataType< cras::ShapeShifter >::value
static const char * value()
Definition: shape_shifter.h:153
ros::message_traits::MD5Sum< cras::ShapeShifter >::value
static const char * value()
Definition: shape_shifter.h:146
cras::copyShapeShifter
void copyShapeShifter(const ::topic_tools::ShapeShifter &in, ::topic_tools::ShapeShifter &out)
Copy in ShapeShifter to out.
ros::serialization::Serializer< cras::ShapeShifter >::read
static void read(Stream &stream, cras::ShapeShifter &m)
Definition: shape_shifter.h:176
ros::serialization::PreDeserializeParams::connection_header
boost::shared_ptr< std::map< std::string, std::string > > connection_header
cras::msgToShapeShifter
void msgToShapeShifter(const T &msg, ::topic_tools::ShapeShifter &shifter)
Copy the message instance into the given ShapeShifter.
Definition: shape_shifter.hpp:22
ros::serialization::Serializer< cras::ShapeShifter >::serializedLength
static uint32_t serializedLength(const cras::ShapeShifter &m)
Definition: shape_shifter.h:181
cras::getBuffer
uint8_t * getBuffer(::topic_tools::ShapeShifter &msg)
Get the internal buffer with serialized message data.
ros::message_traits::IsMessage
topic_tools::ShapeShifter::size
uint32_t size() const
datatype
const char * datatype()
ros::message_traits::Definition
topic_tools::ShapeShifter
cras::ShapeShifter::ShapeShifter
ShapeShifter()
Definition: shape_shifter.cpp:203
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.
ros::message_traits::Definition< cras::ShapeShifter >::value
static const char * value(const cras::ShapeShifter &m)
Definition: shape_shifter.h:159
ros::serialization::Serializer< cras::ShapeShifter >::write
static void write(Stream &stream, const cras::ShapeShifter &m)
Definition: shape_shifter.h:171
ros::serialization::Serializer
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
Definition: shape_shifter.cpp:204
cras::setHeader
bool setHeader(::topic_tools::ShapeShifter &msg, ::std_msgs::Header &header)
Change the header field of the given message, if it has any.
topic_tools::ShapeShifter::getMessageDefinition
std::string const & getMessageDefinition() const


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sun Mar 2 2025 03:51:09