rgbd
Classes | Typedefs | Enumerations | Functions | Variables
rgbd Namespace Reference

Classes

struct  BufferHeader
 
class  Client
 Client which uses the interfaces of ClientRGBD and ClientSHM. More...
 
class  ClientRGBD
 Client which subscribes to RGBD topic. More...
 
class  ClientROS
 Client which subscribes to regular ROS image topics. More...
 
class  ClientROSBase
 Client which subscribes to regular ROS image topics. More...
 
class  ClientRosNodelet
 
class  ClientSHM
 Client which uses shared memory, requires a server on the same machine. More...
 
class  Image
 
class  ROSToRGBDNodelet
 
class  Server
 Server which provides interfaces of ServerRGBD and ServerSHM. More...
 
class  ServerRGBD
 Server which provides RGBD topic and RGBD service. More...
 
class  ServerROS
 Server which publishes ROS rgb image, depth image and pointcloud messages. More...
 
class  ServerSHM
 Server which uses shared memory, this only works for clients on the same machine. More...
 
class  View
 

Typedefs

typedef std::shared_ptr< const ImageImageConstPtr
 
typedef std::shared_ptr< ImageImagePtr
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > RGBDApproxPolicy
 

Enumerations

enum  CameraModelType { CAMERA_MODEL_NONE = 0, CAMERA_MODEL_PINHOLE = 1 }
 
enum  DepthStorageType { DEPTH_STORAGE_NONE = 0, DEPTH_STORAGE_LOSSLESS = 1, DEPTH_STORAGE_PNG = 2 }
 
enum  RGBStorageType { RGB_STORAGE_NONE = 0, RGB_STORAGE_LOSSLESS = 1, RGB_STORAGE_JPG = 2 }
 

Functions

bool 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 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 convert (const rgbd_msgs::RGBDConstPtr &msg, rgbd::Image *&image)
 Convert rgbd message to an Image. More...
 
bool deserialize (tue::serialization::InputArchive &a, Image &image)
 
rgbd::Image generateRandomImage ()
 
std::string get_hostname ()
 Get the hostname of the current machine. More...
 
std::ostreamoperator<< (std::ostream &out, const rgbd::Image &image)
 
void pubHostnameThreadFunc (ros::NodeHandle &nh, const std::string server_name, const std::string hostname, const float frequency)
 
double randomDouble (double min=0, double max=1000000)
 
std::string randomString (size_t length=10)
 
bool serialize (const Image &image, tue::serialization::OutputArchive &a, RGBStorageType rgb_type=RGB_STORAGE_JPG, DepthStorageType depth_type=DEPTH_STORAGE_PNG)
 

Variables

const static int SERIALIZATION_VERSION = 2
 

Detailed Description

This client listens to RGBD messages on a single topic or via shared memory, provides rgbd::Image.

This client listens to RGBD messages on a single topic directing rgbd::Image.

This client converts rgb/depth/camera_info into RGBD::Image

Typedef Documentation

◆ ImageConstPtr

Definition at line 10 of file types.h.

◆ ImagePtr

Definition at line 8 of file types.h.

◆ RGBDApproxPolicy

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> rgbd::RGBDApproxPolicy

Definition at line 27 of file client_ros_base.h.

Enumeration Type Documentation

◆ CameraModelType

Enumerator
CAMERA_MODEL_NONE 
CAMERA_MODEL_PINHOLE 

Definition at line 23 of file image.h.

◆ DepthStorageType

Enumerator
DEPTH_STORAGE_NONE 
DEPTH_STORAGE_LOSSLESS 
DEPTH_STORAGE_PNG 

Definition at line 36 of file image.h.

◆ RGBStorageType

Enumerator
RGB_STORAGE_NONE 
RGB_STORAGE_LOSSLESS 
RGB_STORAGE_JPG 

Definition at line 29 of file image.h.

Function Documentation

◆ convert() [1/3]

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.

Parameters
imagergb or depth image
cam_modelCamera model
image_msgImage message
cam_model_msgCameraInfo message
Returns

Definition at line 51 of file conversions.cpp.

◆ convert() [2/3]

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.

Parameters
imageimage matrix
image_msgimage message to fill
Returns
success

Definition at line 32 of file conversions.cpp.

◆ convert() [3/3]

bool rgbd::convert ( const rgbd_msgs::RGBDConstPtr &  msg,
rgbd::Image *&  image 
)

Convert rgbd message to an Image.

Parameters
msgpointer to const rgbd message
imageraw pointer to an Image. In case it is a nullptr, a new instance will be created.
Returns
success

Definition at line 88 of file conversions.cpp.

◆ deserialize()

bool rgbd::deserialize ( tue::serialization::InputArchive a,
Image image 
)

Definition at line 174 of file serialization.cpp.

◆ generateRandomImage()

rgbd::Image rgbd::generateRandomImage ( )

Definition at line 36 of file test_utils.h.

◆ get_hostname()

std::string rgbd::get_hostname ( )

Get the hostname of the current machine.

Returns
hostname or an empty string in case of any error

Definition at line 13 of file utility.cpp.

◆ operator<<()

std::ostream& rgbd::operator<< ( std::ostream out,
const rgbd::Image image 
)

Definition at line 106 of file image.cpp.

◆ pubHostnameThreadFunc()

void rgbd::pubHostnameThreadFunc ( ros::NodeHandle &  nh,
const std::string  server_name,
const std::string  hostname,
const float  frequency 
)

Definition at line 154 of file server_shm.cpp.

◆ randomDouble()

double rgbd::randomDouble ( double  min = 0,
double  max = 1000000 
)

Definition at line 29 of file test_utils.h.

◆ randomString()

std::string rgbd::randomString ( size_t  length = 10)

Definition at line 17 of file test_utils.h.

◆ serialize()

bool rgbd::serialize ( const Image image,
tue::serialization::OutputArchive a,
RGBStorageType  rgb_type = RGB_STORAGE_JPG,
DepthStorageType  depth_type = DEPTH_STORAGE_PNG 
)

Definition at line 23 of file serialization.cpp.

Variable Documentation

◆ SERIALIZATION_VERSION

const static int rgbd::SERIALIZATION_VERSION = 2
static

Definition at line 15 of file serialization.cpp.