39 #include <boost/assign.hpp> 40 #include <boost/filesystem.hpp> 43 #include <jsk_recognition_msgs/RectArray.h> 45 #include <opencv2/opencv.hpp> 46 #include <opencv2/saliency.hpp> 54 DiagnosticNodelet::onInit();
55 pub_rects_ = advertise<jsk_recognition_msgs::RectArray>(*
pnh_,
"output", 1);
58 std::string training_path;
61 rospack::Package *
p = rp.get_pkg(
"jsk_perception");
63 ROS_ERROR(
"Package path of 'jsk_perception' does not found");
66 training_path = p->path + std::string(
"/trained_data/ObjectnessTrainedModel");
72 rp.
crawl(search_path, 1);
74 if (rp.
find(
"jsk_perception", path) ==
true) {
75 training_path = path + std::string(
"/trained_data/ObjectnessTrainedModel");
77 ROS_ERROR(
"Package path of 'jsk_perception' does not found");
81 if (!boost::filesystem::exists(training_path)) {
82 ROS_ERROR(
"Training data path '%s' does not exist", training_path.c_str());
86 binger_ =
new cv::saliency::ObjectnessBING();
87 binger_->setTrainingPath(training_path);
104 const sensor_msgs::Image::ConstPtr&
img_msg)
107 img_msg, img_msg->encoding);
108 cv::Mat
img = cv_ptr->image;
112 if (img.rows * img.cols > 250000) {
113 scale =
static_cast<double>(std::min(500. / img.rows, 500. / img.cols));
114 cv::resize(img, img, cv::Size(static_cast<int>(scale * img.cols),
115 static_cast<int>(scale * img.rows)));
118 std::vector<cv::Vec4i> saliency_map;
119 binger_->computeSaliency(img, saliency_map);
120 std::vector<float> objectness_values =
binger_->getobjectnessValues();
122 jsk_recognition_msgs::RectArray rects_msg;
123 cv::Mat objectness_img = cv::Mat(img.rows, img.cols, CV_32FC1);
124 for (
size_t k=0; k < saliency_map.size(); k++) {
125 int min_x =
static_cast<int>(saliency_map[k][0] / scale);
126 int min_y =
static_cast<int>(saliency_map[k][1] / scale);
127 int max_x =
static_cast<int>(saliency_map[k][2] / scale);
128 int max_y =
static_cast<int>(saliency_map[k][3] / scale);
130 jsk_recognition_msgs::Rect rect;
133 rect.width = max_x - min_x;
134 rect.height = max_y - min_y;
135 rects_msg.rects.push_back(rect);
137 for (
size_t j=std::max(0, min_y); j < std::min(max_y, img.rows); j++) {
138 for (
size_t i=std::max(0, min_x); i < std::min(max_x, img.cols); i++) {
139 objectness_img.at<
float>(j, i) += objectness_values[k];
144 rects_msg.header = img_msg->header;
ros::Publisher pub_rects_
void publish(const boost::shared_ptr< M > &message) const
cv::saliency::ObjectnessBING * binger_
std::vector< std::string > V_string
const std::string TYPE_32FC1
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
bool getSearchPathFromEnv(std::vector< std::string > &sp)
void crawl(std::vector< std::string > search_path, bool force)
ros::Publisher pub_objectness_
bool find(const std::string &name, std::string &path)
virtual void apply(const sensor_msgs::Image::ConstPtr &image_msg)
PLUGINLIB_EXPORT_CLASS(jsk_perception::Bing, nodelet::Nodelet)
sensor_msgs::ImagePtr toImageMsg() const
virtual void unsubscribe()