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/CvBridge.h> 00054 00055 #include <ar_pose/ARMarkers.h> 00056 #include <ar_pose/ARMarker.h> 00057 #include <ar_kinect/object.h> 00058 00059 const std::string cloudTopic_ = "points"; 00060 00061 const double AR_TO_ROS = 0.001; 00062 typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud; 00063 typedef pcl::registration::TransformationEstimationSVD<pcl::PointXYZRGB, pcl::PointXYZRGB> TransformationEstimationSVD; 00064 00065 namespace ar_pose 00066 { 00067 class ARPublisher 00068 { 00069 public: 00070 ARPublisher (ros::NodeHandle & n); 00071 ~ARPublisher (void); 00072 00073 private: 00074 void arInit (); 00075 void getTransformationCallback (const sensor_msgs::PointCloud2ConstPtr &); 00076 00077 ros::NodeHandle n_; 00078 tf::TransformBroadcaster broadcaster_; 00079 ros::Subscriber cloud_sub_; 00080 ros::Publisher arMarkerPub_; 00081 00082 sensor_msgs::CvBridge bridge_; 00083 00084 // **** for visualisation in rviz 00085 ros::Publisher rvizMarkerPub_; 00086 visualization_msgs::Marker rvizMarker_; 00087 00088 // **** parameters 00089 ARParam cam_param_; // Camera Calibration Parameters 00090 ARMultiMarkerInfoT *config; // AR Marker Info 00091 ar_object::ObjectData_T * object; 00092 int objectnum; 00093 char pattern_filename_[FILENAME_MAX]; 00094 char data_directory_[FILENAME_MAX]; 00095 00096 ar_pose::ARMarkers arPoseMarkers_; 00097 int threshold_; 00098 bool getCamInfo_; 00099 bool publishTf_; 00100 bool publishVisualMarkers_; 00101 CvSize sz_; 00102 IplImage *capture_; 00103 bool configured_; 00104 }; // end class ARPublisher 00105 } //end namespace ar_pose 00106 00107 #endif