50 std::string topic_name;
51 nh.
param<std::string>(
"topic", topic_name,
"/points");
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)
63 ROS_ERROR(
"Checkerboard is symmetric - orientation estimate can be wrong");
67 nh.
param<
bool>(
"debug", output_debug_,
false);
70 nh.
param<std::string>(
"frame_id", frame_id_,
"checkerboard");
73 nh.
param<std::string>(
"camera_sensor_name", camera_sensor_name_,
"camera");
74 nh.
param<std::string>(
"chain_sensor_name", chain_sensor_name_,
"arm");
77 publisher_ = nh.
advertise<sensor_msgs::PointCloud2>(
getName() +
"_points", 10);
80 if (!depth_camera_manager_.init(nh))
100 template <
typename T>
122 template <
typename T>
126 for (
int i = 0; i < 50; ++i)
129 robot_calibration_msgs::CalibrationData tmp_msg(*msg);
130 if (findInternal(&tmp_msg))
149 if (msg_.height == 1)
151 ROS_ERROR(
"OpenCV does not support unorganized cloud/image.");
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++)
165 for (
size_t x = 0;
x < msg_.width;
x++)
167 uint8_t* pixel = &(image_msg->data[
y * image_msg->step +
x * 3]);
175 std::vector<cv::Point2f> points;
176 if (findCheckerboardPoints(image_msg, points))
181 sensor_msgs::PointCloud2 cloud;
185 cloud.header.frame_id = msg_.header.frame_id;
188 cloud_mod.
resize(points_x_ * points_y_);
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_;
198 msg->observations[idx_cam].features.resize(points_x_ * points_y_);
199 msg->observations[idx_chain].features.resize(points_x_ * points_y_);
202 geometry_msgs::PointStamped rgbd;
203 rgbd.header = msg_.header;
204 geometry_msgs::PointStamped world;
205 world.header.frame_id = frame_id_;
209 for (
size_t i = 0; i < points.size(); ++i)
211 world.point.x = (i % points_x_) * square_size_;
212 world.point.y = (i / points_x_) * square_size_;
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];
221 if (std::isnan(rgbd.point.x) ||
222 std::isnan(rgbd.point.y) ||
223 std::isnan(rgbd.point.z))
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;
234 iter_cloud[0] = rgbd.point.x;
235 iter_cloud[1] = rgbd.point.y;
236 iter_cloud[2] = rgbd.point.z;
243 msg->observations[idx_cam].cloud = msg_;
247 publisher_.publish(cloud);
266 std::vector<cv::Point2f> points;
267 if (findCheckerboardPoints(msg_, points))
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_;
278 msg->observations[idx_cam].features.resize(points_x_ * points_y_);
279 msg->observations[idx_chain].features.resize(points_x_ * points_y_);
282 geometry_msgs::PointStamped rgbd;
283 rgbd.header = msg_->header;
284 geometry_msgs::PointStamped world;
285 world.header.frame_id = frame_id_;
288 for (
size_t i = 0; i < points.size(); ++i)
291 world.point.x = (i % points_x_) * square_size_;
292 world.point.y = (i / points_x_) * square_size_;
295 rgbd.point.x = points[i].x;
296 rgbd.point.y = points[i].y;
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;
307 msg->observations[idx_cam].image = *msg_;
317 template <
typename T>
319 std::vector<cv::Point2f>& points)
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);