checkerboard_finder.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2015 Fetch Robotics Inc.
00003  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
00004  *
00005  * Licensed under the Apache License, Version 2.0 (the "License");
00006  * you may not use this file except in compliance with the License.
00007  * You may obtain a copy of the License at
00008  *
00009  *     http://www.apache.org/licenses/LICENSE-2.0
00010  *
00011  * Unless required by applicable law or agreed to in writing, software
00012  * distributed under the License is distributed on an "AS IS" BASIS,
00013  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014  * See the License for the specific language governing permissions and
00015  * limitations under the License.
00016  */
00017 
00018 // Author: Michael Ferguson
00019 
00020 #ifndef ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H
00021 #define ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H
00022 
00023 #include <ros/ros.h>
00024 #include <robot_calibration/capture/depth_camera.h>
00025 #include <robot_calibration/capture/feature_finder.h>
00026 #include <robot_calibration_msgs/CalibrationData.h>
00027 
00028 #include <opencv2/calib3d/calib3d.hpp>
00029 #include <cv_bridge/cv_bridge.h>
00030 
00031 namespace robot_calibration
00032 {
00033 
00037 class CheckerboardFinder : public FeatureFinder
00038 {
00039 public:
00040   CheckerboardFinder(ros::NodeHandle & n);
00041 
00049   bool find(robot_calibration_msgs::CalibrationData * msg);
00050 
00051 private:
00052   bool findInternal(robot_calibration_msgs::CalibrationData * msg);
00053 
00054   void cameraCallback(const sensor_msgs::PointCloud2& cloud);
00055   bool waitForCloud();
00056 
00057   ros::Subscriber subscriber_;  
00058   ros::Publisher publisher_;   
00059 
00060   bool waiting_;
00061   sensor_msgs::PointCloud2 cloud_;
00062   DepthCameraInfoManager depth_camera_manager_;
00063 
00064   /*
00065    * ROS Parameters
00066    */
00067   int points_x_;        
00068   int points_y_;        
00069 
00070   double square_size_;     
00071 
00072   bool output_debug_;   
00073 
00074   std::string camera_sensor_name_;
00075   std::string chain_sensor_name_;
00076 };
00077 
00078 }  // namespace robot_calibration
00079 
00080 #endif  // ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H


robot_calibration
Author(s): Michael Ferguson
autogenerated on Thu Jun 6 2019 21:54:10