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