00001 #include <cstring>
00002 #include <stdexcept>
00003
00004 #include <boost/format.hpp>
00005
00006 #include <LinearMath/btMatrix3x3.h>
00007 #include <LinearMath/btQuaternion.h>
00008
00009 #include <sensor_msgs/Image.h>
00010 #include <sensor_msgs/image_encodings.h>
00011
00012
00013 #include <visp/vpImage.h>
00014
00015 #define protected public
00016 # include <visp/vpMbEdgeTracker.h>
00017 #undef protected
00018
00019 #include "conversion.hh"
00020
00021 void rosImageToVisp(vpImage<unsigned char>& dst,
00022 const sensor_msgs::Image::ConstPtr& src)
00023 {
00024 using sensor_msgs::image_encodings::RGB8;
00025 using sensor_msgs::image_encodings::RGBA8;
00026 using sensor_msgs::image_encodings::BGR8;
00027 using sensor_msgs::image_encodings::BGRA8;
00028 using sensor_msgs::image_encodings::MONO8;
00029 using sensor_msgs::image_encodings::MONO16;
00030 using sensor_msgs::image_encodings::numChannels;
00031
00032
00033 if (src->width != dst.getWidth() || src->height != dst.getHeight())
00034 {
00035 ROS_INFO
00036 ("dst is %dx%d but src size is %dx%d, resizing.",
00037 src->width, src->height,
00038 dst.getWidth (), dst.getHeight ());
00039 dst.resize (src->height, src->width);
00040 }
00041
00042 if(src->encoding == MONO8)
00043 memcpy(dst.bitmap,
00044 &src->data[0],
00045 dst.getHeight () * src->step * sizeof(unsigned char));
00046 else if(src->encoding == RGB8 || src->encoding == RGBA8
00047 || src->encoding == BGR8 || src->encoding == BGRA8)
00048 {
00049 unsigned nc = numChannels(src->encoding);
00050 unsigned cEnd =
00051 (src->encoding == RGBA8 || src->encoding == BGRA8) ? nc - 1 : nc;
00052
00053 for(unsigned i = 0; i < dst.getWidth (); ++i)
00054 for(unsigned j = 0; j < dst.getHeight (); ++j)
00055 {
00056 int acc = 0;
00057 for(unsigned c = 0; c < cEnd; ++c)
00058 acc += src->data[j * src->step + i * nc + c];
00059 dst[j][i] = acc / nc;
00060 }
00061 }
00062 else
00063 {
00064 boost::format fmt("bad encoding '%1'");
00065 fmt % src->encoding;
00066 throw std::runtime_error(fmt.str());
00067 }
00068 }
00069
00070 void vispImageToRos(sensor_msgs::Image& dst,
00071 const vpImage<unsigned char>& src)
00072 {
00073 dst.width = src.getWidth();
00074 dst.height = src.getHeight();
00075 dst.encoding = sensor_msgs::image_encodings::MONO8;
00076 dst.step = src.getWidth();
00077 dst.data.resize(dst.height * dst.step);
00078 for(unsigned i = 0; i < src.getWidth (); ++i)
00079 for(unsigned j = 0; j < src.getHeight (); ++j)
00080 dst.data[j * dst.step + i] = src[j][i];
00081 }
00082
00083 void vpHomogeneousMatrixToTransform(geometry_msgs::Transform& dst,
00084 const vpHomogeneousMatrix& src)
00085 {
00086 btMatrix3x3 rotation;
00087 btQuaternion quaternion;
00088 for(unsigned i = 0; i < 3; ++i)
00089 for(unsigned j = 0; j < 3; ++j)
00090 rotation[i][j] = src[i][j];
00091 rotation.getRotation(quaternion);
00092
00093 dst.translation.x = src[0][3];
00094 dst.translation.y = src[1][3];
00095 dst.translation.z = src[2][3];
00096
00097 dst.rotation.x = quaternion.x();
00098 dst.rotation.y = quaternion.y();
00099 dst.rotation.z = quaternion.z();
00100 dst.rotation.w = quaternion.w();
00101 }
00102
00103 void transformToVpHomogeneousMatrix(vpHomogeneousMatrix& dst,
00104 const geometry_msgs::Transform& src)
00105 {
00106 btQuaternion quaternion
00107 (src.rotation.x, src.rotation.y, src.rotation.z, src.rotation.w);
00108 btMatrix3x3 rotation(quaternion);
00109
00110
00111 for(unsigned i = 0; i < 3; ++i)
00112 for(unsigned j = 0; j < 3; ++j)
00113 dst[i][j] = rotation[i][j];
00114
00115
00116 dst[0][3] = src.translation.x;
00117 dst[1][3] = src.translation.y;
00118 dst[2][3] = src.translation.z;
00119 }
00120
00121 void convertMovingEdgeConfigToVpMe(const visp_tracker::MovingEdgeConfig& config,
00122 vpMe& moving_edge,
00123 vpMbEdgeTracker& tracker)
00124 {
00125 moving_edge.mask_size = config.mask_size;
00126 moving_edge.n_mask = config.n_mask;
00127 moving_edge.range = config.range;
00128 moving_edge.threshold = config.threshold;
00129 moving_edge.mu1 = config.mu1;
00130 moving_edge.mu2 = config.mu2;
00131 moving_edge.sample_step = config.sample_step;
00132 moving_edge.ntotal_sample = config.ntotal_sample;
00133
00134 moving_edge.strip = config.strip;
00135 moving_edge.min_samplestep = config.min_samplestep;
00136 moving_edge.aberration = config.aberration;
00137 moving_edge.init_aberration = config.init_aberration;
00138
00139 tracker.setLambda(config.lambda);
00140 tracker.setFirstThreshold(config.first_threshold);
00141 }
00142
00143 void convertVpMeToMovingEdgeConfig(const vpMe& moving_edge,
00144 const vpMbEdgeTracker& tracker,
00145 visp_tracker::MovingEdgeConfig& config)
00146 {
00147 config.mask_size = moving_edge.mask_size;
00148 config.n_mask = moving_edge.n_mask;
00149 config.range = moving_edge.range;
00150 config.threshold = moving_edge.threshold;
00151 config.mu1 = moving_edge.mu1;
00152 config.mu2 = moving_edge.mu2;
00153 config.sample_step = moving_edge.sample_step;
00154 config.ntotal_sample = moving_edge.ntotal_sample;
00155
00156 config.strip = moving_edge.strip;
00157 config.min_samplestep = moving_edge.min_samplestep;
00158 config.aberration = moving_edge.aberration;
00159 config.init_aberration = moving_edge.init_aberration;
00160
00161 config.lambda = tracker.lambda;
00162 config.first_threshold = tracker.percentageGdPt;
00163 }
00164
00165 void convertVpMeToInitRequest(const vpMe& moving_edge,
00166 const vpMbEdgeTracker& tracker,
00167 visp_tracker::Init& srv)
00168 {
00169 srv.request.moving_edge.mask_size = moving_edge.mask_size;
00170 srv.request.moving_edge.n_mask = moving_edge.n_mask;
00171 srv.request.moving_edge.range = moving_edge.range;
00172 srv.request.moving_edge.threshold = moving_edge.threshold;
00173 srv.request.moving_edge.mu1 = moving_edge.mu1;
00174 srv.request.moving_edge.mu2 = moving_edge.mu2;
00175 srv.request.moving_edge.sample_step = moving_edge.sample_step;
00176 srv.request.moving_edge.ntotal_sample = moving_edge.ntotal_sample;
00177
00178 srv.request.moving_edge.strip = moving_edge.strip;
00179 srv.request.moving_edge.min_samplestep = moving_edge.min_samplestep;
00180 srv.request.moving_edge.aberration = moving_edge.aberration;
00181 srv.request.moving_edge.init_aberration = moving_edge.init_aberration;
00182
00183 srv.request.moving_edge.lambda = tracker.lambda;
00184 srv.request.moving_edge.first_threshold = tracker.percentageGdPt;
00185 }
00186
00187 void convertInitRequestToVpMe(const visp_tracker::Init::Request& req,
00188 vpMbEdgeTracker& tracker,
00189 vpMe& moving_edge)
00190 {
00191 moving_edge.mask_size = req.moving_edge.mask_size;
00192 moving_edge.n_mask = req.moving_edge.n_mask;
00193 moving_edge.range = req.moving_edge.range;
00194 moving_edge.threshold = req.moving_edge.threshold;
00195 moving_edge.mu1 = req.moving_edge.mu1;
00196 moving_edge.mu2 = req.moving_edge.mu2;
00197 moving_edge.sample_step = req.moving_edge.sample_step;
00198 moving_edge.ntotal_sample = req.moving_edge.ntotal_sample;
00199
00200 moving_edge.strip = req.moving_edge.strip;
00201 moving_edge.min_samplestep = req.moving_edge.min_samplestep;
00202 moving_edge.aberration = req.moving_edge.aberration;
00203 moving_edge.init_aberration = req.moving_edge.init_aberration;
00204
00205 tracker.setLambda(req.moving_edge.lambda);
00206 tracker.setFirstThreshold(req.moving_edge.first_threshold);
00207 }
00208
00209 void initializeVpCameraFromCameraInfo(vpCameraParameters& cam,
00210 sensor_msgs::CameraInfoConstPtr info)
00211 {
00212 if (!info || info->P.size() != 3 * 4)
00213 throw std::runtime_error
00214 ("camera calibration P matrix has an incorrect size");
00215
00216 const double& px = info->P[0 * 4 + 0];
00217 const double& py = info->P[1 * 4 + 1];
00218 const double& u0 = info->P[0 * 4 + 2];
00219 const double& v0 = info->P[1 * 4 + 2];
00220 cam.initPersProjWithoutDistortion(px, py, u0, v0);
00221 }