checkerboard_finder.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 Michael Ferguson
3  * Copyright (C) 2015 Fetch Robotics Inc.
4  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 // Author: Michael Ferguson
20 
21 #ifndef ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H
22 #define ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H
23 
24 #include <ros/ros.h>
27 #include <robot_calibration_msgs/CalibrationData.h>
28 
29 #include <opencv2/calib3d/calib3d.hpp>
30 #include <cv_bridge/cv_bridge.h>
31 
32 namespace robot_calibration
33 {
34 
39 {
40 public:
42  bool init(const std::string& name, ros::NodeHandle & n);
43  bool find(robot_calibration_msgs::CalibrationData * msg);
44 
45 private:
46  bool findInternal(robot_calibration_msgs::CalibrationData * msg);
47 
48  void cameraCallback(const sensor_msgs::PointCloud2& cloud);
49  bool waitForCloud();
50 
53 
54  bool waiting_;
55  sensor_msgs::PointCloud2 cloud_;
57 
58  /*
59  * ROS Parameters
60  */
61  int points_x_;
62  int points_y_;
63 
64  double square_size_;
65 
67 
68  std::string frame_id_;
69 
70  std::string camera_sensor_name_;
71  std::string chain_sensor_name_;
72 };
73 
74 } // namespace robot_calibration
75 
76 #endif // ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H
bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called...
void cameraCallback(const sensor_msgs::PointCloud2 &cloud)
Base class for a feature finder.
ros::Publisher publisher_
Incoming sensor_msgs::PointCloud2.
bool findInternal(robot_calibration_msgs::CalibrationData *msg)
This class processes the point cloud input to find a checkerboard.
double square_size_
Size of checkerboard.
std::string camera_sensor_name_
Name of checkerboard frame.
std::string frame_id_
Should we output debug image/cloud?
bool output_debug_
Size of a square on checkboard (in meters)
Calibration code lives under this namespace.
bool waiting_
Outgoing sensor_msgs::PointCloud2.
bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Base class for a feature finder.
Definition: depth_camera.h:32
DepthCameraInfoManager depth_camera_manager_


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30