Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
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... | |
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()
T | type of pixel |
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.
rows | number of image rows |
columns | number of image columns |
data | existing memory buffer with size at least rows * columns |
step | offset from row(i) to row(i + 1) in memory buffer (number of elements of type T). offset = columns if rows are stored continuity |
|
inline |
Definition at line 64 of file image.hpp.
Referenced by nav2_costmap_2d::Image< T >::convert().
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
TargetElement | type of target pixel |
Converter | function object. Signature should be equivalent to the following: void fn(const T& src, TargetElement& trg) |
target | output image with TargetElement-type pixels |
operation | the binary operation op is applied to pairs of pixels: first (const) from source and second (mutable) from target |
std::logic_error | if 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().
|
inline |
void nav2_costmap_2d::Image< T >::forEach | ( | Functor && | fn | ) |
Read (and modify, if need) each pixel sequentially.
Functor | function object. Signature should be equivalent to the following: void fn(T& pixel) or void fn(const T& pixel) |
fn | a 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().
void nav2_costmap_2d::Image< T >::forEach | ( | Functor && | fn | ) | const |
T * nav2_costmap_2d::Image< T >::row | ( | size_t | row | ) |
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().
|
inline |
Definition at line 61 of file image.hpp.
Referenced by nav2_costmap_2d::Image< T >::convert().
|
inline |
Definition at line 70 of file image.hpp.
Referenced by nav2_costmap_2d::Image< T >::convert().