37 #include <boost/assign.hpp>
38 #include <jsk_topic_tools/log_utils.h>
44 DiagnosticNodelet::onInit();
45 pub_ = advertise<geometry_msgs::PolygonStamped>(
54 jsk_topic_tools::warnNoRemap(names);
63 const sensor_msgs::CameraInfo::ConstPtr& roi_msg)
65 vital_checker_->poke();
66 geometry_msgs::PolygonStamped rect;
67 rect.header = roi_msg->header;
68 geometry_msgs::Point32 top_left_pt, top_right_pt, bottom_left_pt, bottom_right_pt;
69 top_left_pt.x = roi_msg->roi.x_offset;
70 top_left_pt.y = roi_msg->roi.y_offset;
71 top_right_pt.x = roi_msg->roi.x_offset + roi_msg->roi.width;
72 top_right_pt.y = roi_msg->roi.y_offset;
73 bottom_left_pt.x = roi_msg->roi.x_offset;
74 bottom_left_pt.y = roi_msg->roi.y_offset + roi_msg->roi.height;
75 bottom_right_pt.x = roi_msg->roi.x_offset + roi_msg->roi.width;
76 bottom_right_pt.y = roi_msg->roi.y_offset + roi_msg->roi.height;
77 rect.polygon.points.push_back(top_left_pt);
78 rect.polygon.points.push_back(bottom_left_pt);
79 rect.polygon.points.push_back(bottom_right_pt);
80 rect.polygon.points.push_back(top_right_pt);