YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
yarp::sig::PointCloud< T > Class Template Reference

The PointCloud class. More...

#include <yarp/sig/PointCloud.h>

+ Inheritance diagram for yarp::sig::PointCloud< T >:

Public Member Functions

 PointCloud ()
 PointCloud, default constructor.
 
template<class T1 >
 PointCloud (const PointCloud< T1 > &alt)
 PointCloud, copy constructor.
 
virtual void resize (size_t width, size_t height)
 Resize the PointCloud.
 
virtual void resize (size_t width)
 Resize the PointCloud.
 
const char * getRawData () const override
 Get the pointer to the data.
 
size_t wireSizeBytes () const override
 Get the size of the data + the header in terms of number of bytes.
 
size_t dataSizeBytes () const override
 Get the size of the data in terms of number of bytes.
 
size_t size () const override
 
T & operator() (size_t u, size_t v)
 Obtain the point given by the (column, row) coordinates.
 
const T & operator() (size_t u, size_t v) const
 Obtain the point given by the (column, row) coordinates (const version).
 
T & operator() (size_t i)
 Obtain the point given by the index.
 
const T & operator() (size_t i) const
 Obtain the point given by the index (const version).
 
template<class T1 >
const PointCloud< T > & operator= (const PointCloud< T1 > &alt)
 Assignment operator.
 
PointCloud< T > & operator+= (const PointCloud< T > &rhs)
 Concatenate a point cloud to the current cloud.
 
const PointCloud< T > operator+ (const PointCloud< T > &rhs)
 Concatenate a point cloud to another cloud.
 
void push_back (const T &pt)
 Insert a new point in the cloud, at the end of the container.
 
virtual void clear ()
 Clear the data.
 
virtual void fromExternalPC (const char *source, int type, size_t width, size_t height, bool isDense=true)
 Copy the content of an external PointCloud.
 
template<class T1 >
void copy (const PointCloud< T1 > &alt)
 Copy operator.
 
bool read (yarp::os::ConnectionReader &connection) override
 Read this object from a network connection.
 
bool write (yarp::os::ConnectionWriter &writer) const override
 Write this object to a network connection.
 
virtual std::string toString (int precision=-1, int width=-1) const
 
yarp::os::Bottle toBottle () const
 Generate a yarp::os::Bottle filled with the PointCloud data.
 
bool fromBottle (const yarp::os::Bottle &bt)
 Populate the PointCloud from a yarp::os::Bottle.
 
int getBottleTag () const override
 
bool sortDataZ ()
 Rearranges the pointcloud data so that the points are ordered from the nearest to the farthest.
 
bool filterDataZ (double minZ=0, double maxZ=std::numeric_limits< double >::infinity())
 Filter out points which are not included in the specified range.
 
- Public Member Functions inherited from yarp::sig::PointCloudBase
virtual ~PointCloudBase ()=default
 
virtual size_t height () const
 
virtual size_t width () const
 
virtual int getPointType () const
 
yarp::os::Type getType () const override
 
virtual bool isOrganized () const
 
virtual bool isDense () const
 
- Public Member Functions inherited from yarp::os::PortReader
virtual ~PortReader ()
 Destructor.
 
virtual Type getReadType () const
 
- Public Member Functions inherited from yarp::os::PortWriter
virtual ~PortWriter ()
 Destructor.
 
virtual void onCompletion () const
 This is called when the port has finished all writing operations.
 
virtual void onCommencement () const
 This is called when the port is about to begin writing operations.
 
virtual yarp::os::Type getWriteType () const
 

Additional Inherited Members

- Static Public Member Functions inherited from yarp::os::Portable
static bool copyPortable (const PortWriter &writer, PortReader &reader)
 Copy one portable to another, via writing and reading.
 
- Protected Member Functions inherited from yarp::sig::PointCloudBase
 PointCloudBase ()=default
 
virtual void copyFromRawData (const char *dst, const char *source, std::vector< int > &recipe)
 
virtual std::vector< int > getComposition (int type_composite) const
 
virtual size_t pointType2Size (int type) const
 
virtual size_t getOffset (int type_composite, int type_basic) const
 
- Protected Attributes inherited from yarp::sig::PointCloudBase
yarp::sig::PointCloudNetworkHeader header
 

Detailed Description

template<class T>
class yarp::sig::PointCloud< T >

The PointCloud class.

Definition at line 20 of file PointCloud.h.

