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/grid_label.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 GridLabel::onInit()
00046 {
00047 DiagnosticNodelet::onInit();
00048
00049 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00050 dynamic_reconfigure::Server<Config>::CallbackType f =
00051 boost::bind (&GridLabel::configCallback, this, _1, _2);
00052 srv_->setCallback (f);
00053
00054 pnh_->param("use_camera_info", use_camera_info_, false);
00055 pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00056 onInitPostProcess();
00057 }
00058
00059 void GridLabel::subscribe()
00060 {
00061 if (use_camera_info_) {
00062 sub_ = pnh_->subscribe(
00063 "input", 1, &GridLabel::infoCallback, this);
00064 }
00065 else {
00066 sub_ = pnh_->subscribe(
00067 "input", 1, &GridLabel::imageCallback, this);
00068 }
00069 ros::V_string names = boost::assign::list_of("~input");
00070 jsk_topic_tools::warnNoRemap(names);
00071 }
00072
00073 void GridLabel::unsubscribe()
00074 {
00075 sub_.shutdown();
00076 }
00077
00078 void GridLabel::configCallback(Config &config, uint32_t level)
00079 {
00080 boost::mutex::scoped_lock lock(mutex_);
00081 label_size_ = config.label_size;
00082 }
00083
00084 void GridLabel::infoCallback(
00085 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00086 {
00087 boost::mutex::scoped_lock lock(mutex_);
00088 cv::Mat label = cv::Mat::zeros(info_msg->height,
00089 info_msg->width,
00090 CV_32SC1);
00091 makeLabel(label, info_msg->header);
00092 }
00093
00094 void GridLabel::imageCallback(
00095 const sensor_msgs::Image::ConstPtr& image_msg)
00096 {
00097 boost::mutex::scoped_lock lock(mutex_);
00098 cv::Mat label = cv::Mat::zeros(image_msg->height,
00099 image_msg->width,
00100 CV_32SC1);
00101 makeLabel(label, image_msg->header);
00102 }
00103
00104 void GridLabel::makeLabel(cv::Mat& label, const std_msgs::Header& header) {
00105 int num_u = ceil(label.cols / (float)label_size_);
00106 int num_v = ceil(label.rows / (float)label_size_);
00107 int counter = 1;
00108 for (int v = 0; v < num_v; v++) {
00109 for (int u = 0; u < num_u; u++) {
00110 cv::Rect region(u * label_size_, v * label_size_,
00111 label_size_, label_size_);
00112 cv::rectangle(label, region, cv::Scalar(counter), CV_FILLED);
00113 ++counter;
00114 }
00115 }
00116 pub_.publish(cv_bridge::CvImage(header,
00117 sensor_msgs::image_encodings::TYPE_32SC1,
00118 label).toImageMsg());
00119 }
00120
00121 }
00122
00123 #include <pluginlib/class_list_macros.h>
00124 PLUGINLIB_EXPORT_CLASS (jsk_perception::GridLabel, nodelet::Nodelet);