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 <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 PolygonToMaskImage::onInit()
00046 {
00047 DiagnosticNodelet::onInit();
00048 pub_ = advertise<sensor_msgs::Image>(
00049 *pnh_, "output", 1);
00050 onInitPostProcess();
00051 }
00052
00053 void PolygonToMaskImage::subscribe()
00054 {
00055 sub_info_ = pnh_->subscribe("input/camera_info", 1,
00056 &PolygonToMaskImage::infoCallback, this);
00057 sub_ = pnh_->subscribe("input", 1,
00058 &PolygonToMaskImage::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 PolygonToMaskImage::unsubscribe()
00064 {
00065 sub_info_.shutdown();
00066 sub_.shutdown();
00067 }
00068
00069 void PolygonToMaskImage::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 PolygonToMaskImage::convert(
00077 const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg)
00078 {
00079 boost::mutex::scoped_lock lock(mutex_);
00080 vital_checker_->poke();
00081 if (camera_info_) {
00082 if (polygon_msg->header.frame_id != camera_info_->header.frame_id) {
00083 NODELET_ERROR("frame_id of polygon (%s) and camera (%s) are not same.",
00084 polygon_msg->header.frame_id.c_str(), camera_info_->header.frame_id.c_str());
00085 }
00086
00087 image_geometry::PinholeCameraModel model;
00088 model.fromCameraInfo(camera_info_);
00089 cv::Mat mask_image = cv::Mat::zeros(camera_info_->height,
00090 camera_info_->width,
00091 CV_8UC1);
00092 std::vector<cv::Point> points;
00093
00094 if (polygon_msg->polygon.points.size() >= 3) {
00095 for (size_t i = 0; i < polygon_msg->polygon.points.size(); i++) {
00096 geometry_msgs::Point32 p = polygon_msg->polygon.points[i];
00097 cv::Point uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
00098 points.push_back(uv);
00099 }
00100 cv::fillConvexPoly(mask_image, &(points[0]), points.size(), cv::Scalar(255));
00101 }
00102 pub_.publish(cv_bridge::CvImage(polygon_msg->header,
00103 sensor_msgs::image_encodings::MONO8,
00104 mask_image).toImageMsg());
00105 }
00106 else {
00107 NODELET_WARN("no camera info is available");
00108 }
00109 }
00110
00111 }
00112
00113 #include <pluginlib/class_list_macros.h>
00114 PLUGINLIB_EXPORT_CLASS (jsk_perception::PolygonToMaskImage, nodelet::Nodelet);