37 #include <boost/thread.hpp>
43 #include <opencv2/core/core.hpp>
44 #include <opencv2/core/core_c.h>
46 #include <sensor_msgs/Image.h>
47 #include <sensor_msgs/CameraInfo.h>
48 #include <image_cb_detector/ConfigAction.h>
49 #include <calibration_msgs/Interval.h>
63 as_(
"cb_detector_config", false),
109 const sensor_msgs::ImageConstPtr& depth_msg,
110 const sensor_msgs::CameraInfoConstPtr& caminfo_msg)
114 std::ostringstream
s;
120 calibration_msgs::CalibrationPattern features;
125 ROS_ERROR_STREAM(
s.str()<<
"Error trying to detect checkerboard, not going to publish CalibrationPattern");
130 ROS_ERROR_STREAM(
"Depth image must be 32-bit floating point (encoding '32FC1'), but has encoding '" << depth_msg->encoding <<
"'");
137 const float* depth_ptr =
reinterpret_cast<const float*
>(&depth_msg->data[0]);
138 std::size_t width = depth_msg->width;
139 std::size_t height = depth_msg->height;
142 std::vector<cv::Point3f> corner_cloud;
143 for(
size_t i = 0; i< features.image_points.size(); i++){
144 geometry_msgs::Point pixel = features.image_points[i];
145 float depth = *(depth_ptr+width*(
unsigned int)pixel.y+(
unsigned int)pixel.x);
153 corner_cloud.push_back( point );
156 if( corner_cloud.size() < features.image_points.size()/2 ) {
157 ROS_ERROR_STREAM(
s.str() <<
"More than 50% missing 3d points in checkerboard, not going to publish CalibrationPattern");
165 float best_ratio = 0;
167 for(
size_t i = 0; i < 100; ++i) {
169 for(
int i=0;i<3;++i) {
170 std::swap(corner_cloud[i], corner_cloud[rng.uniform(i+1,
int(corner_cloud.size()))]);
173 cv::Vec3f nrm = cv::Vec3f(corner_cloud[2]-corner_cloud[0]).cross(cv::Vec3f(corner_cloud[1])-cv::Vec3f(corner_cloud[0]));
174 nrm = nrm / cv::norm(nrm);
175 cv::Vec3f x0(corner_cloud[0]);
177 float p_to_plane_thresh = 0.01;
181 for (
size_t i=0; i<corner_cloud.size(); ++i) {
182 cv::Vec3f w = cv::Vec3f(corner_cloud[i]) - x0;
183 float D = std::fabs(nrm.dot(w));
184 if(D < p_to_plane_thresh)
187 float ratio = float(num_inliers) / float(corner_cloud.size());
188 if (ratio > best_ratio) {
197 ROS_ERROR (
"Could not estimate a planar model from the checkboard corners.");
208 for(
size_t i = 0; i< features.image_points.size(); i++)
211 geometry_msgs::Point& pixel = features.image_points[i];
215 cv::Vec3f ray(ray_pt);
216 ray = ray / cv::norm(ray);
218 float d1 = ray.dot(n);
219 float lambda =
d / d1;
272 int main(
int argc,
char** argv)
274 ros::init(argc, argv,
"rgbd_cb_detector_action");