Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | List of all members
nav2_costmap_2d::Image< T > Class Template Reference

Image with pixels of type T Сan own data, be a wrapper over some memory buffer, or refer to a fragment of another image Pixels of one row are stored continuity. But rows continuity is not guaranteed. The distance (number of elements of type T) from row(i) to row(i + 1) is equal to step() More...

#include <nav2_costmap_2d/include/nav2_costmap_2d/denoise/image.hpp>

Public Member Functions

 Image ()=default
 Create empty image.
 
 Image (size_t rows, size_t columns, T *data, size_t step)
 Create image referencing to a third-party buffer. More...
 
 Image (const Image &other)
 Create image referencing to the other Share image data between new and old object. Changing data in a new object will affect the given one and vice versa.
 
 Image (Image &&other) noexcept
 Create image from the other (move constructor)
 
size_t rows () const
 
size_t columns () const
 
bool empty () const
 
size_t step () const
 
T * row (size_t row)
 
const T * row (size_t row) const
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
 
template<class Functor >
void forEach (Functor &&fn)
 Read (and modify, if need) each pixel sequentially. More...
 
template<class Functor >
void forEach (Functor &&fn) const
 Read each pixel sequentially. More...
 
template<class TargetElement , class Converter >
void convert (Image< TargetElement > &target, Converter &&converter) const
 Convert each pixel to corresponding pixel of target using a custom function. More...
 

Detailed Description

template<class T>
class nav2_costmap_2d::Image< T >

Image with pixels of type T Сan own data, be a wrapper over some memory buffer, or refer to a fragment of another image Pixels of one row are stored continuity. But rows continuity is not guaranteed. The distance (number of elements of type T) from row(i) to row(i + 1) is equal to step()

Template Parameters
Ttype of pixel

Definition at line 32 of file image.hpp.

Constructor & Destructor Documentation

◆ Image()

template<class T >
nav2_costmap_2d::Image< T >::Image ( size_t  rows,
size_t  columns,
T *  data,
size_t  step 
)

Create image referencing to a third-party buffer.

Parameters
rowsnumber of image rows
columnsnumber of image columns
dataexisting memory buffer with size at least rows * columns
stepoffset from row(i) to row(i + 1) in memory buffer (number of elements of type T). offset = columns if rows are stored continuity

Definition at line 128 of file image.hpp.

Member Function Documentation

◆ columns()

template<class T >
size_t nav2_costmap_2d::Image< T >::columns ( ) const
inline
Returns
number of image columns

Definition at line 64 of file image.hpp.

Referenced by nav2_costmap_2d::Image< T >::convert().

Here is the caller graph for this function:

◆ convert()

template<class T >
template<class TargetElement , class Converter >
void nav2_costmap_2d::Image< T >::convert ( Image< TargetElement > &  target,
Converter &&  converter 
) const

Convert each pixel to corresponding pixel of target using a custom function.

The source and target must be the same size. For calculation of new target value the operation can use source value and an optionally current target value. This function call operation(this[i, j], target[i, j]) for each pixel where target[i, j] is mutable

Template Parameters
TargetElementtype of target pixel
Converterfunction object. Signature should be equivalent to the following: void fn(const T& src, TargetElement& trg)
Parameters
targetoutput image with TargetElement-type pixels
operationthe binary operation op is applied to pairs of pixels: first (const) from source and second (mutable) from target
Exceptions
std::logic_errorif the source and target of different sizes

Definition at line 184 of file image.hpp.

References nav2_costmap_2d::Image< T >::columns(), nav2_costmap_2d::Image< T >::row(), nav2_costmap_2d::Image< T >::rows(), and nav2_costmap_2d::Image< T >::step().

Referenced by nav2_common.launch.rewritten_yaml.RewrittenYaml::describe().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ empty()

template<class T >
bool nav2_costmap_2d::Image< T >::empty ( ) const
inline
Returns
true if image empty

Definition at line 67 of file image.hpp.

◆ forEach() [1/2]

template<class T >
template<class Functor >
void nav2_costmap_2d::Image< T >::forEach ( Functor &&  fn)

Read (and modify, if need) each pixel sequentially.

Template Parameters
Functorfunction object. Signature should be equivalent to the following: void fn(T& pixel) or void fn(const T& pixel)
Parameters
fna function that will be applied to each pixel in the image. Can modify image data

Definition at line 158 of file image.hpp.

References nav2_costmap_2d::Image< T >::forEach().

Referenced by nav2_costmap_2d::Image< T >::forEach().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ forEach() [2/2]

template<class T >
template<class Functor >
void nav2_costmap_2d::Image< T >::forEach ( Functor &&  fn) const

Read each pixel sequentially.

Template Parameters
Functorfunction object. Signature should be equivalent to the following: void fn(const T& pixel)
Parameters
fna function that will be applied to each pixel in the image

Definition at line 168 of file image.hpp.

◆ row()

template<class T >
T * nav2_costmap_2d::Image< T >::row ( size_t  row)
Returns
pointer to first pixel of row
Warning
If row >= rows(), the behavior is undefined

Definition at line 145 of file image.hpp.

References nav2_costmap_2d::Image< T >::row().

Referenced by nav2_costmap_2d::Image< T >::convert(), and nav2_costmap_2d::Image< T >::row().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ rows()

template<class T >
size_t nav2_costmap_2d::Image< T >::rows ( ) const
inline
Returns
number of image rows

Definition at line 61 of file image.hpp.

Referenced by nav2_costmap_2d::Image< T >::convert().

Here is the caller graph for this function:

◆ step()

template<class T >
size_t nav2_costmap_2d::Image< T >::step ( ) const
inline
Returns
offset (number of elements of type T) from row(i) to row(i + 1)

Definition at line 70 of file image.hpp.

Referenced by nav2_costmap_2d::Image< T >::convert().

Here is the caller graph for this function:

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