checkerboard_finder.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2023 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 
38 template <typename T>
40 {
41 public:
43  bool init(const std::string& name, ros::NodeHandle & n);
44  bool find(robot_calibration_msgs::CalibrationData * msg);
45 
46 private:
47  bool findInternal(robot_calibration_msgs::CalibrationData * msg);
48  bool findCheckerboardPoints(const sensor_msgs::ImagePtr& msg,
49  std::vector<cv::Point2f>& points);
50 
51  void cameraCallback(const T& msg);
52  bool waitForMsg();
53 
56 
57  bool waiting_;
58  T msg_;
60 
61  /*
62  * ROS Parameters
63  */
64  int points_x_;
65  int points_y_;
66 
67  double square_size_;
68 
70 
71  std::string frame_id_;
72 
73  std::string camera_sensor_name_;
74  std::string chain_sensor_name_;
75 };
76 
77 } // namespace robot_calibration
78 
79 #endif // ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H
bool findCheckerboardPoints(const sensor_msgs::ImagePtr &msg, std::vector< cv::Point2f > &points)
bool findInternal(robot_calibration_msgs::CalibrationData *msg)
bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called...
Base class for a feature finder.
bool output_debug_
Size of a square on checkboard (in meters)
double square_size_
Size of checkerboard.
Finds checkerboards in images or point clouds.
ros::Publisher publisher_
Incoming message.
DepthCameraInfoManager depth_camera_manager_
std::string frame_id_
Should we output debug image/cloud?
bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Calibration code lives under this namespace.
Base class for a feature finder.
Definition: depth_camera.h:32
std::string camera_sensor_name_
Name of checkerboard frame.
bool waiting_
Outgoing sensor_msgs::PointCloud2.


robot_calibration
Author(s): Michael Ferguson
autogenerated on Wed May 24 2023 02:30:23