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