37 #include <sensor_msgs/Image.h> 40 #include <boost/assign.hpp> 47 DiagnosticNodelet::onInit();
49 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50 dynamic_reconfigure::Server<Config>::CallbackType
f =
54 pub_ = advertise<sensor_msgs::Image>(*
pnh_,
"output", 1);
59 Config &config, uint32_t level)
80 const sensor_msgs::Image::ConstPtr& label_msg)
85 cv::Mat mask_image = cv::Mat::zeros(label_msg->height,
88 for (
size_t j = 0; j < label_img_ptr->image.rows; j++)
90 for (
size_t i = 0; i < label_img_ptr->image.cols; i++)
92 int label = label_img_ptr->image.at<
int>(j, i);
94 mask_image.at<uchar>(j, i) = 255;
void publish(const boost::shared_ptr< M > &message) const
std::vector< std::string > V_string
virtual void unsubscribe()
virtual void convert(const sensor_msgs::Image::ConstPtr &label_msg)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_perception::LabelToMaskImage, nodelet::Nodelet)
const std::string TYPE_32SC1
sensor_msgs::ImagePtr toImageMsg() const
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
jsk_perception::LabelToMaskImageConfig Config