YARP
Yet Another Robot Platform
GetPlan.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 "nav_msgs/GetPlan" msg definition:
9// # Get a plan from the current position to the goal Pose
10//
11// # The start pose for the plan
12// geometry_msgs/PoseStamped start
13//
14// # The final pose of the goal position
15// geometry_msgs/PoseStamped goal
16//
17// # If the goal is obstructed, how many meters the planner can
18// # relax the constraint in x and y before failing.
19// float32 tolerance
20// ---
21// nav_msgs/Path plan
22// Instances of this class can be read and written with YARP ports,
23// using a ROS-compatible format.
24
25#ifndef YARP_ROSMSG_nav_msgs_GetPlan_h
26#define YARP_ROSMSG_nav_msgs_GetPlan_h
27
28#include <yarp/os/Wire.h>
29#include <yarp/os/Type.h>
31#include <string>
32#include <vector>
34
35namespace yarp {
36namespace rosmsg {
37namespace nav_msgs {
38
40{
41public:
45
47 start(),
48 goal(),
49 tolerance(0.0f)
50 {
51 }
52
53 void clear()
54 {
55 // *** start ***
56 start.clear();
57
58 // *** goal ***
59 goal.clear();
60
61 // *** tolerance ***
62 tolerance = 0.0f;
63 }
64
65 bool readBare(yarp::os::ConnectionReader& connection) override
66 {
67 // *** start ***
68 if (!start.read(connection)) {
69 return false;
70 }
71
72 // *** goal ***
73 if (!goal.read(connection)) {
74 return false;
75 }
76
77 // *** tolerance ***
78 tolerance = connection.expectFloat32();
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 // *** start ***
92 if (!start.read(connection)) {
93 return false;
94 }
95
96 // *** goal ***
97 if (!goal.read(connection)) {
98 return false;
99 }
100
101 // *** tolerance ***
102 tolerance = reader.expectFloat32();
103
104 return !connection.isError();
105 }
106
108 bool read(yarp::os::ConnectionReader& connection) override
109 {
110 return (connection.isBareMode() ? readBare(connection)
111 : readBottle(connection));
112 }
113
114 bool writeBare(yarp::os::ConnectionWriter& connection) const override
115 {
116 // *** start ***
117 if (!start.write(connection)) {
118 return false;
119 }
120
121 // *** goal ***
122 if (!goal.write(connection)) {
123 return false;
124 }
125
126 // *** tolerance ***
127 connection.appendFloat32(tolerance);
128
129 return !connection.isError();
130 }
131
132 bool writeBottle(yarp::os::ConnectionWriter& connection) const override
133 {
134 connection.appendInt32(BOTTLE_TAG_LIST);
135 connection.appendInt32(3);
136
137 // *** start ***
138 if (!start.write(connection)) {
139 return false;
140 }
141
142 // *** goal ***
143 if (!goal.write(connection)) {
144 return false;
145 }
146
147 // *** tolerance ***
149 connection.appendFloat32(tolerance);
150
151 connection.convertTextMode();
152 return !connection.isError();
153 }
154
156 bool write(yarp::os::ConnectionWriter& connection) const override
157 {
158 return (connection.isBareMode() ? writeBare(connection)
159 : writeBottle(connection));
160 }
161
162 // This class will serialize ROS style or YARP style depending on protocol.
163 // If you need to force a serialization style, use one of these classes:
166
167 // The name for this message, ROS will need this
168 static constexpr const char* typeName = "nav_msgs/GetPlan";
169
170 // The checksum for this message, ROS will need this
171 static constexpr const char* typeChecksum = "e25a43e0752bcca599a8c2eef8282df8";
172
173 // The source text for this message, ROS will need this
174 static constexpr const char* typeText = "\
175# Get a plan from the current position to the goal Pose \n\
176\n\
177# The start pose for the plan\n\
178geometry_msgs/PoseStamped start\n\
179\n\
180# The final pose of the goal position\n\
181geometry_msgs/PoseStamped goal\n\
182\n\
183# If the goal is obstructed, how many meters the planner can \n\
184# relax the constraint in x and y before failing. \n\
185float32 tolerance\n\
186---\n\
187nav_msgs/Path plan\n\
188\n\
189================================================================================\n\
190MSG: geometry_msgs/PoseStamped\n\
191# A Pose with reference coordinate frame and timestamp\n\
192Header header\n\
193Pose pose\n\
194\n\
195================================================================================\n\
196MSG: std_msgs/Header\n\
197# Standard metadata for higher-level stamped data types.\n\
198# This is generally used to communicate timestamped data \n\
199# in a particular coordinate frame.\n\
200# \n\
201# sequence ID: consecutively increasing ID \n\
202uint32 seq\n\
203#Two-integer timestamp that is expressed as:\n\
204# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
205# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
206# time-handling sugar is provided by the client library\n\
207time stamp\n\
208#Frame this data is associated with\n\
209# 0: no frame\n\
210# 1: global frame\n\
211string frame_id\n\
212\n\
213================================================================================\n\
214MSG: geometry_msgs/Pose\n\
215# A representation of pose in free space, composed of position and orientation. \n\
216Point position\n\
217Quaternion orientation\n\
218\n\
219================================================================================\n\
220MSG: geometry_msgs/Point\n\
221# This contains the position of a point in free space\n\
222float64 x\n\
223float64 y\n\
224float64 z\n\
225\n\
226================================================================================\n\
227MSG: geometry_msgs/Quaternion\n\
228# This represents an orientation in free space in quaternion form.\n\
229\n\
230float64 x\n\
231float64 y\n\
232float64 z\n\
233float64 w\n\
234";
235
236 yarp::os::Type getType() const override
237 {
240 typ.addProperty("message_definition", yarp::os::Value(typeText));
241 return typ;
242 }
243};
244
245} // namespace nav_msgs
246} // namespace rosmsg
247} // namespace yarp
248
249#endif // YARP_ROSMSG_nav_msgs_GetPlan_h
#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 isBareMode() const =0
Check if the connection is bare mode.
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 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::conf::float32_t expectFloat32()
Definition: WireReader.h:103
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: PoseStamped.h:129
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: PoseStamped.h:88
yarp::os::Type getType() const override
Definition: GetPlan.h:236
yarp::rosmsg::geometry_msgs::PoseStamped start
Definition: GetPlan.h:42
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::GetPlan > rosStyle
Definition: GetPlan.h:164
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: GetPlan.h:65
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: GetPlan.h:132
yarp::rosmsg::geometry_msgs::PoseStamped goal
Definition: GetPlan.h:43
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: GetPlan.h:108
static constexpr const char * typeName
Definition: GetPlan.h:168
static constexpr const char * typeChecksum
Definition: GetPlan.h:171
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: GetPlan.h:83
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::GetPlan > bottleStyle
Definition: GetPlan.h:165
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: GetPlan.h:156
yarp::conf::float32_t tolerance
Definition: GetPlan.h:44
static constexpr const char * typeText
Definition: GetPlan.h:174
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: GetPlan.h:114
float float32_t
Definition: numeric.h:76
The main, catch-all namespace for YARP.
Definition: dirs.h:16