00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros/find_object_on_plane.h"
00037 #include <opencv2/opencv.hpp>
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <sensor_msgs/image_encodings.h>
00040
00041 namespace jsk_pcl_ros
00042 {
00043 void FindObjectOnPlane::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 pub_min_area_rect_image_ = advertise<sensor_msgs::Image>(
00047 *pnh_, "debug/min_area_rect_image", 1);
00048 }
00049
00050 void FindObjectOnPlane::subscribe()
00051 {
00052 sub_image_.subscribe(*pnh_, "input", 1);
00053 sub_info_.subscribe(*pnh_, "input/camera_info", 1);
00054 sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
00055 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00056 sync_->connectInput(sub_image_, sub_info_, sub_coefficients_);
00057 sync_->registerCallback(boost::bind(&FindObjectOnPlane::find,
00058 this, _1, _2, _3));
00059 }
00060
00061 void FindObjectOnPlane::unsubscribe()
00062 {
00063 sub_image_.unsubscribe();
00064 sub_coefficients_.unsubscribe();
00065 }
00066
00067 void FindObjectOnPlane::find(
00068 const sensor_msgs::Image::ConstPtr& image_msg,
00069 const sensor_msgs::CameraInfo::ConstPtr& info_msg,
00070 const pcl_msgs::ModelCoefficients::ConstPtr& polygon_3d_coefficient_msg)
00071 {
00072 cv::Mat object_image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
00073
00074 image_geometry::PinholeCameraModel model;
00075 pcl::ModelCoefficients::Ptr polygon_coefficients
00076 (new pcl::ModelCoefficients);
00077 pcl_conversions::toPCL(*polygon_3d_coefficient_msg, *polygon_coefficients);
00078 jsk_pcl_ros::Plane::Ptr plane
00079 (new jsk_pcl_ros::Plane(polygon_coefficients->values));
00080 model.fromCameraInfo(info_msg);
00081 std::vector<cv::Point> all_points;
00082 for (int j = 0; j < object_image.rows; j++) {
00083 for (int i = 0; i < object_image.cols; i++) {
00084 if (object_image.at<uchar>(j, i) == 255) {
00085 all_points.push_back(cv::Point(i, j));
00086 }
00087 }
00088 }
00089 cv::RotatedRect obb = cv::minAreaRect(all_points);
00090
00091 cv::Mat min_area_rect_image;
00092 cv::cvtColor(object_image, min_area_rect_image, CV_GRAY2BGR);
00093 cv::Point2f vertices2f[4];
00094 obb.points(vertices2f);
00095 cv::line(min_area_rect_image, vertices2f[0], vertices2f[1],
00096 cv::Scalar(0, 0, 255), 4);
00097 cv::line(min_area_rect_image, vertices2f[1], vertices2f[2],
00098 cv::Scalar(0, 0, 255), 4);
00099 cv::line(min_area_rect_image, vertices2f[2], vertices2f[3],
00100 cv::Scalar(0, 0, 255), 4);
00101 cv::line(min_area_rect_image, vertices2f[3], vertices2f[0],
00102 cv::Scalar(0, 0, 255), 4);
00103 cv::Rect bb = obb.boundingRect();
00104 std::vector<cv::Point3f> search_points_3d;
00105 std::vector<cv::Point2f> search_points_2d;
00106 generateStartPoints(cv::Point2f(bb.x, bb.y),
00107 model, polygon_coefficients,
00108 search_points_3d, search_points_2d);
00109 for (size_t i = 0; i < search_points_2d.size(); i++) {
00110 cv::circle(min_area_rect_image, search_points_2d[i], 5, cv::Scalar(0, 255, 0), 1);
00111 }
00112
00113
00114 double min_area = DBL_MAX;
00115 double min_angle;
00116 cv::Point2f min_search_point;
00117 double min_x;
00118 double min_y;
00119 for (size_t i = 0; i < search_points_2d.size(); i++) {
00120 std::vector<double> angles;
00121 std::vector<double> max_x;
00122 std::vector<double> max_y;
00123 generateAngles(object_image, search_points_2d[i], angles,
00124 max_x, max_y,
00125 model, plane);
00126
00127 for (size_t j = 0; j < angles.size(); j++) {
00128 double area = drawAngle(min_area_rect_image, search_points_2d[i], angles[j],
00129 max_x[j], max_y[j], model, plane, cv::Scalar(0, 255, 0));
00130 if (area < min_area) {
00131 min_area = area;
00132 min_x = max_x[j];
00133 min_y = max_y[j];
00134 min_angle = angles[j];
00135 min_search_point = search_points_2d[i];
00136 }
00137 }
00138 }
00139 drawAngle(min_area_rect_image, min_search_point, min_angle,
00140 min_x, min_y, model, plane, cv::Scalar(0, 255, 255));
00141
00142 pub_min_area_rect_image_.publish(
00143 cv_bridge::CvImage(image_msg->header,
00144 sensor_msgs::image_encodings::BGR8,
00145 min_area_rect_image).toImageMsg());
00146 JSK_NODELET_INFO("published");
00147 }
00148
00149
00150 void FindObjectOnPlane::generateAngles(
00151 const cv::Mat& blob_image, const cv::Point2f& test_point,
00152 std::vector<double>& angles,
00153 std::vector<double>& max_x,
00154 std::vector<double>& max_y,
00155 const image_geometry::PinholeCameraModel& model,
00156 const jsk_pcl_ros::Plane::Ptr& plane)
00157 {
00158 angles.clear();
00159 const double angle_step = 3;
00160 std::vector<cv::Point> indices;
00161 for (int j = 0; j < blob_image.rows; j++) {
00162 for (int i = 0; i < blob_image.cols; i++) {
00163 if (blob_image.at<uchar>(j, i) != 0) {
00164 indices.push_back(cv::Point(i, j));
00165 }
00166 }
00167 }
00168 for (double angle = -180; angle < 180; angle += angle_step) {
00169 Eigen::Vector2f ux(cos(angle/180*M_PI), sin(angle/180*M_PI));
00170
00171 cv::Point2d uy_end = getUyEnd(test_point, cv::Point2d(test_point.x + ux[0], test_point.y + ux[1]),
00172 model,
00173 plane);
00174 Eigen::Vector2f uy(uy_end.x - test_point.x, uy_end.y - test_point.y);
00175
00176 Eigen::Matrix2f A;
00177 A << ux[0], uy[0],
00178 ux[1], uy[1];
00179 bool excluded = false;
00180 double max_alpha = -DBL_MAX;
00181 double max_beta = -DBL_MAX;
00182 for (size_t i = 0; i < indices.size(); i++) {
00183 Eigen::Vector2f p_q = Eigen::Vector2f(indices[i].x, indices[i].y) - Eigen::Vector2f(test_point.x, test_point.y);
00184 Eigen::Vector2f a_b = A.inverse() * p_q;
00185 double alpha = a_b[0];
00186 double beta = a_b[1];
00187 if (alpha < 0 || beta < 0) {
00188 excluded = true;
00189 break;
00190 }
00191 if (alpha > max_alpha) {
00192 max_alpha = alpha;
00193 }
00194 if (beta > max_beta) {
00195 max_beta = beta;
00196 }
00197
00198 }
00199 if (!excluded) {
00200 angles.push_back(angle);
00201 max_x.push_back(max_alpha);
00202 max_y.push_back(max_beta);
00203 }
00204 }
00205 }
00206
00207 Eigen::Vector3f FindObjectOnPlane::rayPlaneInteersect(
00208 const cv::Point3d& ray,
00209 const jsk_pcl_ros::Plane::Ptr& plane)
00210 {
00211 Eigen::Vector3f n = plane->getNormal();
00212 Eigen::Vector3f d(ray.x, ray.y, ray.z);
00213 double alpha = - plane->getD() / n.dot(d);
00214 return alpha * d;
00215 }
00216
00217 cv::Point2d FindObjectOnPlane::getUyEnd(
00218 const cv::Point2d& ux_start,
00219 const cv::Point2d& ux_end,
00220 const image_geometry::PinholeCameraModel& model,
00221 const jsk_pcl_ros::Plane::Ptr& plane)
00222 {
00223 cv::Point3d start_ray = model.projectPixelTo3dRay(ux_start);
00224 cv::Point3d end_ray = model.projectPixelTo3dRay(ux_end);
00225 Eigen::Vector3f ux_start_3d = rayPlaneInteersect(start_ray, plane);
00226 Eigen::Vector3f ux_end_3d = rayPlaneInteersect(end_ray, plane);
00227 Eigen::Vector3f ux_3d = ux_end_3d - ux_start_3d;
00228 Eigen::Vector3f normal = plane->getNormal();
00229 Eigen::Vector3f uy_3d = normal.cross(ux_3d).normalized();
00230 Eigen::Vector3f uy_end_3d = ux_start_3d + uy_3d;
00231 cv::Point2d uy_end = model.project3dToPixel(cv::Point3d(uy_end_3d[0],
00232 uy_end_3d[1],
00233 uy_end_3d[2]));
00234 return uy_end;
00235 }
00236
00237 double FindObjectOnPlane::drawAngle(
00238 cv::Mat& out_image, const cv::Point2f& test_point, const double angle,
00239 const double max_x, const double max_y,
00240 const image_geometry::PinholeCameraModel& model,
00241 const jsk_pcl_ros::Plane::Ptr& plane,
00242 cv::Scalar color)
00243 {
00244 Eigen::Vector2f ux(cos(angle/180*M_PI), sin(angle/180*M_PI));
00245 cv::Point2d uy_end = getUyEnd(
00246 test_point, cv::Point2d(test_point.x + ux[0], test_point.y + ux[1]),
00247 model, plane);
00248 Eigen::Vector2f uy(uy_end.x - test_point.x, uy_end.y - test_point.y);
00249
00250 Eigen::Vector2f to_point = ux * max_x + Eigen::Vector2f(test_point.x, test_point.y);
00251 Eigen::Vector2f to_point2 = uy * max_y + Eigen::Vector2f(test_point.x, test_point.y);
00252 cv::Point2f to_point_cv(to_point[0], to_point[1]);
00253 cv::Point2f to_point2_cv(to_point2[0], to_point2[1]);
00254 cv::Point2f to_point3_cv = to_point_cv + to_point2_cv - test_point;
00255 cv::line(out_image, test_point, to_point_cv, color, 4);
00256 cv::line(out_image, test_point, to_point2_cv, color, 4);
00257 cv::line(out_image, to_point_cv, to_point3_cv, color, 4);
00258 cv::line(out_image, to_point2_cv, to_point3_cv, color, 4);
00259 return max_x * max_y;
00260 }
00261
00262 void FindObjectOnPlane::generateStartPoints(
00263 const cv::Point2f& point_2d,
00264 const image_geometry::PinholeCameraModel& model,
00265 const pcl::ModelCoefficients::Ptr& coefficients,
00266 std::vector<cv::Point3f>& search_points_3d,
00267 std::vector<cv::Point2f>& search_points_2d)
00268 {
00269 JSK_NODELET_INFO("generateStartPoints");
00270 jsk_pcl_ros::Plane::Ptr plane
00271 (new jsk_pcl_ros::Plane(coefficients->values));
00272 cv::Point3d ray = model.projectPixelTo3dRay(point_2d);
00273 Eigen::Vector3f projected_point = rayPlaneInteersect(ray, plane);
00274 const double resolution_step = 0.01;
00275 const int resolution = 5;
00276 search_points_3d.clear();
00277 search_points_2d.clear();
00278 for (int i = - resolution; i < resolution; ++i) {
00279 for (int j = - resolution; j < resolution; ++j) {
00280 double x_diff = resolution_step * i;
00281 double y_diff = resolution_step * j;
00282 Eigen::Vector3f moved_point = projected_point + Eigen::Vector3f(x_diff, y_diff, 0);
00283 Eigen::Vector3f projected_moved_point;
00284 plane->project(moved_point, projected_moved_point);
00285 cv::Point3f projected_moved_point_cv(projected_moved_point[0],
00286 projected_moved_point[1],
00287 projected_moved_point[2]);
00288 search_points_3d.push_back(cv::Point3f(projected_moved_point_cv));
00289 cv::Point2d p2d = model.project3dToPixel(projected_moved_point_cv);
00290 search_points_2d.push_back(p2d);
00291 }
00292 }
00293 }
00294 }
00295
00296
00297 #include <pluginlib/class_list_macros.h>
00298 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::FindObjectOnPlane, nodelet::Nodelet);