Constructor & Destructor Documentation

◆ PointCloud() [1/2]

template<class T >
yarp::sig::PointCloud< T >::PointCloud ( )
inline

PointCloud, default constructor.

Definition at line 40 of file PointCloud.h.

◆ PointCloud() [2/2]

template<class T >
template<class T1 >
yarp::sig::PointCloud< T >::PointCloud ( const PointCloud< T1 > &  alt)
inline

PointCloud, copy constructor.

Clones the content of another point cloud.

Parameters
altthe point cloud to clone.

Definition at line 52 of file PointCloud.h.

Member Function Documentation

◆ clear()

template<class T >
void yarp::sig::PointCloud< T >::clear ( )
virtual

Clear the data.

Definition at line 41 of file PointCloud.cpp.

◆ copy()

template<class T >
template<class T1 >
void yarp::sig::PointCloud< T >::copy ( const PointCloud< T1 > &  alt)
inline

Copy operator.

clones the content of another point cloud

Parameters
altthe point cloud to clone

Definition at line 198 of file PointCloud.h.

◆ dataSizeBytes()

template<class T >
size_t yarp::sig::PointCloud< T >::dataSizeBytes ( ) const
inlineoverridevirtual

Get the size of the data in terms of number of bytes.

Returns
the size of the data

Implements yarp::sig::PointCloudBase.

Definition at line 94 of file PointCloud.h.

◆ filterDataZ()

template<class T >
bool yarp::sig::PointCloud< T >::filterDataZ ( double  minZ = 0,
double  maxZ = std::numeric_limits<double>::infinity() 
)

Filter out points which are not included in the specified range.

Parameters
[minZ]minimum distance. Points with z smaller than minZ are removed.
[minZ]maximum distance. Points with z bugger than maxZ are removed.
Returns
true for success, false otherwise

Definition at line 199 of file PointCloud.cpp.

◆ fromBottle()

template<class T >
bool yarp::sig::PointCloud< T >::fromBottle ( const yarp::os::Bottle bt)

Populate the PointCloud from a yarp::os::Bottle.

Parameters
[in]bt,theyarp::os::Bottle to read from. It has to be formatted in the same way it is generated by the toBottle() method.
Returns
true for success, false otherwise

Definition at line 157 of file PointCloud.cpp.

◆ fromExternalPC()

template<class T >
void yarp::sig::PointCloud< T >::fromExternalPC ( const char *  source,
int  type,
size_t  width,
size_t  height,
bool  isDense = true 
)
virtual

Copy the content of an external PointCloud.

Parameters
source,pointerto the source data.
type,enumrepresenting the type of the source cloud.
width,widthof the source cloud.
height,heightof the source cloud.
isDense

Definition at line 49 of file PointCloud.cpp.

◆ getBottleTag()

template<class T >
int yarp::sig::PointCloud< T >::getBottleTag ( ) const
overridevirtual

Implements yarp::sig::PointCloudBase.

Definition at line 266 of file PointCloud.cpp.

◆ getRawData()

template<class T >
const char * yarp::sig::PointCloud< T >::getRawData ( ) const
inlineoverridevirtual

Get the pointer to the data.

Returns
the pointer to the data.

Implements yarp::sig::PointCloudBase.

Definition at line 74 of file PointCloud.h.

◆ operator()() [1/4]

template<class T >
T & yarp::sig::PointCloud< T >::operator() ( size_t  i)
inline

Obtain the point given by the index.

Parameters
i,index

Definition at line 130 of file PointCloud.h.

◆ operator()() [2/4]

template<class T >
const T & yarp::sig::PointCloud< T >::operator() ( size_t  i) const
inline

Obtain the point given by the index (const version).

Parameters
i,index

Definition at line 139 of file PointCloud.h.

◆ operator()() [3/4]

template<class T >
T & yarp::sig::PointCloud< T >::operator() ( size_t  u,
size_t  v 
)
inline

Obtain the point given by the (column, row) coordinates.

Only works on organized clouds (those that have height != 1).

Parameters
u,columncoordinate
v,rowcoordinate

Definition at line 110 of file PointCloud.h.

◆ operator()() [4/4]

template<class T >
const T & yarp::sig::PointCloud< T >::operator() ( size_t  u,
size_t  v 
) const
inline

Obtain the point given by the (column, row) coordinates (const version).

Only works on organized clouds (those that have height != 1).

Parameters
u,columncoordinate
v,rowcoordinate

