YARP
Yet Another Robot Platform
GetPlan.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 "nav_msgs/GetPlan" msg definition:
12 // # Get a plan from the current position to the goal Pose
13 //
14 // # The start pose for the plan
15 // geometry_msgs/PoseStamped start
16 //
17 // # The final pose of the goal position
18 // geometry_msgs/PoseStamped goal
19 //
20 // # If the goal is obstructed, how many meters the planner can
21 // # relax the constraint in x and y before failing.
22 // float32 tolerance
23 // ---
24 // nav_msgs/Path plan
25 // Instances of this class can be read and written with YARP ports,
26 // using a ROS-compatible format.
27 
28 #ifndef YARP_ROSMSG_nav_msgs_GetPlan_h
29 #define YARP_ROSMSG_nav_msgs_GetPlan_h
30 
31 #include <yarp/os/Wire.h>
32 #include <yarp/os/Type.h>
33 #include <yarp/os/idl/WireTypes.h>
34 #include <string>
35 #include <vector>
37 
38 namespace yarp {
39 namespace rosmsg {
40 namespace nav_msgs {
41 
43 {
44 public:
48 
49  GetPlan() :
50  start(),
51  goal(),
52  tolerance(0.0f)
53  {
54  }
55 
56  void clear()
57  {
58  // *** start ***
59  start.clear();
60 
61  // *** goal ***
62  goal.clear();
63 
64  // *** tolerance ***
65  tolerance = 0.0f;
66  }
67 
68  bool readBare(yarp::os::ConnectionReader& connection) override
69  {
70  // *** start ***
71  if (!start.read(connection)) {
72  return false;
73  }
74 
75  // *** goal ***
76  if (!goal.read(connection)) {
77  return false;
78  }
79 
80  // *** tolerance ***
81  tolerance = connection.expectFloat32();
82 
83  return !connection.isError();
84  }
85 
86  bool readBottle(yarp::os::ConnectionReader& connection) override
87  {
88  connection.convertTextMode();
89  yarp::os::idl::WireReader reader(connection);
90  if (!reader.readListHeader(3)) {
91  return false;
92  }
93 
94  // *** start ***
95  if (!start.read(connection)) {
96  return false;
97  }
98 
99  // *** goal ***
100  if (!goal.read(connection)) {
101  return false;
102  }
103 
104  // *** tolerance ***
105  tolerance = reader.expectFloat32();
106 
107  return !connection.isError();
108  }
109 
111  bool read(yarp::os::ConnectionReader& connection) override
112  {
113  return (connection.isBareMode() ? readBare(connection)
114  : readBottle(connection));
115  }
116 
117  bool writeBare(yarp::os::ConnectionWriter& connection) const override
118  {
119  // *** start ***
120  if (!start.write(connection)) {
121  return false;
122  }
123 
124  // *** goal ***
125  if (!goal.write(connection)) {
126  return false;
127  }
128 
129  // *** tolerance ***
130  connection.appendFloat32(tolerance);
131 
132  return !connection.isError();
133  }
134 
135  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
136  {
137  connection.appendInt32(BOTTLE_TAG_LIST);
138  connection.appendInt32(3);
139 
140  // *** start ***
141  if (!start.write(connection)) {
142  return false;
143  }
144 
145  // *** goal ***
146  if (!goal.write(connection)) {
147  return false;
148  }
149 
150  // *** tolerance ***
151  connection.appendInt32(BOTTLE_TAG_FLOAT32);
152  connection.appendFloat32(tolerance);
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 = "nav_msgs/GetPlan";
172 
173  // The checksum for this message, ROS will need this
174  static constexpr const char* typeChecksum = "e25a43e0752bcca599a8c2eef8282df8";
175 
176  // The source text for this message, ROS will need this
177  static constexpr const char* typeText = "\
178 # Get a plan from the current position to the goal Pose \n\
179 \n\
180 # The start pose for the plan\n\
181 geometry_msgs/PoseStamped start\n\
182 \n\
183 # The final pose of the goal position\n\
184 geometry_msgs/PoseStamped goal\n\
185 \n\
186 # If the goal is obstructed, how many meters the planner can \n\
187 # relax the constraint in x and y before failing. \n\
188 float32 tolerance\n\
189 ---\n\
190 nav_msgs/Path plan\n\
191 \n\
192 ================================================================================\n\
193 MSG: geometry_msgs/PoseStamped\n\
194 # A Pose with reference coordinate frame and timestamp\n\
195 Header header\n\
196 Pose pose\n\
197 \n\
198 ================================================================================\n\
199 MSG: 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\
205 uint32 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\
210 time stamp\n\
211 #Frame this data is associated with\n\
212 # 0: no frame\n\
213 # 1: global frame\n\
214 string frame_id\n\
215 \n\
216 ================================================================================\n\
217 MSG: geometry_msgs/Pose\n\
218 # A representation of pose in free space, composed of position and orientation. \n\
219 Point position\n\
220 Quaternion orientation\n\
221 \n\
222 ================================================================================\n\
223 MSG: geometry_msgs/Point\n\
224 # This contains the position of a point in free space\n\
225 float64 x\n\
226 float64 y\n\
227 float64 z\n\
228 \n\
229 ================================================================================\n\
230 MSG: geometry_msgs/Quaternion\n\
231 # This represents an orientation in free space in quaternion form.\n\
232 \n\
233 float64 x\n\
234 float64 y\n\
235 float64 z\n\
236 float64 w\n\
237 ";
238 
239  yarp::os::Type getType() const override
240  {
242  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
243  typ.addProperty("message_definition", yarp::os::Value(typeText));
244  return typ;
245  }
246 };
247 
248 } // namespace nav_msgs
249 } // namespace rosmsg
250 } // namespace yarp
251 
252 #endif // YARP_ROSMSG_nav_msgs_GetPlan_h
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::nav_msgs::GetPlan::goal
yarp::rosmsg::geometry_msgs::PoseStamped goal
Definition: GetPlan.h:46
WireTypes.h
BOTTLE_TAG_LIST
#define BOTTLE_TAG_LIST
Definition: Bottle.h:30
yarp::rosmsg::geometry_msgs::PoseStamped::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: PoseStamped.h:132
yarp::os::idl::WireReader::expectFloat32
yarp::conf::float32_t expectFloat32()
Definition: WireReader.h:113
yarp::rosmsg::nav_msgs::GetPlan::typeName
static constexpr const char * typeName
Definition: GetPlan.h:171
yarp::rosmsg::nav_msgs::GetPlan::getType
yarp::os::Type getType() const override
Definition: GetPlan.h:239
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
yarp::os::ConnectionReader::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
Wire.h
yarp::rosmsg::nav_msgs::GetPlan::typeText
static constexpr const char * typeText
Definition: GetPlan.h:177
yarp::rosmsg::nav_msgs::GetPlan::bottleStyle
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::GetPlan > bottleStyle
Definition: GetPlan.h:168
yarp::rosmsg::nav_msgs::GetPlan::rosStyle
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::GetPlan > rosStyle
Definition: GetPlan.h:167
yarp::os::ConnectionWriter::isError
virtual bool isError() const =0
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::os::Type::addProperty
Type & addProperty(const char *key, const Value &val)
Definition: Type.cpp:137
Type.h
yarp::rosmsg::nav_msgs::GetPlan::start
yarp::rosmsg::geometry_msgs::PoseStamped start
Definition: GetPlan.h:45
yarp::os::ConnectionWriter
An interface for writing to a network connection.
Definition: ConnectionWriter.h:40
yarp::os::ConnectionReader::isError
virtual bool isError() const =0
yarp::rosmsg::geometry_msgs::PoseStamped::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: PoseStamped.h:91
yarp::rosmsg::nav_msgs::GetPlan::readBottle
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: GetPlan.h:86
yarp::rosmsg::nav_msgs::GetPlan::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: GetPlan.h:111
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::geometry_msgs::PoseStamped
Definition: PoseStamped.h:34
yarp::rosmsg::nav_msgs::GetPlan::clear
void clear()
Definition: GetPlan.h:56
yarp::rosmsg::nav_msgs::GetPlan::tolerance
yarp::conf::float32_t tolerance
Definition: GetPlan.h:47
yarp::rosmsg::nav_msgs::GetPlan::readBare
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: GetPlan.h:68
yarp::os::idl::WirePortable
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:26
yarp::os::ConnectionWriter::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::rosmsg::nav_msgs::GetPlan::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: GetPlan.h:159
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::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.
nav_msgs
Definition: GetMap.h:22
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::os::idl::BareStyle
Definition: BareStyle.h:22
yarp::rosmsg::nav_msgs::GetPlan
Definition: GetPlan.h:43
yarp::rosmsg::nav_msgs::GetPlan::typeChecksum
static constexpr const char * typeChecksum
Definition: GetPlan.h:174
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::rosmsg::nav_msgs::GetPlan::writeBare
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: GetPlan.h:117
yarp::rosmsg::nav_msgs::GetPlan::writeBottle
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: GetPlan.h:135
yarp::os::Value
A single value (typically within a Bottle).
Definition: Value.h:47
yarp::rosmsg::nav_msgs::GetPlan::GetPlan
GetPlan()
Definition: GetPlan.h:49
yarp::rosmsg::geometry_msgs::PoseStamped::clear
void clear()
Definition: PoseStamped.h:45
PoseStamped.h
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