image_utilities.h
Go to the documentation of this file.
1 #pragma once
2 
5 
8 
9 #include <utility>
10 #include <string>
11 #include <vector>
12 
13 #include "nxLib.h"
14 
17 using ImagePtrPair = std::pair<ImagePtr, ImagePtr>;
18 
22 ImagePtr imageFromNxLibNode(NxLibItem const& node, std::string const& frame, bool isFileCamera);
23 
31 std::vector<ImagePtrPair> imagePairsFromNxLibNode(NxLibItem const& node, std::string const& frame, bool isFileCamera);
32 
39 std::vector<ImagePtr> imagesFromNxLibNode(NxLibItem const& node, std::string const& frame, bool isFileCamera);
40 
44 ensenso::ros::Time timestampFromNxLibNode(NxLibItem const& node);
45 
50 ImagePtr depthImageFromNxLibNode(NxLibItem const& node, std::string const& frame, bool isFileCamera);
51 
55 void fillDistortionParamsFromNxLib(NxLibItem const& distortionItem, sensor_msgs::msg::CameraInfoPtr const& info);
::ros::Time Time
Definition: time.h:67
std::vector< ImagePtr > imagesFromNxLibNode(NxLibItem const &node, std::string const &frame, bool isFileCamera)
ImagePtr depthImageFromNxLibNode(NxLibItem const &node, std::string const &frame, bool isFileCamera)
std::pair< ImagePtr, ImagePtr > ImagePtrPair
void fillDistortionParamsFromNxLib(NxLibItem const &distortionItem, sensor_msgs::msg::CameraInfoPtr const &info)
sensor_msgs::msg::Image Image
ensenso::ros::Time timestampFromNxLibNode(NxLibItem const &node)
ImagePtr imageFromNxLibNode(NxLibItem const &node, std::string const &frame, bool isFileCamera)
std::vector< ImagePtrPair > imagePairsFromNxLibNode(NxLibItem const &node, std::string const &frame, bool isFileCamera)
sensor_msgs::msg::ImagePtr ImagePtr


ensenso_camera
Author(s): Ensenso
autogenerated on Sat Jun 3 2023 02:17:04