26 #ifndef YARP_ROSMSG_sensor_msgs_PointCloud_h
27 #define YARP_ROSMSG_sensor_msgs_PointCloud_h
46 std::vector<yarp::rosmsg::geometry_msgs::Point32>
points;
47 std::vector<yarp::rosmsg::sensor_msgs::ChannelFloat32>
channels;
78 for (
int i=0; i<len; i++) {
87 for (
int i=0; i<len; i++) {
115 for (
int i=0; i<len; i++) {
127 for (
int i=0; i<len; i++) {
152 for (
size_t i=0; i<
points.size(); i++) {
160 for (
size_t i=0; i<
channels.size(); i++) {
182 for (
size_t i=0; i<
points.size(); i++) {
191 for (
size_t i=0; i<
channels.size(); i++) {
214 static constexpr
const char*
typeName =
"sensor_msgs/PointCloud";
217 static constexpr
const char*
typeChecksum =
"d8e9c3f5afbdd8a130fd1d2763945fca";
221 # This message holds a collection of 3d points, plus optional additional\n\
222 # information about each point.\n\
224 # Time of sensor data acquisition, coordinate frame ID.\n\
227 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\
228 # in the frame given in the header.\n\
229 geometry_msgs/Point32[] points\n\
231 # Each channel should have the same number of elements as points array,\n\
232 # and the data in each channel should correspond 1:1 with each point.\n\
233 # Channel names in common practice are listed in ChannelFloat32.msg.\n\
234 ChannelFloat32[] channels\n\
236 ================================================================================\n\
237 MSG: std_msgs/Header\n\
238 # Standard metadata for higher-level stamped data types.\n\
239 # This is generally used to communicate timestamped data \n\
240 # in a particular coordinate frame.\n\
242 # sequence ID: consecutively increasing ID \n\
244 #Two-integer timestamp that is expressed as:\n\
245 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
246 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
247 # time-handling sugar is provided by the client library\n\
249 #Frame this data is associated with\n\
254 ================================================================================\n\
255 MSG: geometry_msgs/Point32\n\
256 # This contains the position of a point in free space(with 32 bits of precision).\n\
257 # It is recommeded to use Point wherever possible instead of Point32. \n\
259 # This recommendation is to promote interoperability. \n\
261 # This message is designed to take up less space when sending\n\
262 # lots of points at once, as in the case of a PointCloud. \n\
267 ================================================================================\n\
268 MSG: sensor_msgs/ChannelFloat32\n\
269 # This message is used by the PointCloud message to hold optional data\n\
270 # associated with each point in the cloud. The length of the values\n\
271 # array should be the same as the length of the points array in the\n\
272 # PointCloud, and each value should be associated with the corresponding\n\
275 # Channel names in existing practice include:\n\
276 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
277 # This is opposite to usual conventions but remains for\n\
278 # historical reasons. The newer PointCloud2 message has no\n\
280 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
281 # (R,G,B) values packed into the least significant 24 bits,\n\
283 # \"intensity\" - laser or pixel intensity.\n\
286 # The channel name should give semantics of the channel (e.g.\n\
287 # \"intensity\" instead of \"value\").\n\
290 # The values array should be 1-1 with the elements of the associated\n\
An interface for reading from a 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 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 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.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::rosmsg::std_msgs::Header header
bool readBare(yarp::os::ConnectionReader &connection) override
std::vector< yarp::rosmsg::sensor_msgs::ChannelFloat32 > channels
yarp::os::Type getType() const override
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::PointCloud > rosStyle
bool readBottle(yarp::os::ConnectionReader &connection) override
static constexpr const char * typeChecksum
static constexpr const char * typeName
bool writeBare(yarp::os::ConnectionWriter &connection) const override
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::PointCloud > bottleStyle
static constexpr const char * typeText
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
std::vector< yarp::rosmsg::geometry_msgs::Point32 > points
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
The main, catch-all namespace for YARP.