36 #define BOOST_PARAMETER_MAX_ARITY 7
46 DiagnosticNodelet::onInit();
51 pub_ = advertise<jsk_recognition_msgs::RectArray>(*pnh_,
"output", 1);
52 pub_internal_ = pnh_->advertise<jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo>(
"internal", 1);
77 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(
queue_size_);
81 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
88 async_box_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicyBox> >(
queue_size_);
107 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
109 jsk_recognition_msgs::BoundingBoxArray::Ptr boxes_msg(
110 new jsk_recognition_msgs::BoundingBoxArray());
111 boxes_msg->header = box_msg->header;
112 boxes_msg->boxes.push_back(*box_msg);
117 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& boxes_msg)
130 jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo internal_msg;
131 internal_msg.header = boxes_msg->header;
132 internal_msg.boxes = *boxes_msg;
133 internal_msg.camera_info = *
info_msg;
138 const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr& msg)
143 msg->boxes.header.frame_id,
144 msg->camera_info.header.frame_id,
145 msg->boxes.header.stamp,
147 Eigen::Affine3f box_to_info;
150 model.fromCameraInfo(
msg->camera_info);
151 jsk_recognition_msgs::RectArray rect_array;
152 rect_array.header =
msg->camera_info.header;
153 for (
size_t i = 0;
i <
msg->boxes.boxes.size();
i++) {
154 jsk_recognition_msgs::BoundingBox box =
msg->boxes.boxes[
i];
158 cv::Rect rect = cv::boundingRect(points);
159 jsk_recognition_msgs::Rect ros_rect;
162 ros_rect.width = rect.width;
163 ros_rect.height = rect.height;
164 rect_array.rects.push_back(ros_rect);