Go to the documentation of this file.
38 #include <geometry_msgs/PolygonStamped.h>
39 #include <jsk_recognition_msgs/ColorHistogram.h>
48 #include <dynamic_reconfigure/server.h>
49 #include <jsk_perception/ColorHistogramConfig.h>
50 #include "opencv2/highgui/highgui.hpp"
51 #include "opencv2/imgproc/imgproc.hpp"
52 #include <jsk_topic_tools/diagnostic_nodelet.h>
56 class ColorHistogram:
public jsk_topic_tools::DiagnosticNodelet
66 typedef jsk_perception::ColorHistogramConfig
Config;
93 jsk_recognition_msgs::ColorHistogram& msg);
94 virtual void processBGR(
const cv::Mat& bgr_image,
95 const std_msgs::Header& header);
96 virtual void processHSI(
const cv::Mat& bgr_image,
97 const std_msgs::Header& header);
98 virtual void processBGR(
const cv::Mat& bgr_image,
100 const std_msgs::Header& header);
101 virtual void processHSI(
const cv::Mat& bgr_image,
103 const std_msgs::Header& header);
105 const sensor_msgs::Image::ConstPtr& image,
106 const geometry_msgs::PolygonStamped::ConstPtr& rectangle);
108 const sensor_msgs::Image::ConstPtr& image,
109 const sensor_msgs::Image::ConstPtr& mask_image);
ros::Publisher s_hist_pub_
boost::shared_ptr< image_transport::ImageTransport > it_
ros::Publisher g_hist_pub_
virtual ~ColorHistogram()
void configCallback(Config &new_config, uint32_t level)
virtual void unsubscribe()
ros::Publisher h_hist_pub_
jsk_perception::ColorHistogramConfig Config
ros::Publisher i_hist_pub_
image_transport::SubscriberFilter image_mask_sub_
virtual void processHSI(const cv::Mat &bgr_image, const std_msgs::Header &header)
virtual void convertHistogramToMsg(const cv::Mat &hist, int size, jsk_recognition_msgs::ColorHistogram &msg)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > MaskSyncPolicy
ros::Publisher image_pub_
virtual void extractMask(const sensor_msgs::Image::ConstPtr &image, const sensor_msgs::Image::ConstPtr &mask_image)
message_filters::Subscriber< geometry_msgs::PolygonStamped > rectangle_sub_
boost::shared_ptr< message_filters::Synchronizer< MaskSyncPolicy > > mask_sync_
virtual void processBGR(const cv::Mat &bgr_image, const std_msgs::Header &header)
ros::Publisher r_hist_pub_
virtual void extract(const sensor_msgs::Image::ConstPtr &image, const geometry_msgs::PolygonStamped::ConstPtr &rectangle)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
ros::Publisher b_hist_pub_
image_transport::SubscriberFilter image_sub_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, geometry_msgs::PolygonStamped > SyncPolicy
jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:16