00001 #include <cstring>
00002 #include <stdexcept>
00003
00004 #include <boost/format.hpp>
00005
00006 #include <tf/transform_datatypes.h>
00007
00008 #include <sensor_msgs/Image.h>
00009 #include <sensor_msgs/image_encodings.h>
00010 #include <sensor_msgs/distortion_models.h>
00011
00012 #include <visp/vpImage.h>
00013 #include <visp/vpTranslationVector.h>
00014 #include <visp/vpQuaternionVector.h>
00015
00016 #define protected public
00017 # include <visp/vpMbEdgeTracker.h>
00018 #undef protected
00019
00020 #define protected public
00021 # include <visp/vpMbKltTracker.h>
00022 #undef protected
00023
00024 #include "conversion.hh"
00025
00026 void rosImageToVisp(vpImage<unsigned char>& dst,
00027 const sensor_msgs::Image::ConstPtr& src)
00028 {
00029 using sensor_msgs::image_encodings::RGB8;
00030 using sensor_msgs::image_encodings::RGBA8;
00031 using sensor_msgs::image_encodings::BGR8;
00032 using sensor_msgs::image_encodings::BGRA8;
00033 using sensor_msgs::image_encodings::MONO8;
00034 using sensor_msgs::image_encodings::MONO16;
00035 using sensor_msgs::image_encodings::numChannels;
00036
00037
00038 if (src->width != dst.getWidth() || src->height != dst.getHeight())
00039 {
00040 ROS_INFO
00041 ("dst is %dx%d but src size is %dx%d, resizing.",
00042 src->width, src->height,
00043 dst.getWidth (), dst.getHeight ());
00044 dst.resize (src->height, src->width);
00045 }
00046
00047 if(src->encoding == MONO8)
00048 memcpy(dst.bitmap,
00049 &src->data[0],
00050 dst.getHeight () * src->step * sizeof(unsigned char));
00051 else if(src->encoding == RGB8 || src->encoding == RGBA8
00052 || src->encoding == BGR8 || src->encoding == BGRA8)
00053 {
00054 unsigned nc = numChannels(src->encoding);
00055 unsigned cEnd =
00056 (src->encoding == RGBA8 || src->encoding == BGRA8) ? nc - 1 : nc;
00057
00058 for(unsigned i = 0; i < dst.getWidth (); ++i)
00059 for(unsigned j = 0; j < dst.getHeight (); ++j)
00060 {
00061 int acc = 0;
00062 for(unsigned c = 0; c < cEnd; ++c)
00063 acc += src->data[j * src->step + i * nc + c];
00064 dst[j][i] = acc / nc;
00065 }
00066 }
00067 else
00068 {
00069 boost::format fmt("bad encoding '%1'");
00070 fmt % src->encoding;
00071 throw std::runtime_error(fmt.str());
00072 }
00073 }
00074
00075 void vispImageToRos(sensor_msgs::Image& dst,
00076 const vpImage<unsigned char>& src)
00077 {
00078 dst.width = src.getWidth();
00079 dst.height = src.getHeight();
00080 dst.encoding = sensor_msgs::image_encodings::MONO8;
00081 dst.step = src.getWidth();
00082 dst.data.resize(dst.height * dst.step);
00083 for(unsigned i = 0; i < src.getWidth (); ++i)
00084 for(unsigned j = 0; j < src.getHeight (); ++j)
00085 dst.data[j * dst.step + i] = src[j][i];
00086 }
00087
00088 void vpHomogeneousMatrixToTransform(geometry_msgs::Transform& dst,
00089 const vpHomogeneousMatrix& src)
00090 {
00091 vpQuaternionVector quaternion;
00092 src.extract(quaternion);
00093
00094 dst.translation.x = src[0][3];
00095 dst.translation.y = src[1][3];
00096 dst.translation.z = src[2][3];
00097
00098 dst.rotation.x = quaternion.x();
00099 dst.rotation.y = quaternion.y();
00100 dst.rotation.z = quaternion.z();
00101 dst.rotation.w = quaternion.w();
00102 }
00103
00104 void transformToVpHomogeneousMatrix(vpHomogeneousMatrix& dst,
00105 const geometry_msgs::Transform& src)
00106 {
00107 vpTranslationVector translation(src.translation.x,src.translation.y,src.translation.z);
00108 vpQuaternionVector quaternion(src.rotation.x,src.rotation.y,src.rotation.z,src.rotation.w);
00109 dst.buildFrom(translation, quaternion);
00110 }
00111
00112 void transformToVpHomogeneousMatrix(vpHomogeneousMatrix& dst,
00113 const geometry_msgs::Pose& src)
00114 {
00115 vpQuaternionVector quaternion
00116 (src.orientation.x, src.orientation.y, src.orientation.z,
00117 src.orientation.w);
00118 vpRotationMatrix rotation(quaternion);
00119
00120
00121 for(unsigned i = 0; i < 3; ++i)
00122 for(unsigned j = 0; j < 3; ++j)
00123 dst[i][j] = rotation[i][j];
00124
00125
00126 dst[0][3] = src.position.x;
00127 dst[1][3] = src.position.y;
00128 dst[2][3] = src.position.z;
00129 }
00130
00131 void transformToVpHomogeneousMatrix(vpHomogeneousMatrix& dst,
00132 const tf::Transform& src)
00133 {
00134
00135 for(unsigned i = 0; i < 3; ++i)
00136 for(unsigned j = 0; j < 3; ++j)
00137 dst[i][j] = src.getBasis ()[i][j];
00138
00139
00140 for (unsigned i = 0; i < 3; ++i)
00141 dst[i][3] = src.getOrigin ()[i];
00142 dst[3][3] = 1.;
00143 }
00144
00145 void convertModelBasedSettingsConfigToVpMe(const visp_tracker::ModelBasedSettingsConfig& config,
00146 vpMe& moving_edge,
00147 vpMbTracker* tracker)
00148 {
00149 vpMbEdgeTracker* t = dynamic_cast<vpMbEdgeTracker*>(tracker);
00150
00151 moving_edge.mask_size = config.mask_size;
00152 moving_edge.n_mask = config.n_mask;
00153 moving_edge.range = config.range;
00154 moving_edge.threshold = config.threshold;
00155 moving_edge.mu1 = config.mu1;
00156 moving_edge.mu2 = config.mu2;
00157 moving_edge.sample_step = config.sample_step;
00158 moving_edge.ntotal_sample = config.ntotal_sample;
00159
00160 moving_edge.strip = config.strip;
00161 moving_edge.min_samplestep = config.min_samplestep;
00162 moving_edge.aberration = config.aberration;
00163 moving_edge.init_aberration = config.init_aberration;
00164
00165 t->setLambda(config.lambda);
00166 t->setFirstThreshold(config.first_threshold);
00167
00168
00169 moving_edge.initMask();
00170
00171 t->setMovingEdge(moving_edge);
00172 }
00173
00174 void convertVpMeToModelBasedSettingsConfig(const vpMe& moving_edge,
00175 const vpMbTracker* tracker,
00176 visp_tracker::ModelBasedSettingsConfig& config)
00177 {
00178 const vpMbEdgeTracker* t = dynamic_cast<const vpMbEdgeTracker*>(tracker);
00179
00180 config.mask_size = moving_edge.mask_size;
00181 config.n_mask = moving_edge.n_mask;
00182 config.range = moving_edge.range;
00183 config.threshold = moving_edge.threshold;
00184 config.mu1 = moving_edge.mu1;
00185 config.mu2 = moving_edge.mu2;
00186 config.sample_step = moving_edge.sample_step;
00187 config.ntotal_sample = moving_edge.ntotal_sample;
00188
00189 config.strip = moving_edge.strip;
00190 config.min_samplestep = moving_edge.min_samplestep;
00191 config.aberration = moving_edge.aberration;
00192 config.init_aberration = moving_edge.init_aberration;
00193
00194 config.lambda = t->lambda;
00195 config.first_threshold = t->percentageGdPt;
00196 }
00197
00198 void convertModelBasedSettingsConfigToVpKltOpencv(const visp_tracker::ModelBasedSettingsConfig& config,
00199 vpKltOpencv& klt,
00200 vpMbTracker* tracker)
00201 {
00202 vpMbKltTracker* t = dynamic_cast<vpMbKltTracker*>(tracker);
00203
00204 klt.setMaxFeatures(config.max_features);
00205 klt.setWindowSize(config.window_size);
00206 klt.setQuality(config.quality);
00207 klt.setMinDistance(config.min_distance);
00208 klt.setHarrisFreeParameter(config.harris);
00209 klt.setBlockSize(config.size_block);
00210 klt.setPyramidLevels(config.pyramid_lvl);
00211
00212 t->setAngleAppear(vpMath::rad(config.angle_appear));
00213 t->setAngleDisappear(vpMath::rad(config.angle_disappear));
00214 t->setMaskBorder((unsigned)config.mask_border);
00215
00216 t->setKltOpencv(klt);
00217 }
00218
00219 void convertVpKltOpencvToModelBasedSettingsConfig(const vpKltOpencv& klt,
00220 const vpMbTracker* tracker,
00221 visp_tracker::ModelBasedSettingsConfig& config)
00222 {
00223 const vpMbKltTracker* t = dynamic_cast<const vpMbKltTracker*>(tracker);
00224
00225 config.max_features = klt.getMaxFeatures();
00226 config.window_size = klt.getWindowSize();
00227 config.quality = klt.getQuality();
00228 config.min_distance = klt.getMinDistance();
00229 config.harris = klt.getHarrisFreeParameter();
00230 config.size_block = klt.getBlockSize();
00231 config.pyramid_lvl = klt.getPyramidLevels();
00232
00233 config.angle_appear = vpMath::deg(t->angleAppears);
00234 config.angle_disappear = vpMath::deg(t->angleDisappears);
00235 config.mask_border = t->maskBorder;
00236 }
00237
00238 void convertVpMeToInitRequest(const vpMe& moving_edge,
00239 const vpMbTracker* tracker,
00240 visp_tracker::Init& srv)
00241 {
00242 const vpMbEdgeTracker* t = dynamic_cast<const vpMbEdgeTracker*>(tracker);
00243
00244 srv.request.moving_edge.mask_size = moving_edge.mask_size;
00245 srv.request.moving_edge.n_mask = moving_edge.n_mask;
00246 srv.request.moving_edge.range = moving_edge.range;
00247 srv.request.moving_edge.threshold = moving_edge.threshold;
00248 srv.request.moving_edge.mu1 = moving_edge.mu1;
00249 srv.request.moving_edge.mu2 = moving_edge.mu2;
00250 srv.request.moving_edge.sample_step = moving_edge.sample_step;
00251 srv.request.moving_edge.ntotal_sample = moving_edge.ntotal_sample;
00252
00253 srv.request.moving_edge.strip = moving_edge.strip;
00254 srv.request.moving_edge.min_samplestep = moving_edge.min_samplestep;
00255 srv.request.moving_edge.aberration = moving_edge.aberration;
00256 srv.request.moving_edge.init_aberration = moving_edge.init_aberration;
00257
00258 srv.request.moving_edge.lambda = t->lambda;
00259 srv.request.moving_edge.first_threshold = t->percentageGdPt;
00260 }
00261
00262 void convertInitRequestToVpMe(const visp_tracker::Init::Request& req,
00263 vpMbTracker* tracker,
00264 vpMe& moving_edge)
00265 {
00266 vpMbEdgeTracker* t = dynamic_cast<vpMbEdgeTracker*>(tracker);
00267
00268 moving_edge.mask_size = req.moving_edge.mask_size;
00269 moving_edge.n_mask = req.moving_edge.n_mask;
00270 moving_edge.range = req.moving_edge.range;
00271 moving_edge.threshold = req.moving_edge.threshold;
00272 moving_edge.mu1 = req.moving_edge.mu1;
00273 moving_edge.mu2 = req.moving_edge.mu2;
00274 moving_edge.sample_step = req.moving_edge.sample_step;
00275 moving_edge.ntotal_sample = req.moving_edge.ntotal_sample;
00276
00277 moving_edge.strip = req.moving_edge.strip;
00278 moving_edge.min_samplestep = req.moving_edge.min_samplestep;
00279 moving_edge.aberration = req.moving_edge.aberration;
00280 moving_edge.init_aberration = req.moving_edge.init_aberration;
00281
00282 t->setLambda(req.moving_edge.lambda);
00283 t->setFirstThreshold(req.moving_edge.first_threshold);
00284 }
00285
00286 void convertVpKltOpencvToInitRequest(const vpKltOpencv& klt,
00287 const vpMbTracker* tracker,
00288 visp_tracker::Init& srv)
00289 {
00290 const vpMbKltTracker* t = dynamic_cast<const vpMbKltTracker*>(tracker);
00291
00292 srv.request.klt_param.max_features = klt.getMaxFeatures();
00293 srv.request.klt_param.window_size = klt.getWindowSize();
00294 srv.request.klt_param.quality = klt.getQuality();
00295 srv.request.klt_param.min_distance = klt.getMinDistance();
00296 srv.request.klt_param.harris = klt.getHarrisFreeParameter();
00297 srv.request.klt_param.size_block = klt.getBlockSize();
00298 srv.request.klt_param.pyramid_lvl = klt.getPyramidLevels();
00299
00300 srv.request.klt_param.angle_appear = vpMath::deg(t->angleAppears);
00301 srv.request.klt_param.angle_disappear = vpMath::deg(t->angleDisappears);
00302 srv.request.klt_param.mask_border = t->maskBorder;
00303 }
00304
00305 void convertInitRequestToVpKltOpencv(const visp_tracker::Init::Request& req,
00306 vpMbTracker* tracker,
00307 vpKltOpencv& klt)
00308 {
00309 vpMbKltTracker* t = dynamic_cast<vpMbKltTracker*>(tracker);
00310
00311 klt.setMaxFeatures(req.klt_param.max_features);
00312 klt.setWindowSize(req.klt_param.window_size);
00313 klt.setQuality(req.klt_param.quality);
00314 klt.setMinDistance(req.klt_param.min_distance);
00315 klt.setHarrisFreeParameter(req.klt_param.harris);
00316 klt.setBlockSize(req.klt_param.size_block);
00317 klt.setPyramidLevels(req.klt_param.pyramid_lvl);
00318
00319 t->setAngleAppear(vpMath::rad(req.klt_param.angle_appear));
00320 t->setAngleDisappear(vpMath::rad(req.klt_param.angle_disappear));
00321 t->setMaskBorder((unsigned)req.klt_param.mask_border);
00322 }
00323
00324 void initializeVpCameraFromCameraInfo(vpCameraParameters& cam,
00325 sensor_msgs::CameraInfoConstPtr info)
00326 {
00327 if (!info)
00328 throw std::runtime_error ("missing camera calibration data");
00329
00330
00331
00332 if (info->K.size() != 3 * 3 || info->K[0] == 0.)
00333 throw std::runtime_error ("uncalibrated camera");
00334
00335
00336 if (!info || info->P.size() != 3 * 4)
00337 throw std::runtime_error
00338 ("camera calibration P matrix has an incorrect size");
00339
00340 if (info->distortion_model.empty ())
00341 {
00342 const double& px = info->K[0 * 3 + 0];
00343 const double& py = info->K[1 * 3 + 1];
00344 const double& u0 = info->K[0 * 3 + 2];
00345 const double& v0 = info->K[1 * 3 + 2];
00346 cam.initPersProjWithoutDistortion(px, py, u0, v0);
00347 return;
00348 }
00349
00350 if (info->distortion_model == sensor_msgs::distortion_models::PLUMB_BOB)
00351 {
00352 const double& px = info->P[0 * 4 + 0];
00353 const double& py = info->P[1 * 4 + 1];
00354 const double& u0 = info->P[0 * 4 + 2];
00355 const double& v0 = info->P[1 * 4 + 2];
00356 cam.initPersProjWithoutDistortion(px, py, u0, v0);
00357 return;
00358 }
00359
00360 throw std::runtime_error ("unsupported distortion model");
00361 }