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