Go to the documentation of this file.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
00036 #include "jsk_perception/polygon_array_to_label_image.h"
00037 #include <opencv2/opencv.hpp>
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <sensor_msgs/image_encodings.h>
00040
00041 namespace jsk_perception
00042 {
00043 void PolygonArrayToLabelImage::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 pub_ = advertise<sensor_msgs::Image>(
00047 *pnh_, "output", 1);
00048 }
00049
00050 void PolygonArrayToLabelImage::subscribe()
00051 {
00052 sub_info_ = pnh_->subscribe("input/camera_info", 1,
00053 &PolygonArrayToLabelImage::infoCallback, this);
00054 sub_ = pnh_->subscribe("input", 1,
00055 &PolygonArrayToLabelImage::convert, this);
00056 }
00057
00058 void PolygonArrayToLabelImage::unsubscribe()
00059 {
00060 sub_info_.shutdown();
00061 sub_.shutdown();
00062 }
00063
00064 void PolygonArrayToLabelImage::infoCallback(
00065 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00066 {
00067 boost::mutex::scoped_lock lock(mutex_);
00068 camera_info_ = info_msg;
00069 }
00070
00071 void PolygonArrayToLabelImage::convert(
00072 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg)
00073 {
00074 boost::mutex::scoped_lock lock(mutex_);
00075 vital_checker_->poke();
00076 if (camera_info_) {
00077 image_geometry::PinholeCameraModel model;
00078 model.fromCameraInfo(camera_info_);
00079 cv::Mat mask_image = cv::Mat::zeros(camera_info_->height,
00080 camera_info_->width,
00081 CV_32SC1);
00082
00083 int label_counter = 1;
00084
00085 for (size_t i_polygon = 0; i_polygon < polygon_msg->polygons.size(); ++i_polygon) {
00086 geometry_msgs::Polygon polygon = polygon_msg->polygons[i_polygon].polygon;
00087 std::vector<cv::Point> points;
00088 if (polygon.points.size() >= 3) {
00089 bool all_outside = true;
00090 for (size_t i = 0; i < polygon.points.size(); i++) {
00091 geometry_msgs::Point32 p = polygon.points[i];
00092 cv::Point uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
00093 if ((uv.x > 0 && uv.x < camera_info_->width) &&
00094 (uv.y > 0 && uv.y < camera_info_->height)) {
00095 all_outside = false;
00096 }
00097 points.push_back(uv);
00098 }
00099 if (!all_outside) {
00100 cv::fillConvexPoly(mask_image, &(points[0]), points.size(), label_counter++);
00101 }
00102 }
00103 }
00104 pub_.publish(cv_bridge::CvImage(polygon_msg->header,
00105 sensor_msgs::image_encodings::TYPE_32SC1,
00106 mask_image).toImageMsg());
00107 }
00108 else {
00109 JSK_NODELET_WARN("no camera info is available");
00110 }
00111 }
00112
00113 }
00114
00115 #include <pluginlib/class_list_macros.h>
00116 PLUGINLIB_EXPORT_CLASS (jsk_perception::PolygonArrayToLabelImage, nodelet::Nodelet);