37 #include <boost/assign.hpp>
38 #include <jsk_topic_tools/log_utils.h>
44 DiagnosticNodelet::onInit();
45 pub_ = advertise<sensor_msgs::CameraInfo>(*pnh_,
"output", 1);
55 ros::V_string names = boost::assign::list_of(
"~input")(
"~input/camera_info");
56 jsk_topic_tools::warnNoRemap(names);
66 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
73 const geometry_msgs::PolygonStamped::ConstPtr& rect_msg)
78 geometry_msgs::Point32 P0 = rect_msg->polygon.points[0];
79 geometry_msgs::Point32 P1 = rect_msg->polygon.points[1];
80 double min_x = std::max(std::min(P0.x, P1.x), 0.0f);
81 double max_x = std::max(P0.x, P1.x);
82 double min_y = std::max(std::min(P0.y, P1.y), 0.0f);
83 double max_y = std::max(P0.y, P1.y);
86 roi.roi.x_offset = (
int)min_x;
87 roi.roi.y_offset = (
int)min_y;
89 roi.roi.width =
width;