YARP
Yet Another Robot Platform
ChannelFloat32.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/ChannelFloat32" msg definition:
9 // # This message is used by the PointCloud message to hold optional data
10 // # associated with each point in the cloud. The length of the values
11 // # array should be the same as the length of the points array in the
12 // # PointCloud, and each value should be associated with the corresponding
13 // # point.
14 //
15 // # Channel names in existing practice include:
16 // # "u", "v" - row and column (respectively) in the left stereo image.
17 // # This is opposite to usual conventions but remains for
18 // # historical reasons. The newer PointCloud2 message has no
19 // # such problem.
20 // # "rgb" - For point clouds produced by color stereo cameras. uint8
21 // # (R,G,B) values packed into the least significant 24 bits,
22 // # in order.
23 // # "intensity" - laser or pixel intensity.
24 // # "distance"
25 //
26 // # The channel name should give semantics of the channel (e.g.
27 // # "intensity" instead of "value").
28 // string name
29 //
30 // # The values array should be 1-1 with the elements of the associated
31 // # PointCloud.
32 // float32[] values
33 // Instances of this class can be read and written with YARP ports,
34 // using a ROS-compatible format.
35 
36 #ifndef YARP_ROSMSG_sensor_msgs_ChannelFloat32_h
37 #define YARP_ROSMSG_sensor_msgs_ChannelFloat32_h
38 
39 #include <yarp/os/Wire.h>
40 #include <yarp/os/Type.h>
41 #include <yarp/os/idl/WireTypes.h>
42 #include <string>
43 #include <vector>
44 
45 namespace yarp {
46 namespace rosmsg {
47 namespace sensor_msgs {
48 
50 {
51 public:
52  std::string name;
53  std::vector<yarp::conf::float32_t> values;
54 
56  name(""),
57  values()
58  {
59  }
60 
61  void clear()
62  {
63  // *** name ***
64  name = "";
65 
66  // *** values ***
67  values.clear();
68  }
69 
70  bool readBare(yarp::os::ConnectionReader& connection) override
71  {
72  // *** name ***
73  int len = connection.expectInt32();
74  name.resize(len);
75  if (!connection.expectBlock((char*)name.c_str(), len)) {
76  return false;
77  }
78 
79  // *** values ***
80  len = connection.expectInt32();
81  values.resize(len);
82  if (len > 0 && !connection.expectBlock((char*)&values[0], sizeof(yarp::conf::float32_t)*len)) {
83  return false;
84  }
85 
86  return !connection.isError();
87  }
88 
89  bool readBottle(yarp::os::ConnectionReader& connection) override
90  {
91  connection.convertTextMode();
92  yarp::os::idl::WireReader reader(connection);
93  if (!reader.readListHeader(2)) {
94  return false;
95  }
96 
97  // *** name ***
98  if (!reader.readString(name)) {
99  return false;
100  }
101 
102  // *** values ***
103  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT32)) {
104  return false;
105  }
106  int len = connection.expectInt32();
107  values.resize(len);
108  for (int i=0; i<len; i++) {
109  values[i] = (yarp::conf::float32_t)connection.expectFloat32();
110  }
111 
112  return !connection.isError();
113  }
114 
116  bool read(yarp::os::ConnectionReader& connection) override
117  {
118  return (connection.isBareMode() ? readBare(connection)
119  : readBottle(connection));
120  }
121 
122  bool writeBare(yarp::os::ConnectionWriter& connection) const override
123  {
124  // *** name ***
125  connection.appendInt32(name.length());
126  connection.appendExternalBlock((char*)name.c_str(), name.length());
127 
128  // *** values ***
129  connection.appendInt32(values.size());
130  if (values.size()>0) {
131  connection.appendExternalBlock((char*)&values[0], sizeof(yarp::conf::float32_t)*values.size());
132  }
133 
134  return !connection.isError();
135  }
136 
137  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
138  {
139  connection.appendInt32(BOTTLE_TAG_LIST);
140  connection.appendInt32(2);
141 
142  // *** name ***
143  connection.appendInt32(BOTTLE_TAG_STRING);
144  connection.appendInt32(name.length());
145  connection.appendExternalBlock((char*)name.c_str(), name.length());
146 
147  // *** values ***
149  connection.appendInt32(values.size());
150  for (size_t i=0; i<values.size(); i++) {
151  connection.appendFloat32(values[i]);
152  }
153 
154  connection.convertTextMode();
155  return !connection.isError();
156  }
157 
159  bool write(yarp::os::ConnectionWriter& connection) const override
160  {
161  return (connection.isBareMode() ? writeBare(connection)
162  : writeBottle(connection));
163  }
164 
165  // This class will serialize ROS style or YARP style depending on protocol.
166  // If you need to force a serialization style, use one of these classes:
169 
170  // The name for this message, ROS will need this
171  static constexpr const char* typeName = "sensor_msgs/ChannelFloat32";
172 
173  // The checksum for this message, ROS will need this
174  static constexpr const char* typeChecksum = "3d40139cdd33dfedcb71ffeeeb42ae7f";
175 
176  // The source text for this message, ROS will need this
177  static constexpr const char* typeText = "\
178 # This message is used by the PointCloud message to hold optional data\n\
179 # associated with each point in the cloud. The length of the values\n\
180 # array should be the same as the length of the points array in the\n\
181 # PointCloud, and each value should be associated with the corresponding\n\
182 # point.\n\
183 \n\
184 # Channel names in existing practice include:\n\
185 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
186 # This is opposite to usual conventions but remains for\n\
187 # historical reasons. The newer PointCloud2 message has no\n\
188 # such problem.\n\
189 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
190 # (R,G,B) values packed into the least significant 24 bits,\n\
191 # in order.\n\
192 # \"intensity\" - laser or pixel intensity.\n\
193 # \"distance\"\n\
194 \n\
195 # The channel name should give semantics of the channel (e.g.\n\
196 # \"intensity\" instead of \"value\").\n\
197 string name\n\
198 \n\
199 # The values array should be 1-1 with the elements of the associated\n\
200 # PointCloud.\n\
201 float32[] values\n\
202 ";
203 
204  yarp::os::Type getType() const override
205  {
207  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
208  typ.addProperty("message_definition", yarp::os::Value(typeText));
209  return typ;
210  }
211 };
212 
213 } // namespace sensor_msgs
214 } // namespace rosmsg
215 } // namespace yarp
216 
217 #endif // YARP_ROSMSG_sensor_msgs_ChannelFloat32_h
#define BOTTLE_TAG_STRING
Definition: Bottle.h:26
#define BOTTLE_TAG_LIST
Definition: Bottle.h:28
#define BOTTLE_TAG_FLOAT32
Definition: Bottle.h:24
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 yarp::conf::float32_t expectFloat32()=0
Read a 32-bit floating point number from the network connection.
virtual bool isError() const =0
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 appendFloat32(yarp::conf::float32_t data)=0
Send a representation of a 32-bit floating point number 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:45
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:23
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:30
bool readString(std::string &str, bool *is_vocab=nullptr)
Definition: WireReader.cpp:382
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::ChannelFloat32 > rosStyle
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool readBare(yarp::os::ConnectionReader &connection) override
static constexpr const char * typeText
static constexpr const char * typeChecksum
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::ChannelFloat32 > bottleStyle
bool writeBare(yarp::os::ConnectionWriter &connection) const override
yarp::os::Type getType() const override
std::vector< yarp::conf::float32_t > values
static constexpr const char * typeName
bool readBottle(yarp::os::ConnectionReader &connection) override
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
float float32_t
Definition: numeric.h:76
The main, catch-all namespace for YARP.
Definition: dirs.h:16