conversion.cpp
Go to the documentation of this file.
1 #include <cstring>
2 #include <stdexcept>
3 
4 #include <boost/format.hpp>
5 
7 
8 #include <sensor_msgs/Image.h>
11 
12 #include <visp3/core/vpImage.h>
13 #include <visp3/core/vpTranslationVector.h>
14 #include <visp3/core/vpQuaternionVector.h>
15 
16 #include <visp3/mbt/vpMbGenericTracker.h>
17 
18 
19 #include "conversion.hh"
20 
21 void rosImageToVisp(vpImage<unsigned char>& dst,
22  const sensor_msgs::Image::ConstPtr& src)
23 {
31 
32  // Resize the image if necessary.
33  if (src->width != dst.getWidth() || src->height != dst.getHeight())
34  {
35  ROS_INFO("dst is %dx%d but src size is %dx%d, resizing.",
36  dst.getWidth (), dst.getHeight (), src->width, src->height);
37  dst.resize (src->height, src->width);
38  }
39 
40  if(src->encoding == MONO8) {
41  memcpy(dst.bitmap, &src->data[0], dst.getHeight () * src->step * sizeof(unsigned char));
42  }
43  else if(src->encoding == RGB8 || src->encoding == RGBA8
44  || src->encoding == BGR8 || src->encoding == BGRA8)
45  {
46  unsigned nc = numChannels(src->encoding);
47  unsigned cEnd =
48  (src->encoding == RGBA8 || src->encoding == BGRA8) ? nc - 1 : nc;
49 
50  for(unsigned i = 0; i < dst.getWidth (); ++i)
51  for(unsigned j = 0; j < dst.getHeight (); ++j)
52  {
53  int acc = 0;
54  for(unsigned c = 0; c < cEnd; ++c)
55  acc += src->data[j * src->step + i * nc + c];
56  dst[j][i] = acc / nc;
57  }
58  }
59  else
60  {
61  boost::format fmt("bad encoding '%1'");
62  fmt % src->encoding;
63  throw std::runtime_error(fmt.str());
64  }
65 }
66 
67 void vispImageToRos(sensor_msgs::Image& dst,
68  const vpImage<unsigned char>& src)
69 {
70  dst.width = src.getWidth();
71  dst.height = src.getHeight();
73  dst.step = src.getWidth();
74  dst.data.resize(dst.height * dst.step);
75  for(unsigned i = 0; i < src.getWidth (); ++i)
76  for(unsigned j = 0; j < src.getHeight (); ++j)
77  dst.data[j * dst.step + i] = src[j][i];
78 }
79 
80 
81 std::string convertVpMbTrackerToRosMessage(const vpMbGenericTracker &tracker)
82 {
83  std::stringstream stream;
84  stream << "Model Based Tracker Common Setttings\n" <<
85  " Angle for polygons apparition...." << vpMath::deg(tracker.getAngleAppear()) <<" degrees\n" <<
86  " Angle for polygons disparition..." << vpMath::deg(tracker.getAngleDisappear()) << " degrees\n";
87  return stream.str();
88 }
89 
90 std::string convertVpMeToRosMessage(const vpMbGenericTracker &tracker, const vpMe& moving_edge)
91 {
92  std::stringstream stream;
93  stream << "Moving Edge Setttings\n" <<
94  " Size of the convolution masks...." << moving_edge.getMaskSize() <<"x"<< moving_edge.getMaskSize() <<" pixels\n" <<
95  " Query range +/- J................" << moving_edge.getRange() <<" pixels\n" <<
96  " Likelihood test ratio............" << moving_edge.getThreshold() << "\n" <<
97  " Contrast tolerance +/-..........." << moving_edge.getMu1() * 100 << "% and " << moving_edge.getMu2() * 100 << "% \n" <<
98  " Sample step......................" << moving_edge.getSampleStep() <<" pixels\n" <<
99  " Strip............................" << moving_edge.getStrip() << " pixels\n";
100 
101  stream << " Good moving edge threshold......." << tracker.getGoodMovingEdgesRatioThreshold()*100 << "%\n";
102 
103  return stream.str();
104 }
105 
106 std::string convertVpKltOpencvToRosMessage(const vpMbGenericTracker &tracker, const vpKltOpencv& klt)
107 {
108  std::stringstream stream;
109  stream << "KLT Setttings\n" <<
110  " Window size......................" << klt.getWindowSize() <<"x"<< klt.getWindowSize() <<" pixels\n" <<
111  " Mask border......................" << tracker.getKltMaskBorder() << " pixels\n" <<
112  " Maximum number of features......." << klt.getMaxFeatures() <<"\n" <<
113  " Detected points quality.........." << klt.getQuality() << "\n" <<
114  " Minimum distance between points.." << klt.getMinDistance() << " pixels\n" <<
115  " Harris free parameter............" << klt.getHarrisFreeParameter() <<"\n" <<
116  " Block size......................." << klt.getBlockSize() << "x" << klt.getBlockSize() << " pixels\n" <<
117  " Number of pyramid levels........." << klt.getPyramidLevels() << "\n";
118 
119  return stream.str();
120 }
121 
122 void vpHomogeneousMatrixToTransform(geometry_msgs::Transform& dst,
123  const vpHomogeneousMatrix& src)
124 {
125  vpQuaternionVector quaternion;
126  src.extract(quaternion);
127 
128  dst.translation.x = src[0][3];
129  dst.translation.y = src[1][3];
130  dst.translation.z = src[2][3];
131 
132  dst.rotation.x = quaternion.x();
133  dst.rotation.y = quaternion.y();
134  dst.rotation.z = quaternion.z();
135  dst.rotation.w = quaternion.w();
136 }
137 
138 void transformToVpHomogeneousMatrix(vpHomogeneousMatrix& dst,
139  const geometry_msgs::Transform& src)
140 {
141  vpTranslationVector translation(src.translation.x,src.translation.y,src.translation.z);
142  vpQuaternionVector quaternion(src.rotation.x,src.rotation.y,src.rotation.z,src.rotation.w);
143  dst.buildFrom(translation, quaternion);
144 }
145 
146 void transformToVpHomogeneousMatrix(vpHomogeneousMatrix& dst,
147  const geometry_msgs::Pose& src)
148 {
149  vpQuaternionVector quaternion
150  (src.orientation.x, src.orientation.y, src.orientation.z,
151  src.orientation.w);
152  vpRotationMatrix rotation(quaternion);
153 
154  // Copy the rotation component.
155  for(unsigned i = 0; i < 3; ++i)
156  for(unsigned j = 0; j < 3; ++j)
157  dst[i][j] = rotation[i][j];
158 
159  // Copy the translation component.
160  dst[0][3] = src.position.x;
161  dst[1][3] = src.position.y;
162  dst[2][3] = src.position.z;
163 }
164 
165 void transformToVpHomogeneousMatrix(vpHomogeneousMatrix& dst,
166  const tf::Transform& src)
167 {
168  // Copy the rotation component.
169  for(unsigned i = 0; i < 3; ++i)
170  for(unsigned j = 0; j < 3; ++j)
171  dst[i][j] = src.getBasis ()[i][j];
172 
173  // Copy the translation component.
174  for (unsigned i = 0; i < 3; ++i)
175  dst[i][3] = src.getOrigin ()[i];
176  dst[3][3] = 1.;
177 }
178 
179 void convertVpMbTrackerToInitRequest(const vpMbGenericTracker &tracker,
180  visp_tracker::Init& srv)
181 {
182  srv.request.tracker_param.angle_appear = vpMath::deg(tracker.getAngleAppear());
183  srv.request.tracker_param.angle_disappear = vpMath::deg(tracker.getAngleDisappear());
184 }
185 
186 void convertInitRequestToVpMbTracker(const visp_tracker::Init::Request& req,
187  vpMbGenericTracker &tracker)
188 {
189  tracker.setAngleAppear(vpMath::rad(req.tracker_param.angle_appear));
190  tracker.setAngleDisappear(vpMath::rad(req.tracker_param.angle_disappear));
191 }
192 
193 void convertVpMeToInitRequest(const vpMe& moving_edge,
194  const vpMbGenericTracker &tracker,
195  visp_tracker::Init& srv)
196 {
197  srv.request.moving_edge.first_threshold = tracker.getGoodMovingEdgesRatioThreshold();
198  srv.request.moving_edge.mask_size = moving_edge.getMaskSize();
199  srv.request.moving_edge.range = moving_edge.getRange();
200  srv.request.moving_edge.threshold = moving_edge.getThreshold();
201  srv.request.moving_edge.mu1 = moving_edge.getMu1();
202  srv.request.moving_edge.mu2 = moving_edge.getMu2();
203  srv.request.moving_edge.sample_step = moving_edge.getSampleStep();
204  srv.request.moving_edge.strip = moving_edge.getStrip();
205 }
206 
207 void convertInitRequestToVpMe(const visp_tracker::Init::Request& req,
208  vpMbGenericTracker &tracker,
209  vpMe& moving_edge)
210 {
211  tracker.setGoodMovingEdgesRatioThreshold(req.moving_edge.first_threshold);
212  moving_edge.setMaskSize( req.moving_edge.mask_size );
213  moving_edge.setRange( req.moving_edge.range );
214  moving_edge.setThreshold( req.moving_edge.threshold );
215  moving_edge.setMu1( req.moving_edge.mu1 );
216  moving_edge.setMu2( req.moving_edge.mu2 );
217  moving_edge.setSampleStep( req.moving_edge.sample_step );
218  moving_edge.setStrip( req.moving_edge.strip );
219 
220  //FIXME: not sure if this is needed.
221  moving_edge.initMask();
222  //Reset the tracker and the node state.
223  tracker.setMovingEdge(moving_edge);
224 }
225 
226 void convertVpKltOpencvToInitRequest(const vpKltOpencv& klt,
227  const vpMbGenericTracker &tracker,
228  visp_tracker::Init& srv)
229 {
230  srv.request.klt_param.max_features = klt.getMaxFeatures();
231  srv.request.klt_param.window_size = klt.getWindowSize();
232  srv.request.klt_param.quality = klt.getQuality();
233  srv.request.klt_param.min_distance = klt.getMinDistance();
234  srv.request.klt_param.harris = klt.getHarrisFreeParameter();
235  srv.request.klt_param.size_block = klt.getBlockSize();
236  srv.request.klt_param.pyramid_lvl = klt.getPyramidLevels();
237  srv.request.klt_param.mask_border = tracker.getKltMaskBorder();
238 }
239 
240 void convertInitRequestToVpKltOpencv(const visp_tracker::Init::Request& req,
241  vpMbGenericTracker &tracker,
242  vpKltOpencv& klt)
243 {
244  klt.setMaxFeatures(req.klt_param.max_features);
245  klt.setWindowSize(req.klt_param.window_size);
246  klt.setQuality(req.klt_param.quality);
247  klt.setMinDistance(req.klt_param.min_distance);
248  klt.setHarrisFreeParameter(req.klt_param.harris);
249  klt.setBlockSize(req.klt_param.size_block);
250  klt.setPyramidLevels(req.klt_param.pyramid_lvl);
251  tracker.setKltMaskBorder((unsigned)req.klt_param.mask_border);
252 
253  tracker.setKltOpencv(klt);
254 }
255 
256 void initializeVpCameraFromCameraInfo(vpCameraParameters& cam,
257  sensor_msgs::CameraInfoConstPtr info)
258 {
259  if (!info)
260  throw std::runtime_error ("missing camera calibration data");
261 
262  // Check that the camera is calibrated, as specified in the
263  // sensor_msgs/CameraInfo message documentation.
264  if (info->K.size() != 3 * 3 || info->K[0] == 0.)
265  throw std::runtime_error ("uncalibrated camera");
266 
267  // Check matrix size.
268  if (!info || info->P.size() != 3 * 4)
269  throw std::runtime_error
270  ("camera calibration P matrix has an incorrect size");
271 
272  if (info->distortion_model.empty ())
273  {
274  const double& px = info->K[0 * 3 + 0];
275  const double& py = info->K[1 * 3 + 1];
276  const double& u0 = info->K[0 * 3 + 2];
277  const double& v0 = info->K[1 * 3 + 2];
278  cam.initPersProjWithoutDistortion(px, py, u0, v0);
279  return;
280  }
281 
282  if (info->distortion_model == sensor_msgs::distortion_models::PLUMB_BOB)
283  {
284  const double& px = info->P[0 * 4 + 0];
285  const double& py = info->P[1 * 4 + 1];
286  const double& u0 = info->P[0 * 4 + 2];
287  const double& v0 = info->P[1 * 4 + 2];
288  cam.initPersProjWithoutDistortion(px, py, u0, v0);
289  return;
290  }
291 
292  throw std::runtime_error ("unsupported distortion model");
293 }
void convertInitRequestToVpMe(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker, vpMe &moving_edge)
Definition: conversion.cpp:207
void transformToVpHomogeneousMatrix(vpHomogeneousMatrix &dst, const geometry_msgs::Transform &src)
Definition: conversion.cpp:138
void vispImageToRos(sensor_msgs::Image &dst, const vpImage< unsigned char > &src)
Convert a ViSP image into a ROS one.
Definition: conversion.cpp:67
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
void convertVpMeToInitRequest(const vpMe &moving_edge, const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
Definition: conversion.cpp:193
void convertVpMbTrackerToInitRequest(const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
Definition: conversion.cpp:179
std::string convertVpKltOpencvToRosMessage(const vpMbGenericTracker &tracker, const vpKltOpencv &klt)
Definition: conversion.cpp:106
void convertVpKltOpencvToInitRequest(const vpKltOpencv &klt, const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
Definition: conversion.cpp:226
void convertInitRequestToVpKltOpencv(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker, vpKltOpencv &klt)
Definition: conversion.cpp:240
std::string convertVpMeToRosMessage(const vpMbGenericTracker &tracker, const vpMe &moving_edge)
Definition: conversion.cpp:90
#define ROS_INFO(...)
const std::string MONO16
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
static int numChannels(const std::string &encoding)
std::string convertVpMbTrackerToRosMessage(const vpMbGenericTracker &tracker)
Definition: conversion.cpp:81
void initializeVpCameraFromCameraInfo(vpCameraParameters &cam, sensor_msgs::CameraInfoConstPtr info)
Definition: conversion.cpp:256
void convertInitRequestToVpMbTracker(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker)
Definition: conversion.cpp:186
void vpHomogeneousMatrixToTransform(geometry_msgs::Transform &dst, const vpHomogeneousMatrix &src)
Definition: conversion.cpp:122
void rosImageToVisp(vpImage< unsigned char > &dst, const sensor_msgs::Image::ConstPtr &src)
Convert a ROS image into a ViSP one.
Definition: conversion.cpp:21


visp_tracker
Author(s): Thomas Moulard
autogenerated on Sat Mar 13 2021 03:20:06