Definition at line 121 of file PointCloud.h.

◆ operator+()

template<class T >
const PointCloud< T > yarp::sig::PointCloud< T >::operator+ ( const PointCloud< T > &  rhs)

Concatenate a point cloud to another cloud.

Parameters
rhsthe cloud to add to the current cloud
Returns
the new cloud as a concatenation of the current cloud and the new given cloud

Definition at line 293 of file PointCloud.cpp.

◆ operator+=()

template<class T >
PointCloud< T > & yarp::sig::PointCloud< T >::operator+= ( const PointCloud< T > &  rhs)

Concatenate a point cloud to the current cloud.

Parameters
rhsthe cloud to add to the current cloud
Returns
the new cloud as a concatenation of the current cloud and the new given cloud

Definition at line 272 of file PointCloud.cpp.

◆ operator=()

template<class T >
template<class T1 >
const PointCloud< T > & yarp::sig::PointCloud< T >::operator= ( const PointCloud< T1 > &  alt)
inline

Assignment operator.

Clones the content of another image.

Parameters
altthe image to clone

Definition at line 150 of file PointCloud.h.

◆ push_back()

template<class T >
void yarp::sig::PointCloud< T >::push_back ( const T &  pt)

Insert a new point in the cloud, at the end of the container.

Note
This breaks the organized structure of the cloud by setting the height to 1.
Parameters
[in]ptthe point to insert.

Definition at line 299 of file PointCloud.cpp.

◆ read()

template<class T >
bool yarp::sig::PointCloud< T >::read ( yarp::os::ConnectionReader reader)
overridevirtual

Read this object from a network connection.

Override this for your particular class.

Parameters
readeran interface to the network connection for reading
Returns
true iff the object is successfully read

Implements yarp::sig::PointCloudBase.

Definition at line 63 of file PointCloud.cpp.

◆ resize() [1/2]

template<class T >
void yarp::sig::PointCloud< T >::resize ( size_t  width)
virtual

Resize the PointCloud.

Note
This function resizes the point cloud and has the side effect of reducing the height to 1. Thus, by definition, the point cloud becomes unorganized.
Parameters
width.

Definition at line 33 of file PointCloud.cpp.

◆ resize() [2/2]

template<class T >
void yarp::sig::PointCloud< T >::resize ( size_t  width,
size_t  height 
)
virtual

Resize the PointCloud.

Parameters
width.
height.

Definition at line 25 of file PointCloud.cpp.

◆ size()

template<class T >
size_t yarp::sig::PointCloud< T >::size ( ) const
inlineoverridevirtual
Returns
the number of points of the PointCloud

Implements yarp::sig::PointCloudBase.

Definition at line 99 of file PointCloud.h.

◆ sortDataZ()

template<class T >
bool yarp::sig::PointCloud< T >::sortDataZ ( )

Rearranges the pointcloud data so that the points are ordered from the nearest to the farthest.

Returns
true for success, false otherwise

Definition at line 182 of file PointCloud.cpp.

◆ toBottle()

template<class T >
yarp::os::Bottle yarp::sig::PointCloud< T >::toBottle ( ) const

Generate a yarp::os::Bottle filled with the PointCloud data.

Returns
the yarp::os::Bottle generated

Definition at line 142 of file PointCloud.cpp.

◆ toString()

template<class T >
std::string yarp::sig::PointCloud< T >::toString ( int  precision = -1,
int  width = -1 
) const
virtual

Definition at line 119 of file PointCloud.cpp.

◆ wireSizeBytes()

template<class T >
size_t yarp::sig::PointCloud< T >::wireSizeBytes ( ) const
inlineoverridevirtual

Get the size of the data + the header in terms of number of bytes.

Returns
the size of the data sent through the network

Implements yarp::sig::PointCloudBase.

Definition at line 84 of file PointCloud.h.

◆ write()

template<class T >
bool yarp::sig::PointCloud< T >::write ( yarp::os::ConnectionWriter writer) const
overridevirtual

Write this object to a network connection.

Override this for your particular class. Be aware that depending on the nature of the connections a port has, and what protocol they use, and how efficient the YARP implementation is, this method may be called once, twice, or many times, as the result of a single call to Port::write

Parameters
writeran interface to the network connection for writing
Returns
true iff the object is successfully written

Implements yarp::sig::PointCloudBase.

Definition at line 112 of file PointCloud.cpp.


The documentation for this class was generated from the following files: