FindMarkerBundles.cpp
Go to the documentation of this file.
1 /*
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2012, Scott Niekum
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without
8  modification, are permitted provided that the following conditions
9  are met:
10 
11  * Redistributions of source code must retain the above copyright
12  notice, this list of conditions and the following disclaimer.
13  * Redistributions in binary form must reproduce the above
14  copyright notice, this list of conditions and the following
15  disclaimer in the documentation and/or other materials provided
16  with the distribution.
17  * Neither the name of the Willow Garage nor the names of its
18  contributors may be used to endorse or promote products derived
19  from this software without specific prior written permission.
20 
21  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  POSSIBILITY OF SUCH DAMAGE.
33 
34  author: Scott Niekum
35 */
40 #include "ar_track_alvar/Shared.h"
41 #include <cv_bridge/cv_bridge.h>
42 #include <ar_track_alvar_msgs/AlvarMarker.h>
43 #include <ar_track_alvar_msgs/AlvarMarkers.h>
44 #include <tf/transform_listener.h>
46 
47 #include <sensor_msgs/PointCloud2.h>
49 #include <pcl/point_types.h>
50 #include <pcl/registration/icp.h>
51 #include <pcl/registration/registration.h>
52 
53 #include <geometry_msgs/PoseStamped.h>
55 #include <ros/ros.h>
56 #include <pcl/ModelCoefficients.h>
57 #include <pcl/point_types.h>
58 #include <pcl/sample_consensus/method_types.h>
59 #include <pcl/sample_consensus/model_types.h>
60 #include <pcl/segmentation/sac_segmentation.h>
61 #include <pcl_ros/point_cloud.h>
62 #include <pcl/filters/extract_indices.h>
63 #include <boost/lexical_cast.hpp>
64 
65 #include <tf/tf.h>
66 #include <Eigen/Core>
69 
70 
71 #define MAIN_MARKER 1
72 #define VISIBLE_MARKER 2
73 #define GHOST_MARKER 3
74 
75 namespace gm=geometry_msgs;
76 namespace ata=ar_track_alvar;
77 
78 typedef pcl::PointXYZRGB ARPoint;
79 typedef pcl::PointCloud<ARPoint> ARCloud;
80 
81 using namespace alvar;
82 using namespace std;
83 using boost::make_shared;
84 
92 ar_track_alvar_msgs::AlvarMarkers arPoseMarkers_;
97 
99 int *master_id;
102 std::vector<int> *bundle_indices;
103 bool init = true;
106 
107 double marker_size;
110 std::string cam_image_topic;
111 std::string cam_info_topic;
112 std::string output_frame;
113 int n_bundles = 0;
114 
115 //Debugging utility function
116 void draw3dPoints(ARCloud::Ptr cloud, string frame, int color, int id, double rad)
117 {
118  visualization_msgs::Marker rvizMarker;
119 
120  rvizMarker.header.frame_id = frame;
121  rvizMarker.header.stamp = ros::Time::now();
122  rvizMarker.id = id;
123  rvizMarker.ns = "3dpts";
124 
125  rvizMarker.scale.x = rad;
126  rvizMarker.scale.y = rad;
127  rvizMarker.scale.z = rad;
128 
129  rvizMarker.type = visualization_msgs::Marker::SPHERE_LIST;
130  rvizMarker.action = visualization_msgs::Marker::ADD;
131 
132  if(color==1){
133  rvizMarker.color.r = 0.0f;
134  rvizMarker.color.g = 1.0f;
135  rvizMarker.color.b = 1.0f;
136  rvizMarker.color.a = 1.0;
137  }
138  if(color==2){
139  rvizMarker.color.r = 1.0f;
140  rvizMarker.color.g = 0.0f;
141  rvizMarker.color.b = 1.0f;
142  rvizMarker.color.a = 1.0;
143  }
144  if(color==3){
145  rvizMarker.color.r = 1.0f;
146  rvizMarker.color.g = 1.0f;
147  rvizMarker.color.b = 0.0f;
148  rvizMarker.color.a = 1.0;
149  }
150 
151  gm::Point p;
152  for(int i=0; i<cloud->points.size(); i++){
153  p.x = cloud->points[i].x;
154  p.y = cloud->points[i].y;
155  p.z = cloud->points[i].z;
156  rvizMarker.points.push_back(p);
157  }
158 
159  rvizMarker.lifetime = ros::Duration (1.0);
160  rvizMarkerPub2_.publish (rvizMarker);
161 }
162 
163 
164 void drawArrow(gm::Point start, tf::Matrix3x3 mat, string frame, int color, int id)
165 {
166  visualization_msgs::Marker rvizMarker;
167 
168  rvizMarker.header.frame_id = frame;
169  rvizMarker.header.stamp = ros::Time::now();
170  rvizMarker.id = id;
171  rvizMarker.ns = "arrow";
172 
173  rvizMarker.scale.x = 0.01;
174  rvizMarker.scale.y = 0.01;
175  rvizMarker.scale.z = 0.1;
176 
177  rvizMarker.type = visualization_msgs::Marker::ARROW;
178  rvizMarker.action = visualization_msgs::Marker::ADD;
179 
180  for(int i=0; i<3; i++){
181  rvizMarker.points.clear();
182  rvizMarker.points.push_back(start);
183  gm::Point end;
184  end.x = start.x + mat[0][i];
185  end.y = start.y + mat[1][i];
186  end.z = start.z + mat[2][i];
187  rvizMarker.points.push_back(end);
188  rvizMarker.id += 10*i;
189  rvizMarker.lifetime = ros::Duration (1.0);
190 
191  if(color==1){
192  rvizMarker.color.r = 1.0f;
193  rvizMarker.color.g = 0.0f;
194  rvizMarker.color.b = 0.0f;
195  rvizMarker.color.a = 1.0;
196  }
197  if(color==2){
198  rvizMarker.color.r = 0.0f;
199  rvizMarker.color.g = 1.0f;
200  rvizMarker.color.b = 0.0f;
201  rvizMarker.color.a = 1.0;
202  }
203  if(color==3){
204  rvizMarker.color.r = 0.0f;
205  rvizMarker.color.g = 0.0f;
206  rvizMarker.color.b = 1.0f;
207  rvizMarker.color.a = 1.0;
208  }
209  color += 1;
210 
211  rvizMarkerPub2_.publish (rvizMarker);
212  }
213 }
214 
215 
216 // Infer the master tag corner positons from the other observed tags
217 // Also does some of the bookkeeping for tracking that MultiMarker::_GetPose does
218 int InferCorners(const ARCloud &cloud, MultiMarkerBundle &master, ARCloud &bund_corners){
219  bund_corners.clear();
220  bund_corners.resize(4);
221  for(int i=0; i<4; i++){
222  bund_corners[i].x = 0;
223  bund_corners[i].y = 0;
224  bund_corners[i].z = 0;
225  }
226 
227  // Reset the marker_status to 1 for all markers in point_cloud for tracking purposes
228  for (size_t i=0; i<master.marker_status.size(); i++) {
229  if (master.marker_status[i] > 0) master.marker_status[i]=1;
230  }
231 
232  int n_est = 0;
233 
234  // For every detected marker
235  for (size_t i=0; i<marker_detector.markers->size(); i++)
236  {
237  const Marker* marker = &((*marker_detector.markers)[i]);
238  int id = marker->GetId();
239  int index = master.get_id_index(id);
240  int mast_id = master.master_id;
241  if (index < 0) continue;
242 
243  // But only if we have corresponding points in the pointcloud
244  if (master.marker_status[index] > 0 && marker->valid) {
245  n_est++;
246 
247  std::string marker_frame = "ar_marker_";
248  std::stringstream mark_out;
249  mark_out << id;
250  std::string id_string = mark_out.str();
251  marker_frame += id_string;
252 
253  //Grab the precomputed corner coords and correct for the weird Alvar coord system
254  for(int j = 0; j < 4; ++j)
255  {
256  tf::Vector3 corner_coord = master.rel_corners[index][j];
257  gm::PointStamped p, output_p;
258  p.header.frame_id = marker_frame;
259  p.point.x = corner_coord.y()/100.0;
260  p.point.y = -corner_coord.x()/100.0;
261  p.point.z = corner_coord.z()/100.0;
262 
263  try{
264  tf_listener->waitForTransform(cloud.header.frame_id, marker_frame, ros::Time(0), ros::Duration(0.1));
265  tf_listener->transformPoint(cloud.header.frame_id, p, output_p);
266  }
267  catch (tf::TransformException ex){
268  ROS_ERROR("ERROR InferCorners: %s",ex.what());
269  return -1;
270  }
271 
272  bund_corners[j].x += output_p.point.x;
273  bund_corners[j].y += output_p.point.y;
274  bund_corners[j].z += output_p.point.z;
275  }
276  master.marker_status[index] = 2; // Used for tracking
277  }
278  }
279 
280  //Divide to take the average of the summed estimates
281  if(n_est > 0){
282  for(int i=0; i<4; i++){
283  bund_corners[i].x /= n_est;
284  bund_corners[i].y /= n_est;
285  bund_corners[i].z /= n_est;
286  }
287  }
288 
289  return 0;
290 }
291 
292 
293 int PlaneFitPoseImprovement(int id, const ARCloud &corners_3D, ARCloud::Ptr selected_points, const ARCloud &cloud, Pose &p){
294 
295  ata::PlaneFitResult res = ata::fitPlane(selected_points);
296  gm::PoseStamped pose;
297  pose.header.stamp = pcl_conversions::fromPCL(cloud.header).stamp;
298  pose.header.frame_id = cloud.header.frame_id;
299  pose.pose.position = ata::centroid(*res.inliers);
300 
301  draw3dPoints(selected_points, cloud.header.frame_id, 1, id, 0.005);
302 
303  //Get 2 points that point forward in marker x direction
304  int i1,i2;
305  if(isnan(corners_3D[0].x) || isnan(corners_3D[0].y) || isnan(corners_3D[0].z) ||
306  isnan(corners_3D[3].x) || isnan(corners_3D[3].y) || isnan(corners_3D[3].z))
307  {
308  if(isnan(corners_3D[1].x) || isnan(corners_3D[1].y) || isnan(corners_3D[1].z) ||
309  isnan(corners_3D[2].x) || isnan(corners_3D[2].y) || isnan(corners_3D[2].z))
310  {
311  return -1;
312  }
313  else{
314  i1 = 1;
315  i2 = 2;
316  }
317  }
318  else{
319  i1 = 0;
320  i2 = 3;
321  }
322 
323  //Get 2 points the point forward in marker y direction
324  int i3,i4;
325  if(isnan(corners_3D[0].x) || isnan(corners_3D[0].y) || isnan(corners_3D[0].z) ||
326  isnan(corners_3D[1].x) || isnan(corners_3D[1].y) || isnan(corners_3D[1].z))
327  {
328  if(isnan(corners_3D[3].x) || isnan(corners_3D[3].y) || isnan(corners_3D[3].z) ||
329  isnan(corners_3D[2].x) || isnan(corners_3D[2].y) || isnan(corners_3D[2].z))
330  {
331  return -1;
332  }
333  else{
334  i3 = 2;
335  i4 = 3;
336  }
337  }
338  else{
339  i3 = 1;
340  i4 = 0;
341  }
342 
343  ARCloud::Ptr orient_points(new ARCloud());
344  orient_points->points.push_back(corners_3D[i1]);
345  draw3dPoints(orient_points, cloud.header.frame_id, 3, id+1000, 0.008);
346 
347  orient_points->clear();
348  orient_points->points.push_back(corners_3D[i2]);
349  draw3dPoints(orient_points, cloud.header.frame_id, 2, id+2000, 0.008);
350 
351  int succ;
352  succ = ata::extractOrientation(res.coeffs, corners_3D[i1], corners_3D[i2], corners_3D[i3], corners_3D[i4], pose.pose.orientation);
353  if(succ < 0) return -1;
354 
355  tf::Matrix3x3 mat;
356  succ = ata::extractFrame(res.coeffs, corners_3D[i1], corners_3D[i2], corners_3D[i3], corners_3D[i4], mat);
357  if(succ < 0) return -1;
358 
359  drawArrow(pose.pose.position, mat, cloud.header.frame_id, 1, id);
360 
361  p.translation[0] = pose.pose.position.x * 100.0;
362  p.translation[1] = pose.pose.position.y * 100.0;
363  p.translation[2] = pose.pose.position.z * 100.0;
364  p.quaternion[1] = pose.pose.orientation.x;
365  p.quaternion[2] = pose.pose.orientation.y;
366  p.quaternion[3] = pose.pose.orientation.z;
367  p.quaternion[0] = pose.pose.orientation.w;
368 
369  return 0;
370 }
371 
372 
373 // Updates the bundlePoses of the multi_marker_bundles by detecting markers and
374 // using all markers in a bundle to infer the master tag's position
375 void GetMultiMarkerPoses(IplImage *image, ARCloud &cloud) {
376 
377  for(int i=0; i<n_bundles; i++){
378  master_visible[i] = false;
379  bundles_seen[i] = 0;
380  }
381 
382  //Detect and track the markers
383  if (marker_detector.Detect(image, cam, true, false, max_new_marker_error,
384  max_track_error, CVSEQ, true))
385  {
386  //printf("\n--------------------------\n\n");
387  for (size_t i=0; i<marker_detector.markers->size(); i++)
388  {
389  vector<cv::Point, Eigen::aligned_allocator<cv::Point> > pixels;
390  Marker *m = &((*marker_detector.markers)[i]);
391  int id = m->GetId();
392  //cout << "******* ID: " << id << endl;
393 
394  //Get the 3D points of the outer corners
395  /*
396  PointDouble corner0 = m->marker_corners_img[0];
397  PointDouble corner1 = m->marker_corners_img[1];
398  PointDouble corner2 = m->marker_corners_img[2];
399  PointDouble corner3 = m->marker_corners_img[3];
400  m->ros_corners_3D[0] = cloud(corner0.x, corner0.y);
401  m->ros_corners_3D[1] = cloud(corner1.x, corner1.y);
402  m->ros_corners_3D[2] = cloud(corner2.x, corner2.y);
403  m->ros_corners_3D[3] = cloud(corner3.x, corner3.y);
404  */
405 
406  //Get the 3D inner corner points - more stable than outer corners that can "fall off" object
407  int resol = m->GetRes();
408  int ori = m->ros_orientation;
409 
410  PointDouble pt1, pt2, pt3, pt4;
411  pt4 = m->ros_marker_points_img[0];
412  pt3 = m->ros_marker_points_img[resol-1];
413  pt1 = m->ros_marker_points_img[(resol*resol)-resol];
414  pt2 = m->ros_marker_points_img[(resol*resol)-1];
415 
416  m->ros_corners_3D[0] = cloud(pt1.x, pt1.y);
417  m->ros_corners_3D[1] = cloud(pt2.x, pt2.y);
418  m->ros_corners_3D[2] = cloud(pt3.x, pt3.y);
419  m->ros_corners_3D[3] = cloud(pt4.x, pt4.y);
420 
421  if(ori >= 0 && ori < 4){
422  if(ori != 0){
423  std::rotate(m->ros_corners_3D.begin(), m->ros_corners_3D.begin() + ori, m->ros_corners_3D.end());
424  }
425  }
426  else
427  ROS_ERROR("FindMarkerBundles: Bad Orientation: %i for ID: %i", ori, id);
428 
429  //Check if we have spotted a master tag
430  int master_ind = -1;
431  for(int j=0; j<n_bundles; j++){
432  if(id == master_id[j])
433  master_visible[j] = true;
434  master_ind = j;
435  }
436 
437  //Mark the bundle that marker belongs to as "seen"
438  int bundle_ind = -1;
439  for(int j=0; j<n_bundles; j++){
440  for(int k=0; k<bundle_indices[j].size(); k++){
441  if(bundle_indices[j][k] == id){
442  bundle_ind = j;
443  bundles_seen[j] += 1;
444  break;
445  }
446  }
447  }
448 
449  //Get the 3D marker points
450  BOOST_FOREACH (const PointDouble& p, m->ros_marker_points_img)
451  pixels.push_back(cv::Point(p.x, p.y));
452  ARCloud::Ptr selected_points = ata::filterCloud(cloud, pixels);
453 
454  //Use the kinect data to find a plane and pose for the marker
455  int ret = PlaneFitPoseImprovement(i, m->ros_corners_3D, selected_points, cloud, m->pose);
456 
457  //If the plane fit fails...
458  if(ret < 0){
459  //Mark this tag as invalid
460  m->valid = false;
461  //If this was a master tag, reset its visibility
462  if(master_ind >= 0)
463  master_visible[master_ind] = false;
464  //decrement the number of markers seen in this bundle
465  bundles_seen[bundle_ind] -= 1;
466 
467  }
468  else
469  m->valid = true;
470  }
471 
472  //For each master tag, infer the 3D position of its corners from other visible tags
473  //Then, do a plane fit to those new corners
474  ARCloud inferred_corners;
475  for(int i=0; i<n_bundles; i++){
476  if(bundles_seen[i] > 0){
477  //if(master_visible[i] == false){
478  if(InferCorners(cloud, *(multi_marker_bundles[i]), inferred_corners) >= 0){
479  ARCloud::Ptr inferred_cloud(new ARCloud(inferred_corners));
480  PlaneFitPoseImprovement(i+5000, inferred_corners, inferred_cloud, cloud, bundlePoses[i]);
481  }
482  //}
483  //If master is visible, use it directly instead of inferring pose
484  //else{
485  // for (size_t j=0; j<marker_detector.markers->size(); j++){
486  // Marker *m = &((*marker_detector.markers)[j]);
487  // if(m->GetId() == master_id[i])
488  // bundlePoses[i] = m->pose;
489  // }
490  //}
491  Pose ret_pose;
492  if(med_filt_size > 0){
493  med_filts[i]->addPose(bundlePoses[i]);
494  med_filts[i]->getMedian(ret_pose);
495  bundlePoses[i] = ret_pose;
496  }
497  }
498  }
499  }
500 }
501 
502 
503 // Given the pose of a marker, builds the appropriate ROS messages for later publishing
504 void makeMarkerMsgs(int type, int id, Pose &p, sensor_msgs::ImageConstPtr image_msg, tf::StampedTransform &CamToOutput, visualization_msgs::Marker *rvizMarker, ar_track_alvar_msgs::AlvarMarker *ar_pose_marker, int confidence){
505  double px,py,pz,qx,qy,qz,qw;
506 
507  px = p.translation[0]/100.0;
508  py = p.translation[1]/100.0;
509  pz = p.translation[2]/100.0;
510  qx = p.quaternion[1];
511  qy = p.quaternion[2];
512  qz = p.quaternion[3];
513  qw = p.quaternion[0];
514 
515  //Get the marker pose in the camera frame
516  tf::Quaternion rotation (qx,qy,qz,qw);
517  tf::Vector3 origin (px,py,pz);
518  tf::Transform t (rotation, origin); //transform from cam to marker
519 
520  tf::Vector3 markerOrigin (0, 0, 0);
521  tf::Transform m (tf::Quaternion::getIdentity (), markerOrigin);
522  tf::Transform markerPose = t * m;
523 
524  //Publish the cam to marker transform for each marker
525  std::string markerFrame = "ar_marker_";
526  std::stringstream out;
527  out << id;
528  std::string id_string = out.str();
529  markerFrame += id_string;
530  tf::StampedTransform camToMarker (t, image_msg->header.stamp, image_msg->header.frame_id, markerFrame.c_str());
531  tf_broadcaster->sendTransform(camToMarker);
532 
533  //Create the rviz visualization message
534  tf::poseTFToMsg (markerPose, rvizMarker->pose);
535  rvizMarker->header.frame_id = image_msg->header.frame_id;
536  rvizMarker->header.stamp = image_msg->header.stamp;
537  rvizMarker->id = id;
538 
539  rvizMarker->scale.x = 1.0 * marker_size/100.0;
540  rvizMarker->scale.y = 1.0 * marker_size/100.0;
541  rvizMarker->scale.z = 0.2 * marker_size/100.0;
542 
543  if(type==MAIN_MARKER)
544  rvizMarker->ns = "main_shapes";
545  else
546  rvizMarker->ns = "basic_shapes";
547 
548 
549  rvizMarker->type = visualization_msgs::Marker::CUBE;
550  rvizMarker->action = visualization_msgs::Marker::ADD;
551 
552  //Determine a color and opacity, based on marker type
553  if(type==MAIN_MARKER){
554  rvizMarker->color.r = 1.0f;
555  rvizMarker->color.g = 0.0f;
556  rvizMarker->color.b = 0.0f;
557  rvizMarker->color.a = 1.0;
558  }
559  else if(type==VISIBLE_MARKER){
560  rvizMarker->color.r = 0.0f;
561  rvizMarker->color.g = 1.0f;
562  rvizMarker->color.b = 0.0f;
563  rvizMarker->color.a = 0.7;
564  }
565  else if(type==GHOST_MARKER){
566  rvizMarker->color.r = 0.0f;
567  rvizMarker->color.g = 0.0f;
568  rvizMarker->color.b = 1.0f;
569  rvizMarker->color.a = 0.5;
570  }
571 
572  rvizMarker->lifetime = ros::Duration (0.1);
573 
574  // Only publish the pose of the master tag in each bundle, since that's all we really care about aside from visualization
575  if(type==MAIN_MARKER){
576  //Take the pose of the tag in the camera frame and convert to the output frame (usually torso_lift_link for the PR2)
577  tf::Transform tagPoseOutput = CamToOutput * markerPose;
578 
579  //Create the pose marker message
580  tf::poseTFToMsg (tagPoseOutput, ar_pose_marker->pose.pose);
581  ar_pose_marker->header.frame_id = output_frame;
582  ar_pose_marker->header.stamp = image_msg->header.stamp;
583  ar_pose_marker->id = id;
584  ar_pose_marker->confidence = confidence;
585  }
586  else
587  ar_pose_marker = NULL;
588 }
589 
590 
591 
592 //Callback to handle getting kinect point clouds and processing them
593 void getPointCloudCallback (const sensor_msgs::PointCloud2ConstPtr &msg)
594 {
595  sensor_msgs::ImagePtr image_msg(new sensor_msgs::Image);
596 
597  //If we've already gotten the cam info, then go ahead
598  if(cam->getCamInfo_){
599  try{
600  //Get the transformation from the Camera to the output frame for this image capture
601  tf::StampedTransform CamToOutput;
602  try{
603  tf_listener->waitForTransform(output_frame, msg->header.frame_id, msg->header.stamp, ros::Duration(1.0));
604  tf_listener->lookupTransform(output_frame, msg->header.frame_id, msg->header.stamp, CamToOutput);
605  }
606  catch (tf::TransformException ex){
607  ROS_ERROR("%s",ex.what());
608  }
609 
610  //Init and clear visualization markers
611  visualization_msgs::Marker rvizMarker;
612  ar_track_alvar_msgs::AlvarMarker ar_pose_marker;
613  arPoseMarkers_.markers.clear ();
614 
615  //Convert cloud to PCL
616  ARCloud cloud;
617  pcl::fromROSMsg(*msg, cloud);
618 
619  //Get an OpenCV image from the cloud
620  pcl::toROSMsg (*msg, *image_msg);
621  image_msg->header.stamp = msg->header.stamp;
622  image_msg->header.frame_id = msg->header.frame_id;
623 
624  //Convert the image
626 
627  //Get the estimated pose of the main markers by using all the markers in each bundle
628 
629  // GetMultiMarkersPoses expects an IplImage*, but as of ros groovy, cv_bridge gives
630  // us a cv::Mat. I'm too lazy to change to cv::Mat throughout right now, so I
631  // do this conversion here -jbinney
632  IplImage ipl_image = cv_ptr_->image;
633  GetMultiMarkerPoses(&ipl_image, cloud);
634 
635  for (size_t i=0; i<marker_detector.markers->size(); i++)
636  {
637  int id = (*(marker_detector.markers))[i].GetId();
638 
639  // Draw if id is valid
640  if(id >= 0){
641 
642  // Don't draw if it is a master tag...we do this later, a bit differently
643  bool should_draw = true;
644  for(int j=0; j<n_bundles; j++){
645  if(id == master_id[j]) should_draw = false;
646  }
647  if(should_draw && (*(marker_detector.markers))[i].valid){
648  Pose p = (*(marker_detector.markers))[i].pose;
649  makeMarkerMsgs(VISIBLE_MARKER, id, p, image_msg, CamToOutput, &rvizMarker, &ar_pose_marker, 1);
650  rvizMarkerPub_.publish (rvizMarker);
651  }
652  }
653  }
654 
655  //Draw the main markers, whether they are visible or not -- but only if at least 1 marker from their bundle is currently seen
656  for(int i=0; i<n_bundles; i++)
657  {
658  if(bundles_seen[i] > 0){
659  makeMarkerMsgs(MAIN_MARKER, master_id[i], bundlePoses[i], image_msg, CamToOutput, &rvizMarker, &ar_pose_marker, bundles_seen[i]);
660  rvizMarkerPub_.publish (rvizMarker);
661  arPoseMarkers_.markers.push_back (ar_pose_marker);
662  }
663  }
664 
665  //Publish the marker messages
666  arMarkerPub_.publish (arPoseMarkers_);
667  }
668  catch (cv_bridge::Exception& e){
669  ROS_ERROR ("ar_track_alvar: Image error: %s", image_msg->encoding.c_str ());
670  }
671  }
672 }
673 
674 
675 //Create a ROS frame out of the known corners of a tag in the weird marker coord frame used by Alvar markers (x right y forward z up)
676 //p0-->p1 should point in Alvar's pos X direction
677 //p1-->p2 should point in Alvar's pos Y direction
678 int makeMasterTransform (const CvPoint3D64f& p0, const CvPoint3D64f& p1,
679  const CvPoint3D64f& p2, const CvPoint3D64f& p3,
680  tf::Transform &retT)
681  {
682  const tf::Vector3 q0(p0.x, p0.y, p0.z);
683  const tf::Vector3 q1(p1.x, p1.y, p1.z);
684  const tf::Vector3 q2(p2.x, p2.y, p2.z);
685  const tf::Vector3 q3(p3.x, p3.y, p3.z);
686 
687  // (inverse) matrix with the given properties
688  const tf::Vector3 v = (q1-q0).normalized();
689  const tf::Vector3 w = (q2-q1).normalized();
690  const tf::Vector3 n = v.cross(w);
691  tf::Matrix3x3 m(v[0], v[1], v[2], w[0], w[1], w[2], n[0], n[1], n[2]);
692  m = m.inverse();
693 
694  //Translate to quaternion
695  if(m.determinant() <= 0)
696  return -1;
697 
698  //Use Eigen for this part instead, because the ROS version of bullet appears to have a bug
699  Eigen::Matrix3f eig_m;
700  for(int i=0; i<3; i++){
701  for(int j=0; j<3; j++){
702  eig_m(i,j) = m[i][j];
703  }
704  }
705  Eigen::Quaternion<float> eig_quat(eig_m);
706 
707  // Translate back to bullet
708  tfScalar ex = eig_quat.x();
709  tfScalar ey = eig_quat.y();
710  tfScalar ez = eig_quat.z();
711  tfScalar ew = eig_quat.w();
712  tf::Quaternion quat(ex,ey,ez,ew);
713  quat = quat.normalized();
714 
715  double qx = (q0.x() + q1.x() + q2.x() + q3.x()) / 4.0;
716  double qy = (q0.y() + q1.y() + q2.y() + q3.y()) / 4.0;
717  double qz = (q0.z() + q1.z() + q2.z() + q3.z()) / 4.0;
718  tf::Vector3 origin (qx,qy,qz);
719 
720  tf::Transform tform (quat, origin); //transform from master to marker
721  retT = tform;
722 
723  return 0;
724  }
725 
726 
727 //Find the coordinates of the Master marker with respect to the coord frame of each of it's child markers
728 //This data is used for later estimation of the Master marker pose from the child poses
730 {
731  int mast_id = master.master_id;
732  std::vector<tf::Vector3> rel_corner_coords;
733 
734  //Go through all the markers associated with this bundle
735  for (size_t i=0; i<master.marker_indices.size(); i++){
736  int mark_id = master.marker_indices[i];
737  rel_corner_coords.clear();
738 
739  //Get the coords of the corners of the child marker in the master frame
740  CvPoint3D64f mark_corners[4];
741  for(int j=0; j<4; j++){
742  mark_corners[j] = master.pointcloud[master.pointcloud_index(mark_id, j)];
743  }
744 
745  //Use them to find a transform from the master frame to the child frame
746  tf::Transform tform;
747  makeMasterTransform(mark_corners[0], mark_corners[1], mark_corners[2], mark_corners[3], tform);
748 
749  //Finally, find the coords of the corners of the master in the child frame
750  for(int j=0; j<4; j++){
751 
752  CvPoint3D64f corner_coord = master.pointcloud[master.pointcloud_index(mast_id, j)];
753  double px = corner_coord.x;
754  double py = corner_coord.y;
755  double pz = corner_coord.z;
756 
757  tf::Vector3 corner_vec (px, py, pz);
758  tf::Vector3 ans = (tform.inverse()) * corner_vec;
759  rel_corner_coords.push_back(ans);
760  }
761 
762  master.rel_corners.push_back(rel_corner_coords);
763  }
764 
765  return 0;
766 }
767 
768 
769 int main(int argc, char *argv[])
770 {
771  ros::init (argc, argv, "marker_detect");
772  ros::NodeHandle n;
773 
774  if(argc < 9){
775  std::cout << std::endl;
776  cout << "Not enough arguments provided." << endl;
777  cout << "Usage: ./findMarkerBundles <marker size in cm> <max new marker error> <max track error> <cam image topic> <cam info topic> <output frame> <median filt size> <list of bundle XML files...>" << endl;
778  std::cout << std::endl;
779  return 0;
780  }
781 
782  // Get params from command line
783  marker_size = atof(argv[1]);
784  max_new_marker_error = atof(argv[2]);
785  max_track_error = atof(argv[3]);
786  cam_image_topic = argv[4];
787  cam_info_topic = argv[5];
788  output_frame = argv[6];
789  med_filt_size = atoi(argv[7]);
790  int n_args_before_list = 8;
791  n_bundles = argc - n_args_before_list;
792 
793  marker_detector.SetMarkerSize(marker_size);
794  multi_marker_bundles = new MultiMarkerBundle*[n_bundles];
795  bundlePoses = new Pose[n_bundles];
796  master_id = new int[n_bundles];
797  bundle_indices = new std::vector<int>[n_bundles];
798  bundles_seen = new int[n_bundles];
799  master_visible = new bool[n_bundles];
800 
801  //Create median filters
802  med_filts = new ata::MedianFilter*[n_bundles];
803  for(int i=0; i<n_bundles; i++)
804  med_filts[i] = new ata::MedianFilter(med_filt_size);
805 
806  // Load the marker bundle XML files
807  for(int i=0; i<n_bundles; i++){
808  bundlePoses[i].Reset();
809  MultiMarker loadHelper;
810  if(loadHelper.Load(argv[i + n_args_before_list], FILE_FORMAT_XML)){
811  vector<int> id_vector = loadHelper.getIndices();
812  multi_marker_bundles[i] = new MultiMarkerBundle(id_vector);
813  multi_marker_bundles[i]->Load(argv[i + n_args_before_list], FILE_FORMAT_XML);
814  master_id[i] = multi_marker_bundles[i]->getMasterId();
815  bundle_indices[i] = multi_marker_bundles[i]->getIndices();
816  calcAndSaveMasterCoords(*(multi_marker_bundles[i]));
817  }
818  else{
819  cout<<"Cannot load file "<< argv[i + n_args_before_list] << endl;
820  return 0;
821  }
822  }
823 
824  // Set up camera, listeners, and broadcasters
825  cam = new Camera(n, cam_info_topic);
826  tf_listener = new tf::TransformListener(n);
827  tf_broadcaster = new tf::TransformBroadcaster();
828  arMarkerPub_ = n.advertise < ar_track_alvar_msgs::AlvarMarkers > ("ar_pose_marker", 0);
829  rvizMarkerPub_ = n.advertise < visualization_msgs::Marker > ("visualization_marker", 0);
830  rvizMarkerPub2_ = n.advertise < visualization_msgs::Marker > ("ARmarker_points", 0);
831 
832  //Give tf a chance to catch up before the camera callback starts asking for transforms
833  ros::Duration(1.0).sleep();
834  ros::spinOnce();
835 
836  //Subscribe to topics and set up callbacks
837  ROS_INFO ("Subscribing to image topic");
838  cloud_sub_ = n.subscribe(cam_image_topic, 1, &getPointCloudCallback);
839 
840  ros::spin();
841 
842  return 0;
843 }
844 
845 
double max_new_marker_error
Main ALVAR namespace.
Definition: Alvar.h:174
int ros_orientation
Definition: Marker.h:181
int GetRes() const
Definition: Marker.h:126
void GetMultiMarkerPoses(IplImage *image, ARCloud &cloud)
void makeMarkerMsgs(int type, int id, Pose &p, sensor_msgs::ImageConstPtr image_msg, tf::StampedTransform &CamToOutput, visualization_msgs::Marker *rvizMarker, ar_track_alvar_msgs::AlvarMarker *ar_pose_marker, int confidence)
#define MAIN_MARKER
void publish(const boost::shared_ptr< M > &message) const
std::string cam_info_topic
double tfScalar
virtual unsigned long GetId() const
Get id for this marker This is used e.g. in MarkerDetector to associate a marker id with an appropria...
Definition: Marker.h:118
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void SetMarkerSize(double _edge_length=1, int _res=5, double _margin=2)
int extractOrientation(const pcl::ModelCoefficients &coeffs, const ARPoint &p1, const ARPoint &p2, const ARPoint &p3, const ARPoint &p4, geometry_msgs::Quaternion &retQ)
bool sleep() const
This file implements a generic marker detector.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< int > marker_status
Definition: MultiMarker.h:65
ARCloud::Ptr filterCloud(const ARCloud &cloud, const std::vector< cv::Point, Eigen::aligned_allocator< cv::Point > > &pixels)
void getPointCloudCallback(const sensor_msgs::PointCloud2ConstPtr &msg)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
unsigned char * image
Definition: GlutViewer.cpp:155
void transformPoint(const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
ros::Publisher rvizMarkerPub2_
double marker_size
Matrix3x3 inverse() const
#define VISIBLE_MARKER
int * master_id
image_transport::Subscriber cam_sub_
Base class for using MultiMarker.
Definition: MultiMarker.h:47
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::map< int, CvPoint3D64f > pointcloud
Definition: MultiMarker.h:63
int makeMasterTransform(const CvPoint3D64f &p0, const CvPoint3D64f &p1, const CvPoint3D64f &p2, const CvPoint3D64f &p3, tf::Transform &retT)
int get_id_index(int id, bool add_if_missing=false)
Definition: MultiMarker.cpp:38
std::vector< int > marker_indices
Definition: MultiMarker.h:64
pcl::PointXYZRGB ARPoint
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
Definition: Camera.h:82
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
ROSCPP_DECL void spin(Spinner &spinner)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
std::vector< M, Eigen::aligned_allocator< M > > * markers
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE Vector3 normalized() const
void getMedian(alvar::Pose &ret_pose)
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
std::string output_frame
MarkerDetector for detecting markers of type M
void draw3dPoints(ARCloud::Ptr cloud, string frame, int color, int id, double rad)
int pointcloud_index(int marker_id, int marker_corner, bool add_if_missing=false)
Definition: MultiMarker.cpp:34
TFSIMD_FORCE_INLINE const tfScalar & z() const
Pose pose
The current marker Pose.
Definition: Marker.h:136
float rad
Definition: GlutViewer.cpp:146
static const Quaternion & getIdentity()
tf::TransformBroadcaster * tf_broadcaster
#define ROS_INFO(...)
int * bundles_seen
void Reset()
Definition: Pose.cpp:69
geometry_msgs::Point centroid(const ARCloud &points)
Multi marker that uses bundle adjustment to refine the 3D positions of the markers (point cloud)...
void drawArrow(gm::Point start, tf::Matrix3x3 mat, string frame, int color, int id)
ros::Subscriber cloud_sub_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::vector< int > * bundle_indices
TFSIMD_FORCE_INLINE const tfScalar & y() const
void sendTransform(const StampedTransform &transform)
Pose representation derived from the Rotation class
Definition: Pose.h:50
EIGEN_MAKE_ALIGNED_OPERATOR_NEW bool valid
Definition: Marker.h:62
int n_bundles
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< PointDouble > ros_marker_points_img
Marker points in image coordinates.
Definition: Marker.h:179
pcl::PointCloud< ARPoint > ARCloud
Transform inverse() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Basic 2D Marker functionality.
Definition: Marker.h:52
int main(int argc, char *argv[])
MultiMarkerBundle ** multi_marker_bundles
XML file format.
Definition: FileFormat.h:66
void addPose(const alvar::Pose &new_pose)
MarkerDetector< MarkerData > marker_detector
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
std::string cam_image_topic
TFSIMD_FORCE_INLINE const tfScalar & z() const
bool init
double quaternion[4]
Definition: Rotation.h:48
double max_track_error
TFSIMD_FORCE_INLINE const tfScalar & w() const
int PlaneFitPoseImprovement(int id, const ARCloud &corners_3D, ARCloud::Ptr selected_points, const ARCloud &cloud, Pose &p)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
This file implements a initialization algorithm to create a multi-marker field configuration.
ALVAR_EXPORT Point< CvPoint2D64f > PointDouble
The default double point type.
Definition: Util.h:108
bool Load(const char *fname, FILE_FORMAT format=FILE_FORMAT_DEFAULT)
Loads multi marker configuration from a text file.
int med_filt_size
int calcAndSaveMasterCoords(MultiMarkerBundle &master)
tfScalar determinant() const
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
int Detect(IplImage *image, Camera *cam, bool track=false, bool visualize=false, double max_new_marker_error=0.08, double max_track_error=0.2, LabelingMethod labeling_method=CVSEQ, bool update_pose=true)
Detect Marker &#39;s from image
int extractFrame(const pcl::ModelCoefficients &coeffs, const ARPoint &p1, const ARPoint &p2, const ARPoint &p3, const ARPoint &p4, tf::Matrix3x3 &retmat)
Pose * bundlePoses
static Time now()
bool * master_visible
ar_track_alvar_msgs::AlvarMarkers arPoseMarkers_
#define GHOST_MARKER
pcl::ModelCoefficients coeffs
Camera * cam
const int res
This file implements an algorithm to create a multi-marker field configuration.
cv_bridge::CvImagePtr cv_ptr_
tf::TransformListener * tf_listener
double translation[4]
Definition: Pose.h:54
ROSCPP_DECL void spinOnce()
ros::Publisher arMarkerPub_
#define ROS_ERROR(...)
ar_track_alvar::ARCloud ros_corners_3D
Definition: Marker.h:180
std::vector< int > getIndices()
Definition: MultiMarker.h:176
PlaneFitResult fitPlane(ARCloud::ConstPtr cloud)
int InferCorners(const ARCloud &cloud, MultiMarkerBundle &master, ARCloud &bund_corners)
Quaternion normalized() const
ros::Publisher rvizMarkerPub_
ata::MedianFilter ** med_filts
std::vector< std::vector< tf::Vector3 > > rel_corners
Definition: MultiMarker.h:66
bool getCamInfo_
Definition: Camera.h:92


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Mon Jun 10 2019 12:47:04