25 #ifndef YARP_ROSMSG_nav_msgs_GetPlan_h
26 #define YARP_ROSMSG_nav_msgs_GetPlan_h
168 static constexpr
const char*
typeName =
"nav_msgs/GetPlan";
171 static constexpr
const char*
typeChecksum =
"e25a43e0752bcca599a8c2eef8282df8";
175 # Get a plan from the current position to the goal Pose \n\
177 # The start pose for the plan\n\
178 geometry_msgs/PoseStamped start\n\
180 # The final pose of the goal position\n\
181 geometry_msgs/PoseStamped goal\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\
187 nav_msgs/Path plan\n\
189 ================================================================================\n\
190 MSG: geometry_msgs/PoseStamped\n\
191 # A Pose with reference coordinate frame and timestamp\n\
195 ================================================================================\n\
196 MSG: 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\
201 # sequence ID: consecutively increasing ID \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\
208 #Frame this data is associated with\n\
213 ================================================================================\n\
214 MSG: geometry_msgs/Pose\n\
215 # A representation of pose in free space, composed of position and orientation. \n\
217 Quaternion orientation\n\
219 ================================================================================\n\
220 MSG: geometry_msgs/Point\n\
221 # This contains the position of a point in free space\n\
226 ================================================================================\n\
227 MSG: geometry_msgs/Quaternion\n\
228 # This represents an orientation in free space in quaternion form.\n\
#define BOTTLE_TAG_FLOAT32
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)
Type & addProperty(const char *key, const Value &val)
A single value (typically within a Bottle).
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool write(const yarp::os::idl::WireWriter &writer) const
IDL-friendly connection reader.
yarp::conf::float32_t expectFloat32()
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::os::Type getType() const override
yarp::rosmsg::geometry_msgs::PoseStamped start
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::GetPlan > rosStyle
bool readBare(yarp::os::ConnectionReader &connection) override
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
yarp::rosmsg::geometry_msgs::PoseStamped goal
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
static constexpr const char * typeName
static constexpr const char * typeChecksum
bool readBottle(yarp::os::ConnectionReader &connection) override
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::GetPlan > bottleStyle
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
yarp::conf::float32_t tolerance
static constexpr const char * typeText
bool writeBare(yarp::os::ConnectionWriter &connection) const override
The main, catch-all namespace for YARP.