52 #include <sensor_msgs/Image.h> 
   54 #include <boost/format.hpp> 
   63   sensor_msgs::Image dst;
 
   64   dst.width = src.getWidth();
 
   65   dst.height = src.getHeight();
 
   67   dst.step = src.getWidth();
 
   68   dst.data.resize(dst.height * dst.step);
 
   69   memcpy(&dst.data[0], src.bitmap, dst.height * dst.step * 
sizeof(
unsigned char));
 
   74 vpImage<unsigned char> 
toVispImage(
const sensor_msgs::Image& src)
 
   83   vpImage<unsigned char> dst(src.height, src.width);
 
   85   if (src.encoding == 
MONO8)
 
   86     memcpy(dst.bitmap, &(src.data[0]), dst.getHeight() * src.step * 
sizeof(
unsigned char));
 
   87   else if (src.encoding == 
RGB8 || src.encoding == 
RGBA8 || src.encoding == 
BGR8 || src.encoding == 
BGRA8){
 
   89     unsigned cEnd = (src.encoding == 
RGBA8 || src.encoding == 
BGRA8) ? nc - 1 : nc;
 
   91     for (
unsigned i = 0; i < dst.getWidth(); ++i){
 
   92       for (
unsigned j = 0; j < dst.getHeight(); ++j){
 
   94         for (
unsigned c = 0; c < cEnd; ++c)
 
   95           acc += src.data[j * src.step + i * nc + c];
 
  112   vpImage<vpRGBa> dst(src.height, src.width);
 
  114   if (src.encoding == 
MONO8)
 
  115     for (
unsigned i = 0; i < dst.getWidth(); ++i){
 
  116       for (
unsigned j = 0; j < dst.getHeight(); ++j){
 
  118         dst[j][i] = vpRGBa(src.data[j * src.step + i],src.data[j * src.step + i],src.data[j * src.step + i]);
 
  124     for (
unsigned i = 0; i < dst.getWidth(); ++i){
 
  125       for (
unsigned j = 0; j < dst.getHeight(); ++j){
 
  126         dst[j][i] = vpRGBa(src.data[j * src.step + i * nc + 0],src.data[j * src.step + i * nc + 1],src.data[j * src.step + i * nc + 2]);
 
  134   sensor_msgs::Image dst;
 
  135   dst.width = src.getWidth();
 
  136   dst.height = src.getHeight();
 
  139   dst.step = src.getWidth()*nc;
 
  141   dst.data.resize(dst.height * dst.step);
 
  142   for (
unsigned i = 0; i < src.getWidth(); ++i){
 
  143     for (
unsigned j = 0; j < src.getHeight(); ++j){
 
  144       dst.data[j * dst.step + i * nc + 0] = src.bitmap[j * src.getWidth() + i].R;
 
  145       dst.data[j * dst.step + i * nc + 1] = src.bitmap[j * src.getWidth() + i].G;
 
  146       dst.data[j * dst.step + i * nc + 2] = src.bitmap[j * src.getWidth() + i].B;