Functions
image_utilities.h File Reference
#include <utility>
#include <string>
#include <vector>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
#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.

Functions

sensor_msgs::ImagePtr depthImageFromNxLibNode (NxLibItem const &node, std::string const &frame)
 
void fillDistortionParamsFromNxLib (NxLibItem const &distortionItem, sensor_msgs::CameraInfoPtr const &info)
 
sensor_msgs::ImagePtr imageFromNxLibNode (NxLibItem const &node, std::string const &frame)
 
std::vector< std::pair< sensor_msgs::ImagePtr, sensor_msgs::ImagePtr > > imagePairsFromNxLibNode (NxLibItem const &node, std::string const &frame)
 
std::vector< sensor_msgs::ImagePtr > imagesFromNxLibNode (NxLibItem const &node, std::string const &frame)
 
ros::Time timestampFromNxLibNode (NxLibItem const &node)
 

Function Documentation

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

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 167 of file image_utilities.cpp.

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

Gets the corresponding distortion parameters from the Item.

Definition at line 189 of file image_utilities.cpp.

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

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

Definition at line 90 of file image_utilities.cpp.

std::vector<std::pair<sensor_msgs::ImagePtr, sensor_msgs::ImagePtr> > imagePairsFromNxLibNode ( NxLibItem const &  node,
std::string const &  frame 
)

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 120 of file image_utilities.cpp.

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

Definition at line 140 of file image_utilities.cpp.

ros::Time timestampFromNxLibNode ( NxLibItem const &  node)

Get the timestamp from an NxLib image node.

Definition at line 159 of file image_utilities.cpp.



ensenso_camera
Author(s): Ensenso
autogenerated on Thu May 6 2021 02:50:06