checkerboard_finder.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 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 
24 
27 
28 namespace robot_calibration
29 {
30 
31 // We use a number of PC2 iterators, define the indexes here
32 const unsigned X = 0;
33 const unsigned Y = 1;
34 const unsigned Z = 2;
35 
36 template <typename T>
38  waiting_(false)
39 {
40 }
41 
42 template <typename T>
43 bool CheckerboardFinder<T>::init(const std::string& name,
44  ros::NodeHandle & nh)
45 {
46  if (!FeatureFinder::init(name, nh))
47  return false;
48 
49  // Setup Scriber
50  std::string topic_name;
51  nh.param<std::string>("topic", topic_name, "/points");
52  subscriber_ = nh.subscribe(topic_name,
53  1,
55  this);
56 
57  // Size of checkerboard
58  nh.param<int>("points_x", points_x_, 5);
59  nh.param<int>("points_y", points_y_, 4);
60  nh.param<double>("size", square_size_, 0.0245);
61  if (points_x_ % 2 == 1 && points_y_ % 2 == 1)
62  {
63  ROS_ERROR("Checkerboard is symmetric - orientation estimate can be wrong");
64  }
65 
66  // Should we include debug image/cloud in observations
67  nh.param<bool>("debug", output_debug_, false);
68 
69  // Name of checkerboard frame that will be used during optimization
70  nh.param<std::string>("frame_id", frame_id_, "checkerboard");
71 
72  // Name of the sensor model that will be used during optimization
73  nh.param<std::string>("camera_sensor_name", camera_sensor_name_, "camera");
74  nh.param<std::string>("chain_sensor_name", chain_sensor_name_, "arm");
75 
76  // Publish where checkerboard points were seen
77  publisher_ = nh.advertise<sensor_msgs::PointCloud2>(getName() + "_points", 10);
78 
79  // Setup to get camera depth info
80  if (!depth_camera_manager_.init(nh))
81  {
82  // Error will have been printed by manager
83  return false;
84  }
85 
86  return true;
87 }
88 
89 template <typename T>
91 {
92  if (waiting_)
93  {
94  msg_ = msg;
95  waiting_ = false;
96  }
97 }
98 
99 // Returns true if we got a message, false if we timeout
100 template <typename T>
102 {
103  // Initial wait cycle so that camera is definitely up to date.
104  ros::Duration(1/10.0).sleep();
105 
106  waiting_ = true;
107  int count = 250;
108  while (--count)
109  {
110  if (!waiting_)
111  {
112  // success
113  return true;
114  }
115  ros::Duration(0.01).sleep();
116  ros::spinOnce();
117  }
118  ROS_ERROR("Failed to get message");
119  return !waiting_;
120 }
121 
122 template <typename T>
123 bool CheckerboardFinder<T>::find(robot_calibration_msgs::CalibrationData * msg)
124 {
125  // Try up to 50 frames
126  for (int i = 0; i < 50; ++i)
127  {
128  // temporary copy of msg, so we throw away all changes if findInternal() returns false
129  robot_calibration_msgs::CalibrationData tmp_msg(*msg);
130  if (findInternal(&tmp_msg))
131  {
132  *msg = tmp_msg;
133  return true;
134  }
135  }
136  return false;
137 }
138 
139 template <>
140 bool CheckerboardFinder<sensor_msgs::PointCloud2>::findInternal(robot_calibration_msgs::CalibrationData * msg)
141 {
142  // Get cloud
143  if (!waitForMsg())
144  {
145  ROS_ERROR("No point cloud data");
146  return false;
147  }
148 
149  if (msg_.height == 1)
150  {
151  ROS_ERROR("OpenCV does not support unorganized cloud/image.");
152  return false;
153  }
154 
155  // Get an image message from point cloud
156  sensor_msgs::ImagePtr image_msg(new sensor_msgs::Image);
158  image_msg->encoding = "bgr8";
159  image_msg->height = msg_.height;
160  image_msg->width = msg_.width;
161  image_msg->step = image_msg->width * sizeof (uint8_t) * 3;
162  image_msg->data.resize(image_msg->step * image_msg->height);
163  for (size_t y = 0; y < msg_.height; y++)
164  {
165  for (size_t x = 0; x < msg_.width; x++)
166  {
167  uint8_t* pixel = &(image_msg->data[y * image_msg->step + x * 3]);
168  pixel[0] = rgb[0];
169  pixel[1] = rgb[1];
170  pixel[2] = rgb[2];
171  ++rgb;
172  }
173  }
174 
175  std::vector<cv::Point2f> points;
176  if (findCheckerboardPoints(image_msg, points))
177  {
178  ROS_INFO("Found the checkboard");
179 
180  // Create PointCloud2 to publish
181  sensor_msgs::PointCloud2 cloud;
182  cloud.width = 0;
183  cloud.height = 0;
184  cloud.header.stamp = ros::Time::now();
185  cloud.header.frame_id = msg_.header.frame_id;
186  sensor_msgs::PointCloud2Modifier cloud_mod(cloud);
187  cloud_mod.setPointCloud2FieldsByString(1, "xyz");
188  cloud_mod.resize(points_x_ * points_y_);
189  sensor_msgs::PointCloud2Iterator<float> iter_cloud(cloud, "x");
190 
191  // Set msg size
192  int idx_cam = msg->observations.size() + 0;
193  int idx_chain = msg->observations.size() + 1;
194  msg->observations.resize(msg->observations.size() + 2);
195  msg->observations[idx_cam].sensor_name = camera_sensor_name_;
196  msg->observations[idx_chain].sensor_name = chain_sensor_name_;
197 
198  msg->observations[idx_cam].features.resize(points_x_ * points_y_);
199  msg->observations[idx_chain].features.resize(points_x_ * points_y_);
200 
201  // Setup observed points
202  geometry_msgs::PointStamped rgbd;
203  rgbd.header = msg_.header;
204  geometry_msgs::PointStamped world;
205  world.header.frame_id = frame_id_;
206 
207  // Fill in message
209  for (size_t i = 0; i < points.size(); ++i)
210  {
211  world.point.x = (i % points_x_) * square_size_;
212  world.point.y = (i / points_x_) * square_size_;
213 
214  // Get 3d point
215  int index = (int)(points[i].y) * msg_.width + (int)(points[i].x);
216  rgbd.point.x = (xyz + index)[X];
217  rgbd.point.y = (xyz + index)[Y];
218  rgbd.point.z = (xyz + index)[Z];
219 
220  // Do not accept NANs
221  if (std::isnan(rgbd.point.x) ||
222  std::isnan(rgbd.point.y) ||
223  std::isnan(rgbd.point.z))
224  {
225  ROS_ERROR_STREAM("NAN point on " << i);
226  return false;
227  }
228 
229  msg->observations[idx_cam].features[i] = rgbd;
230  msg->observations[idx_cam].ext_camera_info = depth_camera_manager_.getDepthCameraInfo();
231  msg->observations[idx_chain].features[i] = world;
232 
233  // Visualize
234  iter_cloud[0] = rgbd.point.x;
235  iter_cloud[1] = rgbd.point.y;
236  iter_cloud[2] = rgbd.point.z;
237  ++iter_cloud;
238  }
239 
240  // Add debug cloud to message
241  if (output_debug_)
242  {
243  msg->observations[idx_cam].cloud = msg_;
244  }
245 
246  // Publish results
247  publisher_.publish(cloud);
248 
249  // Found all points
250  return true;
251  }
252 
253  return false;
254 }
255 
256 template <>
257 bool CheckerboardFinder<sensor_msgs::ImagePtr>::findInternal(robot_calibration_msgs::CalibrationData * msg)
258 {
259  // Get image
260  if (!waitForMsg())
261  {
262  ROS_ERROR("No image data");
263  return false;
264  }
265 
266  std::vector<cv::Point2f> points;
267  if (findCheckerboardPoints(msg_, points))
268  {
269  ROS_INFO("Found the checkboard");
270 
271  // Set msg size
272  int idx_cam = msg->observations.size() + 0;
273  int idx_chain = msg->observations.size() + 1;
274  msg->observations.resize(msg->observations.size() + 2);
275  msg->observations[idx_cam].sensor_name = camera_sensor_name_;
276  msg->observations[idx_chain].sensor_name = chain_sensor_name_;
277 
278  msg->observations[idx_cam].features.resize(points_x_ * points_y_);
279  msg->observations[idx_chain].features.resize(points_x_ * points_y_);
280 
281  // Setup observed points
282  geometry_msgs::PointStamped rgbd;
283  rgbd.header = msg_->header;
284  geometry_msgs::PointStamped world;
285  world.header.frame_id = frame_id_;
286 
287  // Fill in message
288  for (size_t i = 0; i < points.size(); ++i)
289  {
290  // Create 3d position of corner (in checkerboard_frame)
291  world.point.x = (i % points_x_) * square_size_;
292  world.point.y = (i / points_x_) * square_size_;
293 
294  // Save 2d pixel
295  rgbd.point.x = points[i].x;
296  rgbd.point.y = points[i].y;
297  rgbd.point.z = 0.0; // No Z information
298 
299  msg->observations[idx_cam].features[i] = rgbd;
300  msg->observations[idx_cam].ext_camera_info = depth_camera_manager_.getDepthCameraInfo();
301  msg->observations[idx_chain].features[i] = world;
302  }
303 
304  // Add debug cloud to message
305  if (output_debug_)
306  {
307  msg->observations[idx_cam].image = *msg_;
308  }
309 
310  // Found all points
311  return true;
312  }
313 
314  return false;
315 }
316 
317 template <typename T>
318 bool CheckerboardFinder<T>::findCheckerboardPoints(const sensor_msgs::ImagePtr& image,
319  std::vector<cv::Point2f>& points)
320 {
321  // Get an OpenCV image from the cloud
322  cv_bridge::CvImagePtr bridge;
323  try
324  {
325  bridge = cv_bridge::toCvCopy(image, "mono8"); // TODO: was rgb8? does this work?
326  }
327  catch(cv_bridge::Exception& e)
328  {
329  ROS_ERROR("Conversion failed");
330  return false;
331  }
332 
333  // Find checkerboard
334  points.resize(points_x_ * points_y_);
335  cv::Size checkerboard_size(points_x_, points_y_);
336  return cv::findChessboardCorners(bridge->image, checkerboard_size,
337  points, cv::CALIB_CB_ADAPTIVE_THRESH);
338 }
339 
340 } // namespace robot_calibration
robot_calibration::CheckerboardFinder::init
bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Definition: checkerboard_finder.cpp:43
point_cloud2_iterator.h
robot_calibration::Y
const unsigned Y
Definition: checkerboard_finder.cpp:33
robot_calibration::X
const unsigned X
Definition: checkerboard_finder.cpp:32
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
robot_calibration::FeatureFinder
Base class for a feature finder.
Definition: feature_finder.h:33
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
ros::spinOnce
ROSCPP_DECL void spinOnce()
cv_bridge::Exception
robot_calibration::CheckerboardFinder::CheckerboardFinder
CheckerboardFinder()
Definition: checkerboard_finder.cpp:37
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
sensor_msgs::PointCloud2ConstIterator
sensor_msgs::PointCloud2Iterator
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
name
std::string name
robot_calibration::CheckerboardFinder::cameraCallback
void cameraCallback(const T &msg)
Definition: checkerboard_finder.cpp:90
checkerboard_finder.h
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
robot_calibration::CheckerboardFinder
Finds checkerboards in images or point clouds.
Definition: checkerboard_finder.h:39
robot_calibration::CheckerboardFinder::findCheckerboardPoints
bool findCheckerboardPoints(const sensor_msgs::ImagePtr &msg, std::vector< cv::Point2f > &points)
Definition: checkerboard_finder.cpp:318
y
double y
ROS_ERROR
#define ROS_ERROR(...)
robot_calibration::CheckerboardFinder::find
bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called....
Definition: checkerboard_finder.cpp:123
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
robot_calibration::CheckerboardFinder::findInternal
bool findInternal(robot_calibration_msgs::CalibrationData *msg)
robot_calibration::FeatureFinder::init
virtual bool init(const std::string &name, ros::NodeHandle &nh)
Initialize the feature finder.
Definition: feature_finder.h:47
robot_calibration::Z
const unsigned Z
Definition: checkerboard_finder.cpp:34
sensor_msgs::PointCloud2Modifier::resize
void resize(size_t size)
robot_calibration::CheckerboardFinder::waitForMsg
bool waitForMsg()
Definition: checkerboard_finder.cpp:101
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
sensor_msgs::PointCloud2Modifier
class_list_macros.hpp
index
unsigned int index
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
x
double x
ros::Duration::sleep
bool sleep() const
ROS_INFO
#define ROS_INFO(...)
ros::Duration
sensor_msgs::PointCloud2Modifier::setPointCloud2FieldsByString
void setPointCloud2FieldsByString(int n_fields,...)
ros::NodeHandle
ros::Time::now
static Time now()


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01