00001 /* 00002 * Multi Marker Pose Estimation using ARToolkit 00003 * Copyright (C) 2010, CCNY Robotics Lab, 2011 ILS 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 * Michael Ferguson <ferguson@cs.albany.edu> 00010 * http://robotics.ils.albany.edu 00011 * 00012 * This program is free software: you can redistribute it and/or modify 00013 * it under the terms of the GNU General Public License as published by 00014 * the Free Software Foundation, either version 3 of the License, or 00015 * (at your option) any later version. 00016 * 00017 * This program is distributed in the hope that it will be useful, 00018 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00019 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00020 * GNU General Public License for more details. 00021 * 00022 * You should have received a copy of the GNU General Public License 00023 * along with this program. If not, see <http://www.gnu.org/licenses/>. 00024 */ 00025 00026 #ifndef AR_POSE_AR_MULTI_H 00027 #define AR_POSE_AR_MULTI_H 00028 00029 #include <string.h> 00030 #include <stdarg.h> 00031 00032 #include <AR/gsub.h> 00033 #include <AR/video.h> 00034 #include <AR/param.h> 00035 #include <AR/ar.h> 00036 #include <AR/arMulti.h> 00037 00038 #include <ros/ros.h> 00039 #include <ros/package.h> 00040 #include <ros/console.h> 00041 #include <geometry_msgs/TransformStamped.h> 00042 #include <tf/transform_broadcaster.h> 00043 #include <visualization_msgs/Marker.h> 00044 00045 #include <sensor_msgs/PointCloud2.h> 00046 #include <pcl/ros/conversions.h> 00047 #include <pcl/point_types.h> 00048 #include <pcl/registration/icp.h> 00049 #include <pcl/registration/registration.h> 00050 #include <pcl/registration/transformation_estimation_svd.h> 00051 00052 #include <opencv/cv.h> 00053 #include <cv_bridge/cv_bridge.h> 00054 #include <sensor_msgs/image_encodings.h> 00055 00056 #include <ar_pose/ARMarkers.h> 00057 #include <ar_pose/ARMarker.h> 00058 #include <ar_kinect/object.h> 00059 00060 const std::string cloudTopic_ = "points"; 00061 00062 const double AR_TO_ROS = 0.001; 00063 typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud; 00064 typedef pcl::registration::TransformationEstimationSVD<pcl::PointXYZRGB, pcl::PointXYZRGB> TransformationEstimationSVD; 00065 00066 namespace ar_pose 00067 { 00068 class ARPublisher 00069 { 00070 public: 00071 ARPublisher (ros::NodeHandle & n); 00072 ~ARPublisher (void); 00073 00074 private: 00075 void arInit (); 00076 void getTransformationCallback (const sensor_msgs::PointCloud2ConstPtr &); 00077 00078 ros::NodeHandle n_; 00079 tf::TransformBroadcaster broadcaster_; 00080 ros::Subscriber cloud_sub_; 00081 ros::Publisher arMarkerPub_; 00082 00083 // **** for visualisation in rviz 00084 ros::Publisher rvizMarkerPub_; 00085 visualization_msgs::Marker rvizMarker_; 00086 00087 // **** parameters 00088 ARParam cam_param_; // Camera Calibration Parameters 00089 ARMultiMarkerInfoT *config; // AR Marker Info 00090 ar_object::ObjectData_T * object; 00091 int objectnum; 00092 char pattern_filename_[FILENAME_MAX]; 00093 char data_directory_[FILENAME_MAX]; 00094 00095 ar_pose::ARMarkers arPoseMarkers_; 00096 int threshold_; 00097 bool getCamInfo_; 00098 bool publishTf_; 00099 bool publishVisualMarkers_; 00100 CvSize sz_; 00101 IplImage *capture_; 00102 bool configured_; 00103 }; // end class ARPublisher 00104 } //end namespace ar_pose 00105 00106 #endif