ar_single.cpp
Go to the documentation of this file.
00001 /*
00002  *  Single 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_single.h"
00024 
00025 int main (int argc, char **argv)
00026 {
00027   ros::init (argc, argv, "ar_single");
00028   ros::NodeHandle n;
00029   ar_pose::ARSinglePublisher arSingle(n);
00030   ros::spin();
00031   return 0;
00032 }
00033 
00034 namespace ar_pose
00035 {
00036   ARSinglePublisher::ARSinglePublisher (ros::NodeHandle & n):n_ (n), it_ (n_)
00037   {
00038     std::string local_path;
00039     std::string package_path = ros::package::getPath (ROS_PACKAGE_NAME);
00040         std::string default_path = "data/patt.hiro";
00041     ros::NodeHandle n_param ("~");
00042     XmlRpc::XmlRpcValue xml_marker_center;
00043 
00044     ROS_INFO("Starting ArSinglePublisher");
00045 
00046     // **** get parameters
00047 
00048     if (!n_param.getParam("publish_tf", publishTf_))
00049       publishTf_ = true;
00050     ROS_INFO ("\tPublish transforms: %d", publishTf_);
00051 
00052     if (!n_param.getParam("publish_visual_markers", publishVisualMarkers_))
00053       publishVisualMarkers_ = true;
00054     ROS_INFO ("\tPublish visual markers: %d", publishVisualMarkers_);
00055 
00056     if (!n_param.getParam("threshold", threshold_))
00057       threshold_ = 100;
00058     ROS_INFO ("\tThreshold: %d", threshold_);
00059 
00060     if (!n_param.getParam("marker_width", markerWidth_))
00061       markerWidth_ = 80.0;
00062     ROS_INFO ("\tMarker Width: %.1f", markerWidth_);
00063 
00064     if (!n_param.getParam("reverse_transform", reverse_transform_))
00065       reverse_transform_ = false;
00066     ROS_INFO("\tReverse Transform: %d", reverse_transform_);
00067 
00068     if (!n_param.getParam("marker_frame", markerFrame_))
00069       markerFrame_ = "ar_marker";
00070     ROS_INFO ("\tMarker frame: %s", markerFrame_.c_str());
00071 
00072     // If mode=0, we use arGetTransMat instead of arGetTransMatCont
00073     // The arGetTransMatCont function uses information from the previous image
00074     // frame to reduce the jittering of the marker
00075     if (!n_param.getParam("use_history", useHistory_))
00076       useHistory_ = true;
00077     ROS_INFO("\tUse history: %d", useHistory_);
00078 
00079 //     n_param.param ("marker_pattern", local_path, std::string ("data/patt.hiro"));
00080 //     sprintf (pattern_filename_, "%s/%s", package_path.c_str (), local_path.c_str ());
00081 //     ROS_INFO ("\tMarker Pattern Filename: %s", pattern_filename_);
00082 
00083         //modifications to allow patterns to be loaded from outside the package
00084         n_param.param ("marker_pattern", local_path, default_path);
00085         if (local_path.compare(0,5,"data/") == 0){
00086           //to keep working on previous implementations, check if first 5 chars equal "data/"
00087           sprintf (pattern_filename_, "%s/%s", package_path.c_str (), local_path.c_str ());
00088         }
00089         else{
00090           //for new implementations, can pass a path outside the package_path
00091           sprintf (pattern_filename_, "%s", local_path.c_str ());
00092         }
00093 
00094     n_param.param ("marker_center_x", marker_center_[0], 0.0);
00095     n_param.param ("marker_center_y", marker_center_[1], 0.0);
00096     ROS_INFO ("\tMarker Center: (%.1f,%.1f)", marker_center_[0], marker_center_[1]);
00097 
00098     // **** subscribe
00099 
00100     ROS_INFO ("Subscribing to info topic");
00101     sub_ = n_.subscribe (cameraInfoTopic_, 1, &ARSinglePublisher::camInfoCallback, this);
00102     getCamInfo_ = false;
00103     
00104     // **** advertsie 
00105 
00106     arMarkerPub_   = n_.advertise<ar_pose::ARMarker>("ar_pose_marker", 0);
00107     if(publishVisualMarkers_){ 
00108                 rvizMarkerPub_ = n_.advertise<visualization_msgs::Marker>("visualization_marker", 0);
00109          }
00110   }
00111 
00112   ARSinglePublisher::~ARSinglePublisher (void)
00113   {
00114     //cvReleaseImage(&capture); //Don't know why but crash when release the image
00115     arVideoCapStop ();
00116     arVideoClose ();
00117   }
00118 
00119   void ARSinglePublisher::camInfoCallback (const sensor_msgs::CameraInfoConstPtr & cam_info)
00120   {
00121     if (!getCamInfo_)
00122     {
00123       cam_info_ = (*cam_info);
00124 
00125       cam_param_.xsize = cam_info_.width;
00126       cam_param_.ysize = cam_info_.height;
00127       
00128       cam_param_.mat[0][0] = cam_info_.P[0];
00129       cam_param_.mat[1][0] = cam_info_.P[4];
00130       cam_param_.mat[2][0] = cam_info_.P[8];
00131       cam_param_.mat[0][1] = cam_info_.P[1];
00132       cam_param_.mat[1][1] = cam_info_.P[5];
00133       cam_param_.mat[2][1] = cam_info_.P[9];
00134       cam_param_.mat[0][2] = cam_info_.P[2];
00135       cam_param_.mat[1][2] = cam_info_.P[6];
00136       cam_param_.mat[2][2] = cam_info_.P[10];
00137       cam_param_.mat[0][3] = cam_info_.P[3];
00138       cam_param_.mat[1][3] = cam_info_.P[7];
00139       cam_param_.mat[2][3] = cam_info_.P[11];
00140      
00141           cam_param_.dist_factor[0] = cam_info_.K[2];       // x0 = cX from openCV calibration
00142       cam_param_.dist_factor[1] = cam_info_.K[5];       // y0 = cY from openCV calibration
00143       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
00144       cam_param_.dist_factor[3] = 1.0;                  // scale factor, should probably be >1, but who cares...
00145              
00146       arInit();
00147 
00148       ROS_INFO ("Subscribing to image topic");
00149       cam_sub_ = it_.subscribe (cameraImageTopic_, 1, &ARSinglePublisher::getTransformationCallback, this);
00150       getCamInfo_ = true;
00151     }
00152   }
00153 
00154   void ARSinglePublisher::arInit ()
00155   {   
00156     arInitCparam (&cam_param_);
00157 
00158     ROS_INFO ("*** Camera Parameter ***");
00159     arParamDisp (&cam_param_);
00160 
00161     // load pattern file
00162     ROS_INFO ("Loading pattern");
00163     patt_id_ = arLoadPatt (pattern_filename_);
00164     if (patt_id_ < 0)
00165     {
00166       ROS_ERROR ("Pattern file load error: %s", pattern_filename_);
00167       ROS_BREAK ();
00168     }
00169 
00170     sz_ = cvSize (cam_param_.xsize, cam_param_.ysize);
00171     capture_ = cvCreateImage (sz_, IPL_DEPTH_8U, 4);
00172   }
00173 
00174   void ARSinglePublisher::getTransformationCallback (const sensor_msgs::ImageConstPtr & image_msg)
00175   {
00176     ARUint8 *dataPtr;
00177     ARMarkerInfo *marker_info;
00178     int marker_num;
00179     int i, k;
00180 
00181     /* Get the image from ROSTOPIC
00182      * NOTE: the dataPtr format is BGR because the ARToolKit library was
00183      * build with V4L, dataPtr format change according to the 
00184      * ARToolKit configure option (see config.h).*/
00185     try
00186     {
00187       capture_ = bridge_.imgMsgToCv (image_msg, "bgr8");
00188     }
00189     catch (sensor_msgs::CvBridgeException & e)
00190     {
00191       ROS_ERROR ("Could not convert from '%s' to 'bgr8'.", image_msg->encoding.c_str ());
00192     }
00193     //cvConvertImage(capture_,capture_,CV_CVTIMG_FLIP); //flip image
00194     dataPtr = (ARUint8 *) capture_->imageData;
00195 
00196     // detect the markers in the video frame 
00197     if (arDetectMarker (dataPtr, threshold_, &marker_info, &marker_num) < 0)
00198     {
00199       ROS_FATAL ("arDetectMarker failed");
00200       ROS_BREAK ();             // FIXME: I don't think this should be fatal... -Bill
00201     }
00202 
00203     // check for known patterns
00204     k = -1;
00205     for (i = 0; i < marker_num; i++)
00206     {
00207       if (marker_info[i].id == patt_id_)
00208       {
00209         ROS_DEBUG ("Found pattern: %d ", patt_id_);
00210 
00211         // make sure you have the best pattern (highest confidence factor)
00212         if (k == -1)
00213           k = i;
00214         else if (marker_info[k].cf < marker_info[i].cf)
00215           k = i;
00216       }
00217     }
00218 
00219     if (k != -1)
00220     {
00221       // **** get the transformation between the marker and the real camera
00222       double arQuat[4], arPos[3];
00223 
00224       if (!useHistory_ || contF == 0)
00225         arGetTransMat (&marker_info[k], marker_center_, markerWidth_, marker_trans_);
00226       else
00227         arGetTransMatCont (&marker_info[k], marker_trans_, marker_center_, markerWidth_, marker_trans_);
00228 
00229       contF = 1;
00230 
00231       //arUtilMatInv (marker_trans_, cam_trans);
00232       arUtilMat2QuatPos (marker_trans_, arQuat, arPos);
00233 
00234       // **** convert to ROS frame
00235 
00236       double quat[4], pos[3];
00237     
00238       pos[0] = arPos[0] * AR_TO_ROS;
00239       pos[1] = arPos[1] * AR_TO_ROS;
00240       pos[2] = arPos[2] * AR_TO_ROS;
00241 
00242       quat[0] = -arQuat[0];
00243       quat[1] = -arQuat[1];
00244       quat[2] = -arQuat[2];
00245       quat[3] = arQuat[3];
00246 
00247       ROS_DEBUG (" QUAT: Pos x: %3.5f  y: %3.5f  z: %3.5f", pos[0], pos[1], pos[2]);
00248       ROS_DEBUG ("     Quat qx: %3.5f qy: %3.5f qz: %3.5f qw: %3.5f", quat[0], quat[1], quat[2], quat[3]);
00249 
00250       // **** publish the marker
00251 
00252                   ar_pose_marker_.header.frame_id = image_msg->header.frame_id;
00253                   ar_pose_marker_.header.stamp    = image_msg->header.stamp;
00254                   ar_pose_marker_.id              = marker_info->id;
00255 
00256                   ar_pose_marker_.pose.pose.position.x = pos[0];
00257                   ar_pose_marker_.pose.pose.position.y = pos[1];
00258                   ar_pose_marker_.pose.pose.position.z = pos[2];
00259 
00260                   ar_pose_marker_.pose.pose.orientation.x = quat[0];
00261                   ar_pose_marker_.pose.pose.orientation.y = quat[1];
00262                   ar_pose_marker_.pose.pose.orientation.z = quat[2];
00263                   ar_pose_marker_.pose.pose.orientation.w = quat[3];
00264                 
00265                   ar_pose_marker_.confidence = marker_info->cf;
00266 
00267                   arMarkerPub_.publish(ar_pose_marker_);
00268                   ROS_DEBUG ("Published ar_single marker");
00269                 
00270       // **** publish transform between camera and marker
00271 
00272       btQuaternion rotation (quat[0], quat[1], quat[2], quat[3]);
00273       btVector3 origin(pos[0], pos[1], pos[2]);
00274       btTransform t(rotation, origin);
00275 
00276       if(publishTf_)
00277       {
00278         if(reverse_transform_)
00279         {
00280           tf::StampedTransform markerToCam (t.inverse(), image_msg->header.stamp, markerFrame_.c_str(), image_msg->header.frame_id);
00281           broadcaster_.sendTransform(markerToCam);
00282         } else {
00283           tf::StampedTransform camToMarker (t, image_msg->header.stamp, image_msg->header.frame_id, markerFrame_.c_str());
00284           broadcaster_.sendTransform(camToMarker);
00285         }
00286       }
00287 
00288       // **** publish visual marker
00289 
00290       if(publishVisualMarkers_)
00291       {
00292         btVector3 markerOrigin(0, 0, 0.25 * markerWidth_ * AR_TO_ROS);
00293         btTransform m(btQuaternion::getIdentity(), markerOrigin);
00294         btTransform markerPose = t * m; // marker pose in the camera frame
00295       
00296         tf::poseTFToMsg(markerPose, rvizMarker_.pose);
00297 
00298                           rvizMarker_.header.frame_id = image_msg->header.frame_id;
00299                           rvizMarker_.header.stamp = image_msg->header.stamp;
00300                           rvizMarker_.id = 1;
00301 
00302                           rvizMarker_.scale.x = 1.0 * markerWidth_ * AR_TO_ROS;
00303                           rvizMarker_.scale.y = 1.0 * markerWidth_ * AR_TO_ROS;
00304                           rvizMarker_.scale.z = 0.5 * markerWidth_ * AR_TO_ROS;
00305                           rvizMarker_.ns = "basic_shapes";
00306                           rvizMarker_.type = visualization_msgs::Marker::CUBE;
00307                           rvizMarker_.action = visualization_msgs::Marker::ADD;
00308                           rvizMarker_.color.r = 0.0f;
00309                           rvizMarker_.color.g = 1.0f;
00310                           rvizMarker_.color.b = 0.0f;
00311                           rvizMarker_.color.a = 1.0;
00312                           rvizMarker_.lifetime = ros::Duration(1.0);
00313                         
00314                           rvizMarkerPub_.publish(rvizMarker_);
00315                           ROS_DEBUG ("Published visual marker");
00316       }
00317     }
00318     else
00319     {
00320       contF = 0;
00321       ROS_DEBUG ("Failed to locate marker");
00322     }
00323   }
00324 }                               // end namespace ar_pose
00325 
 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