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_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 ros::NodeHandle n_param ("~");
00042 XmlRpc::XmlRpcValue xml_marker_center;
00043
00044
00045
00046 if (!n_param.getParam ("publish_tf", publishTf_))
00047 publishTf_ = true;
00048 ROS_INFO ("\tPublish transforms: %d", publishTf_);
00049
00050 if (!n_param.getParam ("publish_visual_markers", publishVisualMarkers_))
00051 publishVisualMarkers_ = true;
00052 ROS_INFO ("\tPublish visual markers: %d", publishVisualMarkers_);
00053
00054 if (!n_param.getParam ("threshold", threshold_))
00055 threshold_ = 100;
00056 ROS_INFO ("\tThreshold: %d", threshold_);
00057
00058 n_param.param ("marker_pattern_list", local_path, std::string ("data/object_data2"));
00059 sprintf (pattern_filename_, "%s/%s", package_path.c_str (), local_path.c_str ());
00060 ROS_INFO ("Marker Pattern Filename: %s", pattern_filename_);
00061
00062
00063
00064 ROS_INFO ("Subscribing to info topic");
00065 sub_ = n_.subscribe (cameraInfoTopic_, 1, &ARSinglePublisher::camInfoCallback, this);
00066 getCamInfo_ = false;
00067
00068
00069
00070 arMarkerPub_ = n_.advertise < ar_pose::ARMarkers > ("ar_pose_marker", 0);
00071 if(publishVisualMarkers_)
00072 {
00073 rvizMarkerPub_ = n_.advertise < visualization_msgs::Marker > ("visualization_marker", 0);
00074 }
00075 }
00076
00077 ARSinglePublisher::~ARSinglePublisher (void)
00078 {
00079
00080 arVideoCapStop ();
00081 arVideoClose ();
00082 }
00083
00084 void ARSinglePublisher::camInfoCallback (const sensor_msgs::CameraInfoConstPtr & cam_info)
00085 {
00086 if (!getCamInfo_)
00087 {
00088 cam_info_ = (*cam_info);
00089
00090 cam_param_.xsize = cam_info_.width;
00091 cam_param_.ysize = cam_info_.height;
00092
00093 cam_param_.mat[0][0] = cam_info_.P[0];
00094 cam_param_.mat[1][0] = cam_info_.P[4];
00095 cam_param_.mat[2][0] = cam_info_.P[8];
00096 cam_param_.mat[0][1] = cam_info_.P[1];
00097 cam_param_.mat[1][1] = cam_info_.P[5];
00098 cam_param_.mat[2][1] = cam_info_.P[9];
00099 cam_param_.mat[0][2] = cam_info_.P[2];
00100 cam_param_.mat[1][2] = cam_info_.P[6];
00101 cam_param_.mat[2][2] = cam_info_.P[10];
00102 cam_param_.mat[0][3] = cam_info_.P[3];
00103 cam_param_.mat[1][3] = cam_info_.P[7];
00104 cam_param_.mat[2][3] = cam_info_.P[11];
00105
00106 cam_param_.dist_factor[0] = cam_info_.K[2];
00107 cam_param_.dist_factor[1] = cam_info_.K[5];
00108 cam_param_.dist_factor[2] = -100*cam_info_.D[0];
00109 cam_param_.dist_factor[3] = 1.0;
00110
00111 arInit ();
00112
00113 ROS_INFO ("Subscribing to image topic");
00114 cam_sub_ = it_.subscribe (cameraImageTopic_, 1, &ARSinglePublisher::getTransformationCallback, this);
00115 getCamInfo_ = true;
00116 }
00117 }
00118
00119 void ARSinglePublisher::arInit ()
00120 {
00121 arInitCparam (&cam_param_);
00122 ROS_INFO ("*** Camera Parameter ***");
00123 arParamDisp (&cam_param_);
00124
00125
00126 if ((object = ar_object::read_ObjData (pattern_filename_, &objectnum)) == NULL)
00127 ROS_BREAK ();
00128 ROS_DEBUG ("Objectfile num = %d", objectnum);
00129
00130 sz_ = cvSize (cam_param_.xsize, cam_param_.ysize);
00131 capture_ = cvCreateImage (sz_, IPL_DEPTH_8U, 4);
00132 }
00133
00134 void ARSinglePublisher::getTransformationCallback (const sensor_msgs::ImageConstPtr & image_msg)
00135 {
00136 ARUint8 *dataPtr;
00137 ARMarkerInfo *marker_info;
00138 int marker_num;
00139 int i, k, j;
00140
00141
00142
00143
00144
00145 try
00146 {
00147 capture_ = bridge_.imgMsgToCv (image_msg, "bgr8");
00148 }
00149 catch (sensor_msgs::CvBridgeException & e)
00150 {
00151 ROS_ERROR ("Could not convert from '%s' to 'bgr8'.", image_msg->encoding.c_str ());
00152 }
00153
00154 dataPtr = (ARUint8 *) capture_->imageData;
00155
00156
00157 if (arDetectMarker (dataPtr, threshold_, &marker_info, &marker_num) < 0)
00158 {
00159 argCleanup ();
00160 ROS_BREAK ();
00161 }
00162
00163 arPoseMarkers_.markers.clear ();
00164
00165 for (i = 0; i < objectnum; i++)
00166 {
00167 k = -1;
00168 for (j = 0; j < marker_num; j++)
00169 {
00170 if (object[i].id == marker_info[j].id)
00171 {
00172 if (k == -1)
00173 k = j;
00174 else
00175 if (marker_info[k].cf < marker_info[j].cf)
00176 k = j;
00177 }
00178 }
00179 if (k == -1)
00180 {
00181 object[i].visible = 0;
00182 continue;
00183 }
00184
00185
00186 if (object[i].visible == 0)
00187 {
00188 arGetTransMat (&marker_info[k], object[i].marker_center, object[i].marker_width, object[i].trans);
00189 }
00190 else
00191 {
00192 arGetTransMatCont (&marker_info[k], object[i].trans,
00193 object[i].marker_center, object[i].marker_width, object[i].trans);
00194 }
00195 object[i].visible = 1;
00196
00197 double arQuat[4], arPos[3];
00198
00199
00200 arUtilMat2QuatPos (object[i].trans, arQuat, arPos);
00201
00202
00203
00204 double quat[4], pos[3];
00205
00206 pos[0] = arPos[0] * AR_TO_ROS;
00207 pos[1] = arPos[1] * AR_TO_ROS;
00208 pos[2] = arPos[2] * AR_TO_ROS;
00209
00210 quat[0] = -arQuat[0];
00211 quat[1] = -arQuat[1];
00212 quat[2] = -arQuat[2];
00213 quat[3] = arQuat[3];
00214
00215 ROS_DEBUG (" Object num %i ------------------------------------------------", i);
00216 ROS_DEBUG (" QUAT: Pos x: %3.5f y: %3.5f z: %3.5f", pos[0], pos[1], pos[2]);
00217 ROS_DEBUG (" Quat qx: %3.5f qy: %3.5f qz: %3.5f qw: %3.5f", quat[0], quat[1], quat[2], quat[3]);
00218
00219
00220
00221 ar_pose::ARMarker ar_pose_marker;
00222 ar_pose_marker.header.frame_id = image_msg->header.frame_id;
00223 ar_pose_marker.header.stamp = image_msg->header.stamp;
00224 ar_pose_marker.id = object[i].id;
00225
00226 ar_pose_marker.pose.pose.position.x = pos[0];
00227 ar_pose_marker.pose.pose.position.y = pos[1];
00228 ar_pose_marker.pose.pose.position.z = pos[2];
00229
00230 ar_pose_marker.pose.pose.orientation.x = quat[0];
00231 ar_pose_marker.pose.pose.orientation.y = quat[1];
00232 ar_pose_marker.pose.pose.orientation.z = quat[2];
00233 ar_pose_marker.pose.pose.orientation.w = quat[3];
00234
00235 ar_pose_marker.confidence = marker_info->cf;
00236 arPoseMarkers_.markers.push_back (ar_pose_marker);
00237
00238
00239
00240 btQuaternion rotation (quat[0], quat[1], quat[2], quat[3]);
00241 btVector3 origin (pos[0], pos[1], pos[2]);
00242 btTransform t (rotation, origin);
00243
00244 if (publishTf_)
00245 {
00246 tf::StampedTransform camToMarker (t, image_msg->header.stamp, image_msg->header.frame_id, object[i].name);
00247 broadcaster_.sendTransform(camToMarker);
00248 }
00249
00250
00251
00252 if (publishVisualMarkers_)
00253 {
00254 btVector3 markerOrigin (0, 0, 0.25 * object[i].marker_width * AR_TO_ROS);
00255 btTransform m (btQuaternion::getIdentity (), markerOrigin);
00256 btTransform markerPose = t * m;
00257
00258 tf::poseTFToMsg (markerPose, rvizMarker_.pose);
00259
00260 rvizMarker_.header.frame_id = image_msg->header.frame_id;
00261 rvizMarker_.header.stamp = image_msg->header.stamp;
00262 rvizMarker_.id = object[i].id;
00263
00264 rvizMarker_.scale.x = 1.0 * object[i].marker_width * AR_TO_ROS;
00265 rvizMarker_.scale.y = 1.0 * object[i].marker_width * AR_TO_ROS;
00266 rvizMarker_.scale.z = 0.5 * object[i].marker_width * AR_TO_ROS;
00267 rvizMarker_.ns = "basic_shapes";
00268 rvizMarker_.type = visualization_msgs::Marker::CUBE;
00269 rvizMarker_.action = visualization_msgs::Marker::ADD;
00270 switch (i)
00271 {
00272 case 0:
00273 rvizMarker_.color.r = 0.0f;
00274 rvizMarker_.color.g = 0.0f;
00275 rvizMarker_.color.b = 1.0f;
00276 rvizMarker_.color.a = 1.0;
00277 break;
00278 case 1:
00279 rvizMarker_.color.r = 1.0f;
00280 rvizMarker_.color.g = 0.0f;
00281 rvizMarker_.color.b = 0.0f;
00282 rvizMarker_.color.a = 1.0;
00283 break;
00284 default:
00285 rvizMarker_.color.r = 0.0f;
00286 rvizMarker_.color.g = 1.0f;
00287 rvizMarker_.color.b = 0.0f;
00288 rvizMarker_.color.a = 1.0;
00289 }
00290 rvizMarker_.lifetime = ros::Duration ();
00291
00292 rvizMarkerPub_.publish (rvizMarker_);
00293 ROS_DEBUG ("Published visual marker");
00294 }
00295 }
00296 arMarkerPub_.publish (arPoseMarkers_);
00297 ROS_DEBUG ("Published ar_multi markers");
00298 }
00299 }