ros_camera_observer.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Apache License)
00003  *
00004  * Copyright (c) 2014, Southwest Research Institute
00005  *
00006  * Licensed under the Apache License, Version 2.0 (the "License");
00007  * you may not use this file except in compliance with the License.
00008  * You may obtain a copy of the License at
00009  *
00010  * http://www.apache.org/licenses/LICENSE-2.0
00011  *
00012  * Unless required by applicable law or agreed to in writing, software
00013  * distributed under the License is distributed on an "AS IS" BASIS,
00014  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015  * See the License for the specific language governing permissions and
00016  * limitations under the License.
00017  */
00018 
00019 #ifndef ROS_CAMERA_OBSERVER_H_
00020 #define ROS_CAMERA_OBSERVER_H_
00021 
00022 #include <industrial_extrinsic_cal/camera_observer.hpp>
00023 #include <industrial_extrinsic_cal/basic_types.h>
00024 
00025 #include <iostream>
00026 #include <sstream>
00027 #include <time.h>
00028 #include <stdio.h>
00029 
00030 #include <opencv2/core/core.hpp>
00031 #include <opencv2/imgproc/imgproc.hpp>
00032 #include <opencv2/calib3d/calib3d.hpp>
00033 #include <opencv2/highgui/highgui.hpp>
00034 
00035 #include <cv_bridge/cv_bridge.h>
00036 #include <image_transport/image_transport.h>
00037 
00038 #include <ros/ros.h>
00039 #include <sensor_msgs/Image.h>
00040 #include <sensor_msgs/CameraInfo.h>
00041 #include <geometry_msgs/PointStamped.h>
00042 
00046 namespace pattern_options
00047 {
00048 enum pattern_options_
00049 {
00050   Chessboard = 0, CircleGrid = 1, ARtag = 2
00051 };
00052 }
00053 typedef pattern_options::pattern_options_ PatternOption;
00054 
00055 namespace industrial_extrinsic_cal
00056 {
00057 
00058 class ROSCameraObserver : public CameraObserver
00059 {
00060 public:
00061 
00066   ROSCameraObserver(const std::string &image_topic);
00067 
00071   ~ROSCameraObserver()
00072   {
00073   }
00074   ;
00075 
00082   bool addTarget(boost::shared_ptr<Target> targ, Roi &roi);
00083 
00087   void clearTargets();
00088 
00092   void clearObservations();
00093 
00099   int getObservations(CameraObservations &camera_observations);
00100 
00102   void triggerCamera();
00103 
00105   bool observationsDone();
00106 
00107 private:
00108 
00109   PatternOption pattern_;
00113   std::string image_topic_;
00117   cv::Mat image_roi_;
00121   cv::Rect input_roi_;
00125   int pattern_rows_;
00129   int pattern_cols_;
00133   bool sym_circle_;
00137   std::vector<cv::Point2f> observation_pts_;
00141   boost::shared_ptr<Target> instance_target_;
00145   CameraObservations camera_obs_;
00146 
00147   //ROS specific params
00151   ros::NodeHandle nh_;
00155   ros::Subscriber image_sub_;
00159   ros::Publisher results_pub_;
00160 
00161   // Structures for interacting with ROS/CV messages
00165   cv_bridge::CvImagePtr input_bridge_;
00169   cv_bridge::CvImagePtr output_bridge_;
00173   cv_bridge::CvImagePtr out_bridge_;
00174 
00175 };
00176 
00177 } //end industrial_extrinsic_cal namespace
00178 
00179 #endif /* ROS_CAMERA_OBSERVER_H_ */


industrial_extrinsic_cal
Author(s): Chris Lewis
autogenerated on Wed Aug 26 2015 12:00:27