#include <cv_bridge/cv_bridge.h>
#include "ensenso_camera/image_utilities.h"
#include <string>
#include <utility>
#include <vector>
#include <ros/ros.h>
#include <sensor_msgs/image_encodings.h>
Go to the source code of this file.
Functions | |
sensor_msgs::ImagePtr | depthImageFromNxLibNode (NxLibItem const &node, std::string const &frame) |
std::string | imageEncoding (bool isFloat, int channels, int bytesPerElement) |
sensor_msgs::ImagePtr | imageFromNxLibNode (NxLibItem const &node, std::string const &frame) |
std::pair< sensor_msgs::ImagePtr, sensor_msgs::ImagePtr > | imagePairFromNxLibNode (const NxLibItem &node, std::string const &frame) |
std::vector< std::pair< sensor_msgs::ImagePtr, sensor_msgs::ImagePtr > > | imagesFromNxLibNode (const NxLibItem &node, std::string const &frame) |
ros::Time | timestampFromNxLibNode (const NxLibItem &node) |
Variables | |
double const | NXLIB_TIMESTAMP_OFFSET = 11644473600 |
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 147 of file image_utilities.cpp.
std::string imageEncoding | ( | bool | isFloat, |
int | channels, | ||
int | bytesPerElement | ||
) |
Definition at line 14 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 89 of file image_utilities.cpp.
std::pair<sensor_msgs::ImagePtr, sensor_msgs::ImagePtr> imagePairFromNxLibNode | ( | const NxLibItem & | node, |
std::string const & | frame | ||
) |
Definition at line 110 of file image_utilities.cpp.
std::vector<std::pair<sensor_msgs::ImagePtr, sensor_msgs::ImagePtr> > imagesFromNxLibNode | ( | 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 119 of file image_utilities.cpp.
ros::Time timestampFromNxLibNode | ( | NxLibItem const & | node | ) |
Get the timestamp from an NxLib image node.
Definition at line 139 of file image_utilities.cpp.
double const NXLIB_TIMESTAMP_OFFSET = 11644473600 |
Definition at line 12 of file image_utilities.cpp.