Typedefs | Functions
image_utilities.h File Reference
#include "ensenso_camera/ros2/namespace.h"
#include "ensenso_camera/ros2/time.h"
#include "ensenso_camera/ros2/sensor_msgs/camera_info.h"
#include "ensenso_camera/ros2/sensor_msgs/image.h"
#include <utility>
#include <string>
#include <vector>
#include "nxLib.h"
Include dependency graph for image_utilities.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Typedefs

using Image = sensor_msgs::msg::Image
 
using ImagePtr = sensor_msgs::msg::ImagePtr
 
using ImagePtrPair = std::pair< ImagePtr, ImagePtr >
 

Functions

ImagePtr depthImageFromNxLibNode (NxLibItem const &node, std::string const &frame, bool isFileCamera)
 
void fillDistortionParamsFromNxLib (NxLibItem const &distortionItem, sensor_msgs::msg::CameraInfoPtr const &info)
 
ImagePtr imageFromNxLibNode (NxLibItem const &node, std::string const &frame, bool isFileCamera)
 
std::vector< ImagePtrPairimagePairsFromNxLibNode (NxLibItem const &node, std::string const &frame, bool isFileCamera)
 
std::vector< ImagePtrimagesFromNxLibNode (NxLibItem const &node, std::string const &frame, bool isFileCamera)
 
ensenso::ros::Time timestampFromNxLibNode (NxLibItem const &node)
 

Typedef Documentation

◆ Image

using Image = sensor_msgs::msg::Image

Definition at line 15 of file image_utilities.h.

◆ ImagePtr

using ImagePtr = sensor_msgs::msg::ImagePtr

Definition at line 16 of file image_utilities.h.

◆ ImagePtrPair

using ImagePtrPair = std::pair<ImagePtr, ImagePtr>

Definition at line 17 of file image_utilities.h.

Function Documentation

◆ depthImageFromNxLibNode()

ImagePtr depthImageFromNxLibNode ( NxLibItem const &  node,
std::string const &  frame,
bool  isFileCamera 
)

Get the z-channel from the calculated point cloud and transform it into a sensor_msgs/Image depth image defined in REP 118 - depth images. The Image has a canonical format (z-values in Meters, float 1-channel image (TYPE_32FC1)).

Definition at line 182 of file image_utilities.cpp.

◆ fillDistortionParamsFromNxLib()

void fillDistortionParamsFromNxLib ( NxLibItem const &  distortionItem,
sensor_msgs::msg::CameraInfoPtr const &  info 
)

Gets the corresponding distortion parameters from the Item.

Definition at line 206 of file image_utilities.cpp.

◆ imageFromNxLibNode()

ImagePtr imageFromNxLibNode ( NxLibItem const &  node,
std::string const &  frame,
bool  isFileCamera 
)

Convert the given binary NxLib node to a ROS image message.

Definition at line 93 of file image_utilities.cpp.

◆ imagePairsFromNxLibNode()

std::vector<ImagePtrPair> imagePairsFromNxLibNode ( NxLibItem const &  node,
std::string const &  frame,
bool  isFileCamera 
)

Convert the given NxLib node to a set of image pairs.

This function supports different types of image nodes. When the node is an array, it will create an image pair for each entry of the array (this is the case when FlexView is enabled). Otherwise it creates an image pair from the left and right child nodes (as it is the case when FlexView is disabled or not supported by a camera).

Definition at line 136 of file image_utilities.cpp.

◆ imagesFromNxLibNode()

std::vector<ImagePtr> imagesFromNxLibNode ( NxLibItem const &  node,
std::string const &  frame,
bool  isFileCamera 
)

Convert the given NxLib node to a set of images.

This function supports different types of image nodes. When the node is an array, it will create an image for each entry of the array. Otherwise it creates an image from the child node.

Definition at line 155 of file image_utilities.cpp.

◆ timestampFromNxLibNode()

ensenso::ros::Time timestampFromNxLibNode ( NxLibItem const &  node)

Get the timestamp from an NxLib image node.

Definition at line 174 of file image_utilities.cpp.



ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46