00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
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 ros::NodeHandle n_param ("~");
00041 XmlRpc::XmlRpcValue xml_marker_center;
00042
00043 ROS_INFO("Starting ArSinglePublisher");
00044
00045
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 if (!n_param.getParam("marker_width", markerWidth_))
00060 markerWidth_ = 80.0;
00061 ROS_INFO ("\tMarker Width: %.1f", markerWidth_);
00062
00063 if (!n_param.getParam("reverse_transform", reverse_transform_))
00064 reverse_transform_ = false;
00065 ROS_INFO("\tReverse Transform: %d", reverse_transform_);
00066
00067 if (!n_param.getParam("marker_frame", markerFrame_))
00068 markerFrame_ = "ar_marker";
00069 ROS_INFO ("\tMarker frame: %s", markerFrame_.c_str());
00070
00071
00072
00073
00074 if (!n_param.getParam("use_history", useHistory_))
00075 useHistory_ = true;
00076 ROS_INFO("\tUse history: %d", useHistory_);
00077
00078 n_param.param ("marker_pattern", local_path, std::string ("data/patt.hiro"));
00079 sprintf (pattern_filename_, "%s/%s", package_path.c_str (), local_path.c_str ());
00080 ROS_INFO ("\tMarker Pattern Filename: %s", pattern_filename_);
00081
00082 n_param.param ("marker_center_x", marker_center_[0], 0.0);
00083 n_param.param ("marker_center_y", marker_center_[1], 0.0);
00084 ROS_INFO ("\tMarker Center: (%.1f,%.1f)", marker_center_[0], marker_center_[1]);
00085
00086
00087
00088 ROS_INFO ("Subscribing to info topic");
00089 sub_ = n_.subscribe (cameraInfoTopic_, 1, &ARSinglePublisher::camInfoCallback, this);
00090 getCamInfo_ = false;
00091
00092
00093
00094 arMarkerPub_ = n_.advertise<ar_pose::ARMarker>("ar_pose_marker", 0);
00095 if(publishVisualMarkers_){
00096 rvizMarkerPub_ = n_.advertise<visualization_msgs::Marker>("visualization_marker", 0);
00097 }
00098 }
00099
00100 ARSinglePublisher::~ARSinglePublisher (void)
00101 {
00102
00103 arVideoCapStop ();
00104 arVideoClose ();
00105 }
00106
00107 void ARSinglePublisher::camInfoCallback (const sensor_msgs::CameraInfoConstPtr & cam_info)
00108 {
00109 if (!getCamInfo_)
00110 {
00111 cam_info_ = (*cam_info);
00112
00113 cam_param_.xsize = cam_info_.width;
00114 cam_param_.ysize = cam_info_.height;
00115
00116 cam_param_.mat[0][0] = cam_info_.P[0];
00117 cam_param_.mat[1][0] = cam_info_.P[4];
00118 cam_param_.mat[2][0] = cam_info_.P[8];
00119 cam_param_.mat[0][1] = cam_info_.P[1];
00120 cam_param_.mat[1][1] = cam_info_.P[5];
00121 cam_param_.mat[2][1] = cam_info_.P[9];
00122 cam_param_.mat[0][2] = cam_info_.P[2];
00123 cam_param_.mat[1][2] = cam_info_.P[6];
00124 cam_param_.mat[2][2] = cam_info_.P[10];
00125 cam_param_.mat[0][3] = cam_info_.P[3];
00126 cam_param_.mat[1][3] = cam_info_.P[7];
00127 cam_param_.mat[2][3] = cam_info_.P[11];
00128
00129 cam_param_.dist_factor[0] = cam_info_.K[2];
00130 cam_param_.dist_factor[1] = cam_info_.K[5];
00131 cam_param_.dist_factor[2] = -100*cam_info_.D[0];
00132 cam_param_.dist_factor[3] = 1.0;
00133
00134 arInit();
00135
00136 ROS_INFO ("Subscribing to image topic");
00137 cam_sub_ = it_.subscribe (cameraImageTopic_, 1, &ARSinglePublisher::getTransformationCallback, this);
00138 getCamInfo_ = true;
00139 }
00140 }
00141
00142 void ARSinglePublisher::arInit ()
00143 {
00144 arInitCparam (&cam_param_);
00145
00146 ROS_INFO ("*** Camera Parameter ***");
00147 arParamDisp (&cam_param_);
00148
00149
00150 ROS_INFO ("Loading pattern");
00151 patt_id_ = arLoadPatt (pattern_filename_);
00152 if (patt_id_ < 0)
00153 {
00154 ROS_ERROR ("Pattern file load error: %s", pattern_filename_);
00155 ROS_BREAK ();
00156 }
00157
00158 sz_ = cvSize (cam_param_.xsize, cam_param_.ysize);
00159 capture_ = cvCreateImage (sz_, IPL_DEPTH_8U, 4);
00160 }
00161
00162 void ARSinglePublisher::getTransformationCallback (const sensor_msgs::ImageConstPtr & image_msg)
00163 {
00164 ARUint8 *dataPtr;
00165 ARMarkerInfo *marker_info;
00166 int marker_num;
00167 int i, k;
00168
00169
00170
00171
00172
00173 try
00174 {
00175 capture_ = bridge_.imgMsgToCv (image_msg, "bgr8");
00176 }
00177 catch (sensor_msgs::CvBridgeException & e)
00178 {
00179 ROS_ERROR ("Could not convert from '%s' to 'bgr8'.", image_msg->encoding.c_str ());
00180 }
00181
00182 dataPtr = (ARUint8 *) capture_->imageData;
00183
00184
00185 if (arDetectMarker (dataPtr, threshold_, &marker_info, &marker_num) < 0)
00186 {
00187 ROS_FATAL ("arDetectMarker failed");
00188 ROS_BREAK ();
00189 }
00190
00191
00192 k = -1;
00193 for (i = 0; i < marker_num; i++)
00194 {
00195 if (marker_info[i].id == patt_id_)
00196 {
00197 ROS_DEBUG ("Found pattern: %d ", patt_id_);
00198
00199
00200 if (k == -1)
00201 k = i;
00202 else if (marker_info[k].cf < marker_info[i].cf)
00203 k = i;
00204 }
00205 }
00206
00207 if (k != -1)
00208 {
00209
00210 double arQuat[4], arPos[3];
00211
00212 if (!useHistory_ || contF == 0)
00213 arGetTransMat (&marker_info[k], marker_center_, markerWidth_, marker_trans_);
00214 else
00215 arGetTransMatCont (&marker_info[k], marker_trans_, marker_center_, markerWidth_, marker_trans_);
00216
00217 contF = 1;
00218
00219
00220 arUtilMat2QuatPos (marker_trans_, arQuat, arPos);
00221
00222
00223
00224 double quat[4], pos[3];
00225
00226 pos[0] = arPos[0] * AR_TO_ROS;
00227 pos[1] = arPos[1] * AR_TO_ROS;
00228 pos[2] = arPos[2] * AR_TO_ROS;
00229
00230 quat[0] = -arQuat[0];
00231 quat[1] = -arQuat[1];
00232 quat[2] = -arQuat[2];
00233 quat[3] = arQuat[3];
00234
00235 ROS_DEBUG (" QUAT: Pos x: %3.5f y: %3.5f z: %3.5f", pos[0], pos[1], pos[2]);
00236 ROS_DEBUG (" Quat qx: %3.5f qy: %3.5f qz: %3.5f qw: %3.5f", quat[0], quat[1], quat[2], quat[3]);
00237
00238
00239
00240 ar_pose_marker_.header.frame_id = image_msg->header.frame_id;
00241 ar_pose_marker_.header.stamp = image_msg->header.stamp;
00242 ar_pose_marker_.id = marker_info->id;
00243
00244 ar_pose_marker_.pose.pose.position.x = pos[0];
00245 ar_pose_marker_.pose.pose.position.y = pos[1];
00246 ar_pose_marker_.pose.pose.position.z = pos[2];
00247
00248 ar_pose_marker_.pose.pose.orientation.x = quat[0];
00249 ar_pose_marker_.pose.pose.orientation.y = quat[1];
00250 ar_pose_marker_.pose.pose.orientation.z = quat[2];
00251 ar_pose_marker_.pose.pose.orientation.w = quat[3];
00252
00253 ar_pose_marker_.confidence = marker_info->cf;
00254
00255 arMarkerPub_.publish(ar_pose_marker_);
00256 ROS_DEBUG ("Published ar_single marker");
00257
00258
00259
00260 btQuaternion rotation (quat[0], quat[1], quat[2], quat[3]);
00261 btVector3 origin(pos[0], pos[1], pos[2]);
00262 btTransform t(rotation, origin);
00263
00264 if(publishTf_)
00265 {
00266 if(reverse_transform_)
00267 {
00268 tf::StampedTransform markerToCam (t.inverse(), image_msg->header.stamp, markerFrame_.c_str(), image_msg->header.frame_id);
00269 broadcaster_.sendTransform(markerToCam);
00270 } else {
00271 tf::StampedTransform camToMarker (t, image_msg->header.stamp, image_msg->header.frame_id, markerFrame_.c_str());
00272 broadcaster_.sendTransform(camToMarker);
00273 }
00274 }
00275
00276
00277
00278 if(publishVisualMarkers_)
00279 {
00280 btVector3 markerOrigin(0, 0, 0.25 * markerWidth_ * AR_TO_ROS);
00281 btTransform m(btQuaternion::getIdentity(), markerOrigin);
00282 btTransform markerPose = t * m;
00283
00284 tf::poseTFToMsg(markerPose, rvizMarker_.pose);
00285
00286 rvizMarker_.header.frame_id = image_msg->header.frame_id;
00287 rvizMarker_.header.stamp = image_msg->header.stamp;
00288 rvizMarker_.id = 1;
00289
00290 rvizMarker_.scale.x = 1.0 * markerWidth_ * AR_TO_ROS;
00291 rvizMarker_.scale.y = 1.0 * markerWidth_ * AR_TO_ROS;
00292 rvizMarker_.scale.z = 0.5 * markerWidth_ * AR_TO_ROS;
00293 rvizMarker_.ns = "basic_shapes";
00294 rvizMarker_.type = visualization_msgs::Marker::CUBE;
00295 rvizMarker_.action = visualization_msgs::Marker::ADD;
00296 rvizMarker_.color.r = 0.0f;
00297 rvizMarker_.color.g = 1.0f;
00298 rvizMarker_.color.b = 0.0f;
00299 rvizMarker_.color.a = 1.0;
00300 rvizMarker_.lifetime = ros::Duration();
00301
00302 rvizMarkerPub_.publish(rvizMarker_);
00303 ROS_DEBUG ("Published visual marker");
00304 }
00305 }
00306 else
00307 {
00308 contF = 0;
00309 ROS_DEBUG ("Failed to locate marker");
00310 }
00311 }
00312 }
00313