checkerboard_finder.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Fetch Robotics Inc.
3  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16  */
17 
18 // Author: Michael Ferguson
19 
23 
25 
26 namespace robot_calibration
27 {
28 
29 // We use a number of PC2 iterators, define the indexes here
30 const unsigned X = 0;
31 const unsigned Y = 1;
32 const unsigned Z = 2;
33 
34 CheckerboardFinder::CheckerboardFinder() :
35  waiting_(false)
36 {
37 }
38 
39 bool CheckerboardFinder::init(const std::string& name,
40  ros::NodeHandle & nh)
41 {
42  if (!FeatureFinder::init(name, nh))
43  return false;
44 
45  // Setup Scriber
46  std::string topic_name;
47  nh.param<std::string>("topic", topic_name, "/points");
48  subscriber_ = nh.subscribe(topic_name,
49  1,
51  this);
52 
53  // Size of checkerboard
54  nh.param<int>("points_x", points_x_, 5);
55  nh.param<int>("points_y", points_y_, 4);
56  nh.param<double>("size", square_size_, 0.0245);
57 
58  // Should we include debug image/cloud in observations
59  nh.param<bool>("debug", output_debug_, false);
60 
61  // Name of checkerboard frame that will be used during optimization
62  nh.param<std::string>("frame_id", frame_id_, "checkerboard");
63 
64  // Name of the sensor model that will be used during optimization
65  nh.param<std::string>("camera_sensor_name", camera_sensor_name_, "camera");
66  nh.param<std::string>("chain_sensor_name", chain_sensor_name_, "arm");
67 
68  // Publish where checkerboard points were seen
69  publisher_ = nh.advertise<sensor_msgs::PointCloud2>(getName() + "_points", 10);
70 
71  // Setup to get camera depth info
72  if (!depth_camera_manager_.init(nh))
73  {
74  // Error will have been printed by manager
75  return false;
76  }
77 
78  return true;
79 }
80 
81 void CheckerboardFinder::cameraCallback(const sensor_msgs::PointCloud2& cloud)
82 {
83  if (waiting_)
84  {
85  cloud_ = cloud;
86  waiting_ = false;
87  }
88 }
89 
90 // Returns true if we got a message, false if we timeout
92 {
93  // Initial wait cycle so that camera is definitely up to date.
94  ros::Duration(1/10.0).sleep();
95 
96  waiting_ = true;
97  int count = 250;
98  while (--count)
99  {
100  if (!waiting_)
101  {
102  // success
103  return true;
104  }
105  ros::Duration(0.01).sleep();
106  ros::spinOnce();
107  }
108  ROS_ERROR("Failed to get cloud");
109  return !waiting_;
110 }
111 
112 bool CheckerboardFinder::find(robot_calibration_msgs::CalibrationData * msg)
113 {
114  // Try up to 50 frames
115  for (int i = 0; i < 50; ++i)
116  {
117  // temporary copy of msg, so we throw away all changes if findInternal() returns false
118  robot_calibration_msgs::CalibrationData tmp_msg(*msg);
119  if (findInternal(&tmp_msg))
120  {
121  *msg = tmp_msg;
122  return true;
123  }
124  }
125  return false;
126 }
127 
128 bool CheckerboardFinder::findInternal(robot_calibration_msgs::CalibrationData * msg)
129 {
130  geometry_msgs::PointStamped rgbd;
131  geometry_msgs::PointStamped world;
132 
133  // Get cloud
134  if (!waitForCloud())
135  {
136  ROS_ERROR("No point cloud data");
137  return false;
138  }
139 
140  if (cloud_.height == 1)
141  {
142  ROS_ERROR("OpenCV does not support unorganized cloud/image.");
143  return false;
144  }
145 
146  // Get an image message from point cloud
147  sensor_msgs::ImagePtr image_msg(new sensor_msgs::Image);
149  image_msg->encoding = "bgr8";
150  image_msg->height = cloud_.height;
151  image_msg->width = cloud_.width;
152  image_msg->step = image_msg->width * sizeof (uint8_t) * 3;
153  image_msg->data.resize(image_msg->step * image_msg->height);
154  for (size_t y = 0; y < cloud_.height; y++)
155  {
156  for (size_t x = 0; x < cloud_.width; x++)
157  {
158  uint8_t* pixel = &(image_msg->data[y * image_msg->step + x * 3]);
159  pixel[0] = rgb[0];
160  pixel[1] = rgb[1];
161  pixel[2] = rgb[2];
162  ++rgb;
163  }
164  }
165 
166  // Get an OpenCV image from the cloud
167  cv_bridge::CvImagePtr bridge;
168  try
169  {
170  bridge = cv_bridge::toCvCopy(image_msg, "mono8"); // TODO: was rgb8? does this work?
171  }
172  catch(cv_bridge::Exception& e)
173  {
174  ROS_ERROR("Conversion failed");
175  return false;
176  }
177 
178  // Find checkerboard
179  std::vector<cv::Point2f> points;
180  points.resize(points_x_ * points_y_);
181  cv::Size checkerboard_size(points_x_, points_y_);
182  int found = cv::findChessboardCorners(bridge->image, checkerboard_size,
183  points, cv::CALIB_CB_ADAPTIVE_THRESH);
184 
185  if (found)
186  {
187  ROS_INFO("Found the checkboard");
188 
189  // Create PointCloud2 to publish
190  sensor_msgs::PointCloud2 cloud;
191  cloud.width = 0;
192  cloud.height = 0;
193  cloud.header.stamp = ros::Time::now();
194  cloud.header.frame_id = cloud_.header.frame_id;
195  sensor_msgs::PointCloud2Modifier cloud_mod(cloud);
196  cloud_mod.setPointCloud2FieldsByString(1, "xyz");
197  cloud_mod.resize(points_x_ * points_y_);
198  sensor_msgs::PointCloud2Iterator<float> iter_cloud(cloud, "x");
199 
200  // Set msg size
201  int idx_cam = msg->observations.size() + 0;
202  int idx_chain = msg->observations.size() + 1;
203  msg->observations.resize(msg->observations.size() + 2);
204  msg->observations[idx_cam].sensor_name = camera_sensor_name_;
205  msg->observations[idx_chain].sensor_name = chain_sensor_name_;
206 
207  msg->observations[idx_cam].features.resize(points_x_ * points_y_);
208  msg->observations[idx_chain].features.resize(points_x_ * points_y_);
209 
210 
211  // Fill in the headers
212  rgbd.header = cloud_.header;
213  world.header.frame_id = frame_id_;
214 
215  // Fill in message
217  for (size_t i = 0; i < points.size(); ++i)
218  {
219  world.point.x = (i % points_x_) * square_size_;
220  world.point.y = (i / points_x_) * square_size_;
221 
222  // Get 3d point
223  int index = (int)(points[i].y) * cloud_.width + (int)(points[i].x);
224  rgbd.point.x = (xyz + index)[X];
225  rgbd.point.y = (xyz + index)[Y];
226  rgbd.point.z = (xyz + index)[Z];
227 
228  // Do not accept NANs
229  if (std::isnan(rgbd.point.x) ||
230  std::isnan(rgbd.point.y) ||
231  std::isnan(rgbd.point.z))
232  {
233  ROS_ERROR_STREAM("NAN point on " << i);
234  return false;
235  }
236 
237  msg->observations[idx_cam].features[i] = rgbd;
238  msg->observations[idx_cam].ext_camera_info = depth_camera_manager_.getDepthCameraInfo();
239  msg->observations[idx_chain].features[i] = world;
240 
241  // Visualize
242  iter_cloud[0] = rgbd.point.x;
243  iter_cloud[1] = rgbd.point.y;
244  iter_cloud[2] = rgbd.point.z;
245  ++iter_cloud;
246  }
247 
248  // Add debug cloud to message
249  if (output_debug_)
250  {
251  msg->observations[idx_cam].cloud = cloud_;
252  }
253 
254  // Publish results
255  publisher_.publish(cloud);
256 
257  // Found all points
258  return true;
259  }
260 
261  return false;
262 }
263 
264 } // namespace robot_calibration
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)
void publish(const boost::shared_ptr< M > &message) const
Base class for a feature finder.
ros::Publisher publisher_
Incoming sensor_msgs::PointCloud2.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool findInternal(robot_calibration_msgs::CalibrationData *msg)
bool sleep() const
This class processes the point cloud input to find a checkerboard.
double square_size_
Size of checkerboard.
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string camera_sensor_name_
Name of checkerboard frame.
std::string frame_id_
Should we output debug image/cloud?
robot_calibration_msgs::ExtendedCameraInfo getDepthCameraInfo()
Definition: depth_camera.h:75
bool output_debug_
Size of a square on checkboard (in meters)
#define ROS_INFO(...)
virtual bool init(const std::string &name, ros::NodeHandle &nh)
Initialize the feature finder.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string getName()
Get the name of this feature finder.
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.
DepthCameraInfoManager depth_camera_manager_
static Time now()
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()
void setPointCloud2FieldsByString(int n_fields,...)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)


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