|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
20 #ifndef YARP_ROSMSG_geometry_msgs_PoseArray_h
21 #define YARP_ROSMSG_geometry_msgs_PoseArray_h
39 std::vector<yarp::rosmsg::geometry_msgs::Pose>
poses;
66 for (
int i=0; i<len; i++) {
94 for (
int i=0; i<len; i++) {
119 for (
size_t i=0; i<
poses.size(); i++) {
141 for (
size_t i=0; i<
poses.size(); i++) {
164 static constexpr
const char*
typeName =
"geometry_msgs/PoseArray";
167 static constexpr
const char*
typeChecksum =
"916c28c5764443f268b296bb671b9d97";
171 # An array of poses with a header for global reference.\n\
177 ================================================================================\n\
178 MSG: std_msgs/Header\n\
179 # Standard metadata for higher-level stamped data types.\n\
180 # This is generally used to communicate timestamped data \n\
181 # in a particular coordinate frame.\n\
183 # sequence ID: consecutively increasing ID \n\
185 #Two-integer timestamp that is expressed as:\n\
186 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
187 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
188 # time-handling sugar is provided by the client library\n\
190 #Frame this data is associated with\n\
195 ================================================================================\n\
196 MSG: geometry_msgs/Pose\n\
197 # A representation of pose in free space, composed of position and orientation. \n\
199 Quaternion orientation\n\
201 ================================================================================\n\
202 MSG: geometry_msgs/Point\n\
203 # This contains the position of a point in free space\n\
208 ================================================================================\n\
209 MSG: geometry_msgs/Quaternion\n\
210 # This represents an orientation in free space in quaternion form.\n\
231 #endif // YARP_ROSMSG_geometry_msgs_PoseArray_h
yarp::os::Type getType() const override
static constexpr const char * typeChecksum
virtual bool read(yarp::os::idl::WireReader &reader)
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
virtual bool isBareMode() const =0
Check if the connection is bare mode.
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool writeBare(yarp::os::ConnectionWriter &connection) const override
yarp::rosmsg::std_msgs::Header header
virtual bool isError() const =0
static Type byName(const char *name)
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
Type & addProperty(const char *key, const Value &val)
yarp::os::idl::BareStyle< yarp::rosmsg::geometry_msgs::PoseArray > rosStyle
static constexpr const char * typeName
An interface for writing to a network connection.
virtual bool isError() const =0
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
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.
IDL-friendly connection reader.
An interface for reading from a network connection.
yarp::os::idl::BottleStyle< yarp::rosmsg::geometry_msgs::PoseArray > bottleStyle
bool readBottle(yarp::os::ConnectionReader &connection) override
The main, catch-all namespace for YARP.
static constexpr const char * typeText
std::vector< yarp::rosmsg::geometry_msgs::Pose > poses
A single value (typically within a Bottle).
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool readBare(yarp::os::ConnectionReader &connection) override
virtual bool write(const yarp::os::idl::WireWriter &writer) const