YARP
Yet Another Robot Platform
PointField.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6// This is an automatically generated file.
7
8// Generated from the following "sensor_msgs/PointField" msg definition:
9// # This message holds the description of one point entry in the
10// # PointCloud2 message format.
11// uint8 INT8 = 1
12// uint8 UINT8 = 2
13// uint8 INT16 = 3
14// uint8 UINT16 = 4
15// uint8 INT32 = 5
16// uint8 UINT32 = 6
17// uint8 FLOAT32 = 7
18// uint8 FLOAT64 = 8
19//
20// string name # Name of field
21// uint32 offset # Offset from start of point struct
22// uint8 datatype # Datatype enumeration, see above
23// uint32 count # How many elements in the field
24// Instances of this class can be read and written with YARP ports,
25// using a ROS-compatible format.
26
27#ifndef YARP_ROSMSG_sensor_msgs_PointField_h
28#define YARP_ROSMSG_sensor_msgs_PointField_h
29
30#include <yarp/os/Wire.h>
31#include <yarp/os/Type.h>
33#include <string>
34#include <vector>
35
36namespace yarp {
37namespace rosmsg {
38namespace sensor_msgs {
39
41{
42public:
43 static const std::uint8_t INT8 = 1;
44 static const std::uint8_t UINT8 = 2;
45 static const std::uint8_t INT16 = 3;
46 static const std::uint8_t UINT16 = 4;
47 static const std::uint8_t INT32 = 5;
48 static const std::uint8_t UINT32 = 6;
49 static const std::uint8_t FLOAT32 = 7;
50 static const std::uint8_t FLOAT64 = 8;
51 std::string name;
52 std::uint32_t offset;
53 std::uint8_t datatype;
54 std::uint32_t count;
55
57 name(""),
58 offset(0),
59 datatype(0),
60 count(0)
61 {
62 }
63
64 void clear()
65 {
66 // *** INT8 ***
67
68 // *** UINT8 ***
69
70 // *** INT16 ***
71
72 // *** UINT16 ***
73
74 // *** INT32 ***
75
76 // *** UINT32 ***
77
78 // *** FLOAT32 ***
79
80 // *** FLOAT64 ***
81
82 // *** name ***
83 name = "";
84
85 // *** offset ***
86 offset = 0;
87
88 // *** datatype ***
89 datatype = 0;
90
91 // *** count ***
92 count = 0;
93 }
94
95 bool readBare(yarp::os::ConnectionReader& connection) override
96 {
97 // *** name ***
98 int len = connection.expectInt32();
99 name.resize(len);
100 if (!connection.expectBlock((char*)name.c_str(), len)) {
101 return false;
102 }
103
104 // *** offset ***
105 offset = connection.expectInt32();
106
107 // *** datatype ***
108 datatype = connection.expectInt8();
109
110 // *** count ***
111 count = connection.expectInt32();
112
113 return !connection.isError();
114 }
115
116 bool readBottle(yarp::os::ConnectionReader& connection) override
117 {
118 connection.convertTextMode();
119 yarp::os::idl::WireReader reader(connection);
120 if (!reader.readListHeader(12)) {
121 return false;
122 }
123
124 // *** name ***
125 if (!reader.readString(name)) {
126 return false;
127 }
128
129 // *** offset ***
130 offset = reader.expectInt32();
131
132 // *** datatype ***
133 datatype = reader.expectInt8();
134
135 // *** count ***
136 count = reader.expectInt32();
137
138 return !connection.isError();
139 }
140
142 bool read(yarp::os::ConnectionReader& connection) override
143 {
144 return (connection.isBareMode() ? readBare(connection)
145 : readBottle(connection));
146 }
147
148 bool writeBare(yarp::os::ConnectionWriter& connection) const override
149 {
150 // *** name ***
151 connection.appendInt32(name.length());
152 connection.appendExternalBlock((char*)name.c_str(), name.length());
153
154 // *** offset ***
155 connection.appendInt32(offset);
156
157 // *** datatype ***
158 connection.appendInt8(datatype);
159
160 // *** count ***
161 connection.appendInt32(count);
162
163 return !connection.isError();
164 }
165
166 bool writeBottle(yarp::os::ConnectionWriter& connection) const override
167 {
168 connection.appendInt32(BOTTLE_TAG_LIST);
169 connection.appendInt32(12);
170
171 // *** name ***
172 connection.appendInt32(BOTTLE_TAG_STRING);
173 connection.appendInt32(name.length());
174 connection.appendExternalBlock((char*)name.c_str(), name.length());
175
176 // *** offset ***
177 connection.appendInt32(BOTTLE_TAG_INT32);
178 connection.appendInt32(offset);
179
180 // *** datatype ***
181 connection.appendInt32(BOTTLE_TAG_INT8);
182 connection.appendInt8(datatype);
183
184 // *** count ***
185 connection.appendInt32(BOTTLE_TAG_INT32);
186 connection.appendInt32(count);
187
188 connection.convertTextMode();
189 return !connection.isError();
190 }
191
193 bool write(yarp::os::ConnectionWriter& connection) const override
194 {
195 return (connection.isBareMode() ? writeBare(connection)
196 : writeBottle(connection));
197 }
198
199 // This class will serialize ROS style or YARP style depending on protocol.
200 // If you need to force a serialization style, use one of these classes:
203
204 // The name for this message, ROS will need this
205 static constexpr const char* typeName = "sensor_msgs/PointField";
206
207 // The checksum for this message, ROS will need this
208 static constexpr const char* typeChecksum = "268eacb2962780ceac86cbd17e328150";
209
210 // The source text for this message, ROS will need this
211 static constexpr const char* typeText = "\
212# This message holds the description of one point entry in the\n\
213# PointCloud2 message format.\n\
214uint8 INT8 = 1\n\
215uint8 UINT8 = 2\n\
216uint8 INT16 = 3\n\
217uint8 UINT16 = 4\n\
218uint8 INT32 = 5\n\
219uint8 UINT32 = 6\n\
220uint8 FLOAT32 = 7\n\
221uint8 FLOAT64 = 8\n\
222\n\
223string name # Name of field\n\
224uint32 offset # Offset from start of point struct\n\
225uint8 datatype # Datatype enumeration, see above\n\
226uint32 count # How many elements in the field\n\
227";
228
229 yarp::os::Type getType() const override
230 {
233 typ.addProperty("message_definition", yarp::os::Value(typeText));
234 return typ;
235 }
236};
237
238} // namespace sensor_msgs
239} // namespace rosmsg
240} // namespace yarp
241
242#endif // YARP_ROSMSG_sensor_msgs_PointField_h
#define BOTTLE_TAG_INT8
Definition: Bottle.h:19
#define BOTTLE_TAG_INT32
Definition: Bottle.h:21
#define BOTTLE_TAG_STRING
Definition: Bottle.h:26
#define BOTTLE_TAG_LIST
Definition: Bottle.h:28
An interface for reading from a network connection.
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
virtual bool isError() const =0
virtual std::int8_t expectInt8()=0
Read a 8-bit integer from the network connection.
An interface for writing to a network connection.
virtual bool isError() const =0
virtual bool isBareMode() const =0
Check if the connection is bare mode.
virtual void appendInt8(std::int8_t data)=0
Send a representation of a 8-bit integer to the network connection.
virtual void appendExternalBlock(const char *data, size_t len)=0
Send a block of data to the network connection, without making a copy.
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
virtual void appendInt32(std::int32_t data)=0
Send a representation of a 32-bit integer to the network connection.
static Type byName(const char *name)
Definition: Type.cpp:171
Type & addProperty(const char *key, const Value &val)
Definition: Type.cpp:134
A single value (typically within a Bottle).
Definition: Value.h:43
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:21
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool write(const yarp::os::idl::WireWriter &writer) const
IDL-friendly connection reader.
Definition: WireReader.h:27
bool readString(std::string &str, bool *is_vocab=nullptr)
Definition: WireReader.cpp:376
std::int8_t expectInt8()
Definition: WireReader.h:77
std::int32_t expectInt32()
Definition: WireReader.h:89
static constexpr const char * typeChecksum
Definition: PointField.h:208
static const std::uint8_t INT32
Definition: PointField.h:47
yarp::os::Type getType() const override
Definition: PointField.h:229
static const std::uint8_t UINT8
Definition: PointField.h:44
static const std::uint8_t UINT32
Definition: PointField.h:48
static constexpr const char * typeName
Definition: PointField.h:205
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::PointField > bottleStyle
Definition: PointField.h:202
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: PointField.h:95
static const std::uint8_t INT8
Definition: PointField.h:43
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: PointField.h:116
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: PointField.h:166
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::PointField > rosStyle
Definition: PointField.h:201
static const std::uint8_t UINT16
Definition: PointField.h:46
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: PointField.h:148
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: PointField.h:142
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: PointField.h:193
static constexpr const char * typeText
Definition: PointField.h:211
static const std::uint8_t FLOAT64
Definition: PointField.h:50
static const std::uint8_t FLOAT32
Definition: PointField.h:49
static const std::uint8_t INT16
Definition: PointField.h:45
The main, catch-all namespace for YARP.
Definition: dirs.h:16