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_to_mask_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 PolygonToMaskImage::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 pub_ = advertise<sensor_msgs::Image>(
00047 *pnh_, "output", 1);
00048 }
00049
00050 void PolygonToMaskImage::subscribe()
00051 {
00052 sub_info_ = pnh_->subscribe("input/camera_info", 1,
00053 &PolygonToMaskImage::infoCallback, this);
00054 sub_ = pnh_->subscribe("input", 1,
00055 &PolygonToMaskImage::convert, this);
00056 }
00057
00058 void PolygonToMaskImage::unsubscribe()
00059 {
00060 sub_info_.shutdown();
00061 sub_.shutdown();
00062 }
00063
00064 void PolygonToMaskImage::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 PolygonToMaskImage::convert(
00072 const geometry_msgs::PolygonStamped::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_8UC1);
00082 std::vector<cv::Point> points;
00083
00084 if (polygon_msg->polygon.points.size() >= 3) {
00085 for (size_t i = 0; i < polygon_msg->polygon.points.size(); i++) {
00086 geometry_msgs::Point32 p = polygon_msg->polygon.points[i];
00087 cv::Point uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
00088 points.push_back(uv);
00089 }
00090 cv::fillConvexPoly(mask_image, &(points[0]), points.size(), cv::Scalar(255));
00091 }
00092 pub_.publish(cv_bridge::CvImage(polygon_msg->header,
00093 sensor_msgs::image_encodings::MONO8,
00094 mask_image).toImageMsg());
00095 }
00096 }
00097
00098 }
00099
00100 #include <pluginlib/class_list_macros.h>
00101 PLUGINLIB_EXPORT_CLASS (jsk_perception::PolygonToMaskImage, nodelet::Nodelet);