41 #if ( CV_MAJOR_VERSION >= 4) 42 #include <opencv2/imgproc/imgproc_c.h> 52 ConnectionBasedNodelet::onInit();
54 srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
55 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
76 async_ = boost::make_shared<message_filters::Synchronizer<AsyncPolicy> >(
queue_size_);
83 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
104 bool need_resubscribe =
false;
108 need_resubscribe =
true;
125 #if ROS_VERSION_MINIMUM(1, 11, 4) 135 const jsk_recognition_msgs::RectArray::ConstPtr& rects)
137 jsk_recognition_msgs::ClassificationResult classes;
138 classes.header = rects->header;
140 boost::make_shared<jsk_recognition_msgs::ClassificationResult>(classes));
144 const sensor_msgs::Image::ConstPtr& image,
145 const jsk_recognition_msgs::RectArray::ConstPtr& rects,
146 const jsk_recognition_msgs::ClassificationResult::ConstPtr& classes)
159 cv::resize(cv_img->image, img, cv::Size(),
166 for (
size_t i = 0; i < rects->rects.size(); ++i) {
170 drawRect(img, rects->rects[i], color);
174 std::ostringstream oss;
175 oss << classes->label_names[i];
176 if (
show_proba_ && classes->label_proba.size() > i) {
177 oss << std::fixed << std::setprecision(2);
178 oss <<
" (" << classes->label_proba[i] <<
")";
180 drawLabel(img, rects->rects[i], color, oss.str());
188 cv::Mat&
img,
const jsk_recognition_msgs::Rect& orig_rect,
const cv::Scalar& color)
198 cv::Mat&
img,
const jsk_recognition_msgs::Rect& rect,
199 const cv::Scalar& color,
const std::string& label)
202 cv::Size label_size = cv::getTextSize(label,
label_font_,
214 label_size.height * label_margin_factor_ * 1.3),
216 cv::putText(img, label,
217 cv::Point(orig_x + label_size.width * (label_margin_factor_ - 1.0) / 2.0,
218 orig_y - label_size.height * (label_margin_factor_ - 1.0) / 2.0),
221 cv::Scalar(text_color, text_color, text_color),
228 static const float colors[6][3] = { {1,0,1}, {0,0,1},{0,1,1},{0,1,0},{1,1,0},{1,0,0} };
229 float ratio = ((
float)(index * 123457 % label_num) / label_num) * 5;
230 int i = std::floor(ratio);
231 int j = std::ceil(ratio);
233 for (
int c = 0;
c < 3; ++
c)
234 color[
c] = (
int)(((1-ratio) * colors[i][
c] + ratio * colors[j][
c]) * 255);
bool use_classification_result_
double resolution_factor_
virtual void drawRect(cv::Mat &img, const jsk_recognition_msgs::Rect &rect, const cv::Scalar &color)
void publish(const boost::shared_ptr< M > &message) const
double label_margin_factor_
virtual void fillEmptyClasses(const jsk_recognition_msgs::RectArray::ConstPtr &rects)
virtual void configCallback(Config &config, uint32_t level)
message_filters::Subscriber< jsk_recognition_msgs::ClassificationResult > sub_class_
#define NODELET_ERROR_STREAM(...)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::RectArray > sub_rects_
virtual void randomColor(const int &label_num, const int &index, cv::Scalar &color)
virtual void unsubscribe()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void onMessage(const sensor_msgs::Image::ConstPtr &image, const jsk_recognition_msgs::RectArray::ConstPtr &rects, const jsk_recognition_msgs::ClassificationResult::ConstPtr &classes)
message_filters::Subscriber< sensor_msgs::Image > sub_image_
message_filters::PassThrough< jsk_recognition_msgs::ClassificationResult > null_class_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void add(const MConstPtr &msg)
boost::shared_ptr< message_filters::Synchronizer< AsyncPolicy > > async_
PLUGINLIB_EXPORT_CLASS(jsk_perception::DrawRects, nodelet::Nodelet)
ros::Publisher pub_image_
virtual bool isDarkColor(const cv::Scalar &color)
sensor_msgs::ImagePtr toImageMsg() const
int interpolation_method_
virtual void drawLabel(cv::Mat &img, const jsk_recognition_msgs::Rect &rect, const cv::Scalar &color, const std::string &label)
Connection registerCallback(const C &callback)