ar_multi.cpp
Go to the documentation of this file.
00001 /*
00002  *  Multi Marker Pose Estimation using ARToolkit
00003  *  Copyright (C) 2010, CCNY Robotics Lab
00004  *  Ivan Dryanovski <ivan.dryanovski@gmail.com>
00005  *  William Morris <morris@ee.ccny.cuny.edu>
00006  *  Gautier Dumonteil <gautier.dumonteil@gmail.com>
00007  *  http://robotics.ccny.cuny.edu
00008  *
00009  *  This program is free software: you can redistribute it and/or modify
00010  *  it under the terms of the GNU General Public License as published by
00011  *  the Free Software Foundation, either version 3 of the License, or
00012  *  (at your option) any later version.
00013  *
00014  *  This program is distributed in the hope that it will be useful,
00015  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00016  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00017  *  GNU General Public License for more details.
00018  *
00019  *  You should have received a copy of the GNU General Public License
00020  *  along with this program.  If not, see <http://www.gnu.org/licenses/>.
00021  */
00022 
00023 #include "ar_pose/ar_multi.h"
00024 #include "ar_pose/object.h"
00025 
00026 int main (int argc, char **argv)
00027 {
00028   ros::init (argc, argv, "ar_single");
00029   ros::NodeHandle n;
00030   ar_pose::ARSinglePublisher ar_single (n);
00031   ros::spin ();
00032   return 0;
00033 }
00034 
00035 namespace ar_pose
00036 {
00037   ARSinglePublisher::ARSinglePublisher (ros::NodeHandle & n):n_ (n), it_ (n_)
00038   {
00039     std::string local_path;
00040     std::string package_path = ros::package::getPath (ROS_PACKAGE_NAME);
00041         std::string default_path = "data/object_4x4";
00042     ros::NodeHandle n_param ("~");
00043     XmlRpc::XmlRpcValue xml_marker_center;
00044 
00045     // **** get parameters
00046 
00047     if (!n_param.getParam ("publish_tf", publishTf_))
00048       publishTf_ = true;
00049     ROS_INFO ("\tPublish transforms: %d", publishTf_);
00050 
00051     if (!n_param.getParam ("publish_visual_markers", publishVisualMarkers_))
00052       publishVisualMarkers_ = true;
00053     ROS_INFO ("\tPublish visual markers: %d", publishVisualMarkers_);
00054 
00055     if (!n_param.getParam ("threshold", threshold_))
00056       threshold_ = 100;
00057     ROS_INFO ("\tThreshold: %d", threshold_);
00058         
00059         //modifications to allow path list from outside the package
00060         n_param.param ("marker_pattern_list", local_path, default_path);
00061         if (local_path.compare(0,5,"data/") == 0){
00062           //according to previous implementations, check if first 5 chars equal "data/"
00063           sprintf (pattern_filename_, "%s/%s", package_path.c_str (), local_path.c_str ());
00064         }
00065         else{
00066           //for new implementations, can pass a path outside the package_path
00067           sprintf (pattern_filename_, "%s", local_path.c_str ());
00068         }
00069         ROS_INFO ("Marker Pattern Filename: %s", pattern_filename_);
00070         
00071     // **** subscribe
00072 
00073     ROS_INFO ("Subscribing to info topic");
00074     sub_ = n_.subscribe (cameraInfoTopic_, 1, &ARSinglePublisher::camInfoCallback, this);
00075     getCamInfo_ = false;
00076 
00077     // **** advertsie 
00078 
00079     arMarkerPub_ = n_.advertise < ar_pose::ARMarkers > ("ar_pose_marker", 0);
00080     if(publishVisualMarkers_)
00081     {
00082                 rvizMarkerPub_ = n_.advertise < visualization_msgs::Marker > ("visualization_marker", 0);
00083          }
00084   }
00085 
00086   ARSinglePublisher::~ARSinglePublisher (void)
00087   {
00088     //cvReleaseImage(&capture_); //Don't know why but crash when release the image
00089     arVideoCapStop ();
00090     arVideoClose ();
00091   }
00092 
00093   void ARSinglePublisher::camInfoCallback (const sensor_msgs::CameraInfoConstPtr & cam_info)
00094   {
00095     if (!getCamInfo_)
00096     {
00097       cam_info_ = (*cam_info);
00098 
00099       cam_param_.xsize = cam_info_.width;
00100       cam_param_.ysize = cam_info_.height;
00101 
00102       cam_param_.mat[0][0] = cam_info_.P[0];
00103       cam_param_.mat[1][0] = cam_info_.P[4];
00104       cam_param_.mat[2][0] = cam_info_.P[8];
00105       cam_param_.mat[0][1] = cam_info_.P[1];
00106       cam_param_.mat[1][1] = cam_info_.P[5];
00107       cam_param_.mat[2][1] = cam_info_.P[9];
00108       cam_param_.mat[0][2] = cam_info_.P[2];
00109       cam_param_.mat[1][2] = cam_info_.P[6];
00110       cam_param_.mat[2][2] = cam_info_.P[10];
00111       cam_param_.mat[0][3] = cam_info_.P[3];
00112       cam_param_.mat[1][3] = cam_info_.P[7];
00113       cam_param_.mat[2][3] = cam_info_.P[11];
00114 
00115       cam_param_.dist_factor[0] = cam_info_.K[2];       // x0 = cX from openCV calibration
00116       cam_param_.dist_factor[1] = cam_info_.K[5];       // y0 = cY from openCV calibration
00117       cam_param_.dist_factor[2] = -100*cam_info_.D[0];  // f = -100*k1 from CV. Note, we had to do mm^2 to m^2, hence 10^8->10^2
00118       cam_param_.dist_factor[3] = 1.0;                  // scale factor, should probably be >1, but who cares...
00119       
00120       arInit ();
00121 
00122       ROS_INFO ("Subscribing to image topic");
00123       cam_sub_ = it_.subscribe (cameraImageTopic_, 1, &ARSinglePublisher::getTransformationCallback, this);
00124       getCamInfo_ = true;
00125     }
00126   }
00127 
00128   void ARSinglePublisher::arInit ()
00129   {
00130     arInitCparam (&cam_param_);
00131     ROS_INFO ("*** Camera Parameter ***");
00132     arParamDisp (&cam_param_);
00133 
00134     // load in the object data - trained markers and associated bitmap files
00135     if ((object = ar_object::read_ObjData (pattern_filename_, &objectnum)) == NULL)
00136       ROS_BREAK ();
00137     ROS_DEBUG ("Objectfile num = %d", objectnum);
00138 
00139     sz_ = cvSize (cam_param_.xsize, cam_param_.ysize);
00140     capture_ = cvCreateImage (sz_, IPL_DEPTH_8U, 4);
00141   }
00142 
00143   void ARSinglePublisher::getTransformationCallback (const sensor_msgs::ImageConstPtr & image_msg)
00144   {
00145     ARUint8 *dataPtr;
00146     ARMarkerInfo *marker_info;
00147     int marker_num;
00148     int i, k, j;
00149 
00150     /* Get the image from ROSTOPIC
00151      * NOTE: the dataPtr format is BGR because the ARToolKit library was
00152      * build with V4L, dataPtr format change according to the 
00153      * ARToolKit configure option (see config.h).*/
00154     try
00155     {
00156       capture_ = bridge_.imgMsgToCv (image_msg, "bgr8");
00157     }
00158     catch (sensor_msgs::CvBridgeException & e)
00159     {
00160       ROS_ERROR ("Could not convert from '%s' to 'bgr8'.", image_msg->encoding.c_str ());
00161     }
00162     //cvConvertImage(capture,capture,CV_CVTIMG_FLIP);
00163     dataPtr = (ARUint8 *) capture_->imageData;
00164 
00165     // detect the markers in the video frame
00166     if (arDetectMarker (dataPtr, threshold_, &marker_info, &marker_num) < 0)
00167     {
00168       argCleanup ();
00169       ROS_BREAK ();
00170     }
00171 
00172     arPoseMarkers_.markers.clear ();
00173     // check for known patterns
00174     for (i = 0; i < objectnum; i++)
00175     {
00176       k = -1;
00177       for (j = 0; j < marker_num; j++)
00178       {
00179         if (object[i].id == marker_info[j].id)
00180         {
00181           if (k == -1)
00182             k = j;
00183           else                  // make sure you have the best pattern (highest confidence factor)
00184           if (marker_info[k].cf < marker_info[j].cf)
00185             k = j;
00186         }
00187       }
00188       if (k == -1)
00189       {
00190         object[i].visible = 0;
00191         continue;
00192       }
00193 
00194       // calculate the transform for each marker
00195       if (object[i].visible == 0)
00196       {
00197         arGetTransMat (&marker_info[k], object[i].marker_center, object[i].marker_width, object[i].trans);
00198       }
00199       else
00200       {
00201         arGetTransMatCont (&marker_info[k], object[i].trans,
00202                            object[i].marker_center, object[i].marker_width, object[i].trans);
00203       }
00204       object[i].visible = 1;
00205 
00206       double arQuat[4], arPos[3];
00207 
00208       //arUtilMatInv (object[i].trans, cam_trans);
00209       arUtilMat2QuatPos (object[i].trans, arQuat, arPos);
00210 
00211       // **** convert to ROS frame
00212 
00213       double quat[4], pos[3];
00214 
00215       pos[0] = arPos[0] * AR_TO_ROS;
00216       pos[1] = arPos[1] * AR_TO_ROS;
00217       pos[2] = arPos[2] * AR_TO_ROS;
00218 
00219       quat[0] = -arQuat[0];
00220       quat[1] = -arQuat[1];
00221       quat[2] = -arQuat[2];
00222       quat[3] = arQuat[3];
00223 
00224       ROS_DEBUG (" Object num %i ------------------------------------------------", i);
00225       ROS_DEBUG (" QUAT: Pos x: %3.5f  y: %3.5f  z: %3.5f", pos[0], pos[1], pos[2]);
00226       ROS_DEBUG ("     Quat qx: %3.5f qy: %3.5f qz: %3.5f qw: %3.5f", quat[0], quat[1], quat[2], quat[3]);
00227 
00228       // **** publish the marker
00229 
00230       ar_pose::ARMarker ar_pose_marker;
00231       ar_pose_marker.header.frame_id = image_msg->header.frame_id;
00232       ar_pose_marker.header.stamp = image_msg->header.stamp;
00233       ar_pose_marker.id = object[i].id;
00234 
00235       ar_pose_marker.pose.pose.position.x = pos[0];
00236       ar_pose_marker.pose.pose.position.y = pos[1];
00237       ar_pose_marker.pose.pose.position.z = pos[2];
00238 
00239       ar_pose_marker.pose.pose.orientation.x = quat[0];
00240       ar_pose_marker.pose.pose.orientation.y = quat[1];
00241       ar_pose_marker.pose.pose.orientation.z = quat[2];
00242       ar_pose_marker.pose.pose.orientation.w = quat[3];
00243 
00244       ar_pose_marker.confidence = round(marker_info->cf * 100);
00245       arPoseMarkers_.markers.push_back (ar_pose_marker);
00246 
00247       // **** publish transform between camera and marker
00248 
00249       btQuaternion rotation (quat[0], quat[1], quat[2], quat[3]);
00250       btVector3 origin (pos[0], pos[1], pos[2]);
00251       btTransform t (rotation, origin);
00252 
00253       if (publishTf_)
00254       {
00255                         tf::StampedTransform camToMarker (t, image_msg->header.stamp, image_msg->header.frame_id, object[i].name);
00256                         broadcaster_.sendTransform(camToMarker);
00257       }
00258 
00259       // **** publish visual marker
00260 
00261       if (publishVisualMarkers_)
00262       {
00263         btVector3 markerOrigin (0, 0, 0.25 * object[i].marker_width * AR_TO_ROS);
00264         btTransform m (btQuaternion::getIdentity (), markerOrigin);
00265         btTransform markerPose = t * m; // marker pose in the camera frame
00266 
00267         tf::poseTFToMsg (markerPose, rvizMarker_.pose);
00268 
00269         rvizMarker_.header.frame_id = image_msg->header.frame_id;
00270         rvizMarker_.header.stamp = image_msg->header.stamp;
00271         rvizMarker_.id = object[i].id;
00272 
00273         rvizMarker_.scale.x = 1.0 * object[i].marker_width * AR_TO_ROS;
00274         rvizMarker_.scale.y = 1.0 * object[i].marker_width * AR_TO_ROS;
00275         rvizMarker_.scale.z = 0.5 * object[i].marker_width * AR_TO_ROS;
00276         rvizMarker_.ns = "basic_shapes";
00277         rvizMarker_.type = visualization_msgs::Marker::CUBE;
00278         rvizMarker_.action = visualization_msgs::Marker::ADD;
00279         switch (i)
00280         {
00281           case 0:
00282             rvizMarker_.color.r = 0.0f;
00283             rvizMarker_.color.g = 0.0f;
00284             rvizMarker_.color.b = 1.0f;
00285             rvizMarker_.color.a = 1.0;
00286             break;
00287           case 1:
00288             rvizMarker_.color.r = 1.0f;
00289             rvizMarker_.color.g = 0.0f;
00290             rvizMarker_.color.b = 0.0f;
00291             rvizMarker_.color.a = 1.0;
00292             break;
00293           default:
00294             rvizMarker_.color.r = 0.0f;
00295             rvizMarker_.color.g = 1.0f;
00296             rvizMarker_.color.b = 0.0f;
00297             rvizMarker_.color.a = 1.0;
00298         }
00299         rvizMarker_.lifetime = ros::Duration (1.0);
00300 
00301         rvizMarkerPub_.publish (rvizMarker_);
00302         ROS_DEBUG ("Published visual marker");
00303       }
00304     }
00305     arMarkerPub_.publish (arPoseMarkers_);
00306     ROS_DEBUG ("Published ar_multi markers");
00307   }
00308 }                               // end namespace ar_pose
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


ar_pose
Author(s): Ivan Dryanovski, William Morris, Gautier Dumonteil et al.
autogenerated on Thu Apr 25 2013 15:41:19