53 #ifndef __VISP_BRIDGE_IMAGE_H__ 54 #define __VISP_BRIDGE_IMAGE_H__ 56 #include "sensor_msgs/Image.h" 57 #include "visp/vpImage.h" 58 #include "visp/vpRGBa.h" 73 vpImage<unsigned char>
toVispImage(
const sensor_msgs::Image& src);
vpImage< unsigned char > toVispImage(const sensor_msgs::Image &src)
Converts a sensor_msgs::Image to a ViSP image (vpImage). Only works for greyscale images...
sensor_msgs::Image toSensorMsgsImage(const vpImage< unsigned char > &src)
Converts a ViSP image (vpImage) to a sensor_msgs::Image. Only works for greyscale images...
vpImage< vpRGBa > toVispImageRGBa(const sensor_msgs::Image &src)