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 #define BOOST_PARAMETER_MAX_ARITY 7
00037
00038 #include "jsk_perception/bounding_box_to_rect.h"
00039 #include <jsk_recognition_utils/geo/cube.h>
00040 #include <jsk_recognition_utils/sensor_model_utils.h>
00041
00042 namespace jsk_perception
00043 {
00044 void BoundingBoxToRect::onInit()
00045 {
00046 DiagnosticNodelet::onInit();
00047 tf_listener_ = jsk_recognition_utils::TfListenerSingleton::getInstance();
00048 pnh_->param("queue_size", queue_size_, 100);
00049 pnh_->param("approximate_sync", approximate_sync_, false);
00050 pnh_->param("tf_queue_size", tf_queue_size_, 10);
00051 pub_ = advertise<jsk_recognition_msgs::RectArray>(*pnh_, "output", 1);
00052 pub_internal_ = pnh_->advertise<jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo>("internal", 1);
00053 sub_box_with_info_.subscribe(*pnh_, "internal", 1);
00054
00055 }
00056
00057 void BoundingBoxToRect::subscribe()
00058 {
00059
00060 sub_info_.subscribe(*pnh_, "input/info", 1);
00061 sub_boxes_.subscribe(*pnh_, "input", 1);
00062 if (approximate_sync_) {
00063 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
00064 async_->connectInput(sub_info_, sub_boxes_);
00065 async_->registerCallback(boost::bind(&BoundingBoxToRect::inputCallback, this, _1, _2));
00066 } else {
00067 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00068 sync_->connectInput(sub_info_, sub_boxes_);
00069 sync_->registerCallback(boost::bind(&BoundingBoxToRect::inputCallback, this, _1, _2));
00070 }
00071
00072 sub_box_.subscribe(*pnh_, "input/box", 1);
00073 if (approximate_sync_) {
00074 async_box_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicyBox> >(queue_size_);
00075 async_box_->connectInput(sub_info_, sub_box_);
00076 async_box_->registerCallback(boost::bind(&BoundingBoxToRect::inputBoxCallback, this, _1, _2));
00077 } else {
00078 sync_box_ = boost::make_shared<message_filters::Synchronizer<SyncPolicyBox> >(queue_size_);
00079 sync_box_->connectInput(sub_info_, sub_box_);
00080 sync_box_->registerCallback(boost::bind(&BoundingBoxToRect::inputBoxCallback, this, _1, _2));
00081 }
00082 }
00083
00084 void BoundingBoxToRect::unsubscribe()
00085 {
00086 sub_info_.unsubscribe();
00087 sub_boxes_.unsubscribe();
00088 sub_box_.unsubscribe();
00089 frame_id_ = "";
00090 }
00091
00092 void BoundingBoxToRect::inputBoxCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg,
00093 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
00094 {
00095 jsk_recognition_msgs::BoundingBoxArray::Ptr boxes_msg(
00096 new jsk_recognition_msgs::BoundingBoxArray());
00097 boxes_msg->header = box_msg->header;
00098 boxes_msg->boxes.push_back(*box_msg);
00099 inputCallback(info_msg, boxes_msg);
00100 }
00101
00102 void BoundingBoxToRect::inputCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg,
00103 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& boxes_msg)
00104 {
00105 boost::mutex::scoped_lock lock(mutex_);
00106 if (frame_id_.empty()) {
00107
00108 frame_id_ = boxes_msg->header.frame_id;
00109 tf_filter_.reset(new tf::MessageFilter<jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo>(
00110 sub_box_with_info_,
00111 *tf_listener_,
00112 frame_id_,
00113 tf_queue_size_));
00114 tf_filter_->registerCallback(boost::bind(&BoundingBoxToRect::internalCallback, this, _1));
00115 }
00116 jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo internal_msg;
00117 internal_msg.header = boxes_msg->header;
00118 internal_msg.boxes = *boxes_msg;
00119 internal_msg.camera_info = *info_msg;
00120 pub_internal_.publish(internal_msg);
00121 }
00122
00123 void BoundingBoxToRect::internalCallback(
00124 const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr& msg)
00125 {
00126 boost::mutex::scoped_lock lock(mutex_);
00127 tf::StampedTransform box_to_info_tf = jsk_recognition_utils::lookupTransformWithDuration(
00128 tf_listener_,
00129 msg->boxes.header.frame_id,
00130 msg->camera_info.header.frame_id,
00131 msg->boxes.header.stamp,
00132 ros::Duration(0.0));
00133 Eigen::Affine3f box_to_info;
00134 tf::transformTFToEigen(box_to_info_tf, box_to_info);
00135 image_geometry::PinholeCameraModel model;
00136 model.fromCameraInfo(msg->camera_info);
00137 jsk_recognition_msgs::RectArray rect_array;
00138 rect_array.header = msg->camera_info.header;
00139 for (size_t i = 0; i < msg->boxes.boxes.size(); i++) {
00140 jsk_recognition_msgs::BoundingBox box = msg->boxes.boxes[i];
00141 jsk_recognition_utils::Cube cube(box);
00142 jsk_recognition_utils::Vertices vertices = cube.transformVertices(box_to_info);
00143 std::vector<cv::Point> points = jsk_recognition_utils::project3DPointstoPixel(model, vertices);
00144 cv::Rect rect = cv::boundingRect(points);
00145 jsk_recognition_msgs::Rect ros_rect;
00146 ros_rect.x = rect.x;
00147 ros_rect.y = rect.y;
00148 ros_rect.width = rect.width;
00149 ros_rect.height = rect.height;
00150 rect_array.rects.push_back(ros_rect);
00151 }
00152 pub_.publish(rect_array);
00153 }
00154 }
00155
00156 #include <pluginlib/class_list_macros.h>
00157 PLUGINLIB_EXPORT_CLASS (jsk_perception::BoundingBoxToRect, nodelet::Nodelet);