Namespaces | Macros | Typedefs | Functions
cloud.hpp File Reference

Utilities for comfortable working with PointCloud2 messages. More...

#include <string>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/PointField.h>
#include <sensor_msgs/point_cloud2_iterator.h>
#include "cloud/impl/cloud.hpp"
Include dependency graph for cloud.hpp:

Go to the source code of this file.

Namespaces

 cras
 

Macros

#define CREATE_FILTERED_CLOUD(IN, OUT, KEEP_ORGANIZED, FILTER)
 Create a pointcloud that contains a subset of points of IN defined by the filter FILTER. The result is saved into OUT. FILTER should be a boolean expression which can use the following: i: index of the point, x_it, y_it, z_it iterators to XYZ coordinates. Points for which FILTER is true are part of the final pointcloud. More...
 

Typedefs

typedef ::sensor_msgs::PointCloud2 cras::Cloud
 Shorthand for sensor_msgs::PointCloud2. More...
 
typedef ::sensor_msgs::PointCloud2ConstIterator< float > cras::CloudConstIter
 Const cloud float field iterator. More...
 
typedef ::sensor_msgs::PointCloud2ConstIterator< int > cras::CloudIndexConstIter
 Const cloud int field iterator. More...
 
typedef ::sensor_msgs::PointCloud2Iterator< int > cras::CloudIndexIter
 Cloud int field iterator. More...
 
typedef ::sensor_msgs::PointCloud2Iterator< float > cras::CloudIter
 Cloud float field iterator. More...
 
typedef ::sensor_msgs::PointCloud2Modifier cras::CloudModifier
 Shorthand for sensor_msgs::PointCloud2Modifier. More...
 
typedef ::cras::impl::GenericCloudConstIterator cras::GenericCloudConstIter
 
typedef ::cras::impl::GenericCloudIterator cras::GenericCloudIter
 GenericCloudIter and GenericCloudConstIter are iterators of fields of types unknown at compile time. More...
 

Functions

void cras::copyChannelData (const ::cras::Cloud &in, ::cras::Cloud &out, const ::std::string &fieldName)
 Copy data belonging to the given field from in cloud to out cloud. More...
 
::sensor_msgs::PointField & cras::getField (::cras::Cloud &cloud, const ::std::string &fieldName)
 Return the sensor_msgs::PointField with the given name. More...
 
const ::sensor_msgs::PointField & cras::getField (const ::cras::Cloud &cloud, const ::std::string &fieldName)
 Return the sensor_msgs::PointField with the given name. More...
 
bool cras::hasField (const ::cras::Cloud &cloud, const ::std::string &fieldName)
 Return true if the cloud contains a field with the given name. More...
 
size_t cras::numPoints (const ::cras::Cloud &cloud)
 Return the number of points the given pointcloud contains. More...
 
size_t cras::sizeOfPointField (const ::sensor_msgs::PointField &field)
 Return the size (in bytes) of the data represented by the sensor_msgs::PointField. More...
 
size_t cras::sizeOfPointField (int datatype)
 Return the size (in bytes) of a sensor_msgs::PointField datatype. More...
 

Detailed Description

Utilities for comfortable working with PointCloud2 messages.

Author
Martin Pecka SPDX-License-Identifier: BSD-3-Clause SPDX-FileCopyrightText: Czech Technical University in Prague

Definition in file cloud.hpp.

Macro Definition Documentation

◆ CREATE_FILTERED_CLOUD

#define CREATE_FILTERED_CLOUD (   IN,
  OUT,
  KEEP_ORGANIZED,
  FILTER 
)

Create a pointcloud that contains a subset of points of IN defined by the filter FILTER. The result is saved into OUT. FILTER should be a boolean expression which can use the following: i: index of the point, x_it, y_it, z_it iterators to XYZ coordinates. Points for which FILTER is true are part of the final pointcloud.

Definition at line 132 of file cloud.hpp.



cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sun Jan 14 2024 03:48:14