#include "rgbd/ros/conversions.h"
#include <boost/iostreams/filtering_streambuf.hpp>
#include <boost/iostreams/copy.hpp>
#include <boost/iostreams/filter/gzip.hpp>
#include <boost/iostreams/filter/zstd.hpp>
#include <cv_bridge/cv_bridge.h>
#include <geolib/sensors/DepthCamera.h>
#include <geolib/ros/msg_conversions.h>
#include <opencv2/core/core.hpp>
#include <opencv2/imgcodecs.hpp>
#include <ros/console.h>
#include <sensor_msgs/distortion_models.h>
#include <tue/serialization/conversions.h>
#include <sstream>
#include "rgbd/serialization.h"
Go to the source code of this file.
|
bool | rgbd::convert (const cv::Mat &image, const geo::DepthCamera &cam_model, sensor_msgs::Image &image_msg, sensor_msgs::CameraInfo &cam_model_msg) |
| Convert either a rgb or depth image to image and CameraInfo message. Also rectifies the image. More...
|
|
bool | rgbd::convert (const cv::Mat &image, sensor_msgs::Image &image_msg) |
| Convert either a rgb or depth image, cv::Mat, to an image message. More...
|
|
bool | rgbd::convert (const rgbd_msgs::RGBDConstPtr &msg, rgbd::Image *&image) |
| Convert rgbd message to an Image. More...
|
|