YARP
Yet Another Robot Platform
Joy.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 // This is an automatically generated file.
10 
11 // Generated from the following "sensor_msgs/Joy" msg definition:
12 // # Reports the state of a joysticks axes and buttons.
13 // Header header # timestamp in the header is the time the data is received from the joystick
14 // float32[] axes # the axes measurements from a joystick
15 // int32[] buttons # the buttons measurements from a joystick
16 // Instances of this class can be read and written with YARP ports,
17 // using a ROS-compatible format.
18 
19 #ifndef YARP_ROSMSG_sensor_msgs_Joy_h
20 #define YARP_ROSMSG_sensor_msgs_Joy_h
21 
22 #include <yarp/os/Wire.h>
23 #include <yarp/os/Type.h>
25 #include <string>
26 #include <vector>
28 
29 namespace yarp {
30 namespace rosmsg {
31 namespace sensor_msgs {
32 
34 {
35 public:
37  std::vector<yarp::conf::float32_t> axes;
38  std::vector<std::int32_t> buttons;
39 
40  Joy() :
41  header(),
42  axes(),
43  buttons()
44  {
45  }
46 
47  void clear()
48  {
49  // *** header ***
50  header.clear();
51 
52  // *** axes ***
53  axes.clear();
54 
55  // *** buttons ***
56  buttons.clear();
57  }
58 
59  bool readBare(yarp::os::ConnectionReader& connection) override
60  {
61  // *** header ***
62  if (!header.read(connection)) {
63  return false;
64  }
65 
66  // *** axes ***
67  int len = connection.expectInt32();
68  axes.resize(len);
69  if (len > 0 && !connection.expectBlock((char*)&axes[0], sizeof(yarp::conf::float32_t)*len)) {
70  return false;
71  }
72 
73  // *** buttons ***
74  len = connection.expectInt32();
75  buttons.resize(len);
76  if (len > 0 && !connection.expectBlock((char*)&buttons[0], sizeof(std::int32_t)*len)) {
77  return false;
78  }
79 
80  return !connection.isError();
81  }
82 
83  bool readBottle(yarp::os::ConnectionReader& connection) override
84  {
85  connection.convertTextMode();
86  yarp::os::idl::WireReader reader(connection);
87  if (!reader.readListHeader(3)) {
88  return false;
89  }
90 
91  // *** header ***
92  if (!header.read(connection)) {
93  return false;
94  }
95 
96  // *** axes ***
97  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT32)) {
98  return false;
99  }
100  int len = connection.expectInt32();
101  axes.resize(len);
102  for (int i=0; i<len; i++) {
103  axes[i] = (yarp::conf::float32_t)connection.expectFloat32();
104  }
105 
106  // *** buttons ***
107  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_INT32)) {
108  return false;
109  }
110  len = connection.expectInt32();
111  buttons.resize(len);
112  for (int i=0; i<len; i++) {
113  buttons[i] = (std::int32_t)connection.expectInt32();
114  }
115 
116  return !connection.isError();
117  }
118 
120  bool read(yarp::os::ConnectionReader& connection) override
121  {
122  return (connection.isBareMode() ? readBare(connection)
123  : readBottle(connection));
124  }
125 
126  bool writeBare(yarp::os::ConnectionWriter& connection) const override
127  {
128  // *** header ***
129  if (!header.write(connection)) {
130  return false;
131  }
132 
133  // *** axes ***
134  connection.appendInt32(axes.size());
135  if (axes.size()>0) {
136  connection.appendExternalBlock((char*)&axes[0], sizeof(yarp::conf::float32_t)*axes.size());
137  }
138 
139  // *** buttons ***
140  connection.appendInt32(buttons.size());
141  if (buttons.size()>0) {
142  connection.appendExternalBlock((char*)&buttons[0], sizeof(std::int32_t)*buttons.size());
143  }
144 
145  return !connection.isError();
146  }
147 
148  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
149  {
150  connection.appendInt32(BOTTLE_TAG_LIST);
151  connection.appendInt32(3);
152 
153  // *** header ***
154  if (!header.write(connection)) {
155  return false;
156  }
157 
158  // *** axes ***
160  connection.appendInt32(axes.size());
161  for (size_t i=0; i<axes.size(); i++) {
162  connection.appendFloat32(axes[i]);
163  }
164 
165  // *** buttons ***
167  connection.appendInt32(buttons.size());
168  for (size_t i=0; i<buttons.size(); i++) {
169  connection.appendInt32(buttons[i]);
170  }
171 
172  connection.convertTextMode();
173  return !connection.isError();
174  }
175 
177  bool write(yarp::os::ConnectionWriter& connection) const override
178  {
179  return (connection.isBareMode() ? writeBare(connection)
180  : writeBottle(connection));
181  }
182 
183  // This class will serialize ROS style or YARP style depending on protocol.
184  // If you need to force a serialization style, use one of these classes:
187 
188  // The name for this message, ROS will need this
189  static constexpr const char* typeName = "sensor_msgs/Joy";
190 
191  // The checksum for this message, ROS will need this
192  static constexpr const char* typeChecksum = "5a9ea5f83505693b71e785041e67a8bb";
193 
194  // The source text for this message, ROS will need this
195  static constexpr const char* typeText = "\
196 # Reports the state of a joysticks axes and buttons.\n\
197 Header header # timestamp in the header is the time the data is received from the joystick\n\
198 float32[] axes # the axes measurements from a joystick\n\
199 int32[] buttons # the buttons measurements from a joystick \n\
200 \n\
201 ================================================================================\n\
202 MSG: std_msgs/Header\n\
203 # Standard metadata for higher-level stamped data types.\n\
204 # This is generally used to communicate timestamped data \n\
205 # in a particular coordinate frame.\n\
206 # \n\
207 # sequence ID: consecutively increasing ID \n\
208 uint32 seq\n\
209 #Two-integer timestamp that is expressed as:\n\
210 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
211 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
212 # time-handling sugar is provided by the client library\n\
213 time stamp\n\
214 #Frame this data is associated with\n\
215 # 0: no frame\n\
216 # 1: global frame\n\
217 string frame_id\n\
218 ";
219 
220  yarp::os::Type getType() const override
221  {
223  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
224  typ.addProperty("message_definition", yarp::os::Value(typeText));
225  return typ;
226  }
227 };
228 
229 } // namespace sensor_msgs
230 } // namespace rosmsg
231 } // namespace yarp
232 
233 #endif // YARP_ROSMSG_sensor_msgs_Joy_h
yarp::rosmsg::sensor_msgs::Joy::header
yarp::rosmsg::std_msgs::Header header
Definition: Joy.h:36
yarp::os::ConnectionWriter::appendFloat32
virtual void appendFloat32(yarp::conf::float32_t data)=0
Send a representation of a 32-bit floating point number to the network connection.
yarp::rosmsg::std_msgs::Header::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Header.h:115
WireTypes.h
BOTTLE_TAG_LIST
#define BOTTLE_TAG_LIST
Definition: Bottle.h:30
yarp::os::idl::BottleStyle
Definition: BottleStyle.h:22
yarp::os::Type
Definition: Type.h:24
yarp::os::idl::WirePortable::read
virtual bool read(yarp::os::idl::WireReader &reader)
Definition: WirePortable.cpp:14
Header.h
yarp::rosmsg::sensor_msgs::Joy::writeBottle
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: Joy.h:148
yarp::os::ConnectionReader::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::rosmsg::std_msgs::Header::clear
void clear()
Definition: Header.h:58
Wire.h
yarp::rosmsg::sensor_msgs::Joy::readBare
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: Joy.h:59
BOTTLE_TAG_INT32
#define BOTTLE_TAG_INT32
Definition: Bottle.h:23
yarp::rosmsg::sensor_msgs::Joy::writeBare
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: Joy.h:126
yarp::rosmsg::sensor_msgs::Joy::axes
std::vector< yarp::conf::float32_t > axes
Definition: Joy.h:37
yarp::rosmsg::sensor_msgs::Joy::clear
void clear()
Definition: Joy.h:47
yarp::os::ConnectionWriter::isError
virtual bool isError() const =0
yarp::rosmsg::sensor_msgs::Joy
Definition: Joy.h:34
yarp::rosmsg::sensor_msgs::Joy::typeText
static constexpr const char * typeText
Definition: Joy.h:195
BOTTLE_TAG_FLOAT32
#define BOTTLE_TAG_FLOAT32
Definition: Bottle.h:26
yarp::os::Type::byName
static Type byName(const char *name)
Definition: Type.cpp:174
yarp::rosmsg::sensor_msgs::Joy::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Joy.h:177
yarp::os::ConnectionReader::expectInt32
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
yarp::os::Type::addProperty
Type & addProperty(const char *key, const Value &val)
Definition: Type.cpp:137
Type.h
yarp::os::ConnectionWriter
An interface for writing to a network connection.
Definition: ConnectionWriter.h:40
yarp::rosmsg::sensor_msgs::Joy::Joy
Joy()
Definition: Joy.h:40
yarp::os::ConnectionReader::isError
virtual bool isError() const =0
yarp::os::ConnectionReader::convertTextMode
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
yarp::rosmsg::sensor_msgs::Joy::buttons
std::vector< std::int32_t > buttons
Definition: Joy.h:38
yarp::rosmsg::sensor_msgs::Joy::bottleStyle
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::Joy > bottleStyle
Definition: Joy.h:186
yarp::os::idl::WirePortable
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:26
yarp::rosmsg::sensor_msgs::Joy::getType
yarp::os::Type getType() const override
Definition: Joy.h:220
yarp::os::ConnectionWriter::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::rosmsg::std_msgs::Header::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Header.h:162
yarp::os::ConnectionWriter::convertTextMode
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
yarp::rosmsg::sensor_msgs::Joy::typeChecksum
static constexpr const char * typeChecksum
Definition: Joy.h:192
yarp::conf::float32_t
float float32_t
Definition: numeric.h:50
yarp::os::ConnectionWriter::appendInt32
virtual void appendInt32(std::int32_t data)=0
Send a representation of a 32-bit integer to the network connection.
yarp::os::idl::WireReader
IDL-friendly connection reader.
Definition: WireReader.h:33
yarp::os::ConnectionReader
An interface for reading from a network connection.
Definition: ConnectionReader.h:40
yarp::rosmsg::sensor_msgs::Joy::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Joy.h:120
yarp::os::idl::BareStyle
Definition: BareStyle.h:22
yarp::rosmsg::sensor_msgs::Joy::readBottle
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: Joy.h:83
yarp::rosmsg::sensor_msgs::Joy::typeName
static constexpr const char * typeName
Definition: Joy.h:189
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
yarp::os::ConnectionReader::expectFloat32
virtual yarp::conf::float32_t expectFloat32()=0
Read a 32-bit floating point number from the network connection.
yarp::os::ConnectionWriter::appendExternalBlock
virtual void appendExternalBlock(const char *data, size_t len)=0
Send a block of data to the network connection, without making a copy.
yarp::os::ConnectionReader::expectBlock
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
yarp::os::Value
A single value (typically within a Bottle).
Definition: Value.h:47
sensor_msgs
Definition: BatteryState.h:22
yarp::rosmsg::sensor_msgs::Joy::rosStyle
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::Joy > rosStyle
Definition: Joy.h:185
yarp::rosmsg::std_msgs::Header
Definition: Header.h:45
yarp::os::idl::WireReader::readListHeader
bool readListHeader()
Definition: WireReader.cpp:470
yarp::os::idl::WirePortable::write
virtual bool write(const yarp::os::idl::WireWriter &writer) const
Definition: WirePortable.cpp:20