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