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/rect_to_roi.h"
00037 #include <boost/assign.hpp>
00038 #include <jsk_topic_tools/log_utils.h>
00039
00040 namespace jsk_perception
00041 {
00042 void RectToROI::onInit()
00043 {
00044 DiagnosticNodelet::onInit();
00045 pub_ = advertise<sensor_msgs::CameraInfo>(*pnh_, "output", 1);
00046 onInitPostProcess();
00047 }
00048
00049 void RectToROI::subscribe()
00050 {
00051 sub_rect_ = pnh_->subscribe(
00052 "input", 1, &RectToROI::rectCallback, this);
00053 sub_info_ = pnh_->subscribe(
00054 "input/camera_info", 1, &RectToROI::infoCallback, this);
00055 ros::V_string names = boost::assign::list_of("~input")("~input/camera_info");
00056 jsk_topic_tools::warnNoRemap(names);
00057 }
00058
00059 void RectToROI::unsubscribe()
00060 {
00061 sub_rect_.shutdown();
00062 sub_info_.shutdown();
00063 }
00064
00065 void RectToROI::infoCallback(
00066 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00067 {
00068 boost::mutex::scoped_lock lock(mutex_);
00069 latest_camera_info_ = info_msg;
00070 }
00071
00072 void RectToROI::rectCallback(
00073 const geometry_msgs::PolygonStamped::ConstPtr& rect_msg)
00074 {
00075 boost::mutex::scoped_lock lock(mutex_);
00076 if (latest_camera_info_) {
00077 sensor_msgs::CameraInfo roi(*latest_camera_info_);
00078 geometry_msgs::Point32 P0 = rect_msg->polygon.points[0];
00079 geometry_msgs::Point32 P1 = rect_msg->polygon.points[1];
00080 double min_x = std::max(std::min(P0.x, P1.x), 0.0f);
00081 double max_x = std::max(P0.x, P1.x);
00082 double min_y = std::max(std::min(P0.y, P1.y), 0.0f);
00083 double max_y = std::max(P0.y, P1.y);
00084 double width = std::min(max_x - min_x, latest_camera_info_->width - min_x);
00085 double height = std::min(max_y - min_y, latest_camera_info_->height - min_y);
00086 roi.roi.x_offset = (int)min_x;
00087 roi.roi.y_offset = (int)min_y;
00088 roi.roi.height = height;
00089 roi.roi.width = width;
00090 pub_.publish(roi);
00091 }
00092 else {
00093 NODELET_ERROR("camera info is not yet available");
00094 }
00095 }
00096 }
00097
00098 #include <pluginlib/class_list_macros.h>
00099 PLUGINLIB_EXPORT_CLASS (jsk_perception::RectToROI, nodelet::Nodelet);