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 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros/intermittent_image_annotator.h"
00037 #include <tf_conversions/tf_eigen.h>
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 #include <eigen_conversions/eigen_msg.h>
00041 #include "jsk_pcl_ros/pcl_conversion_util.h"
00042 #include <visualization_msgs/Marker.h>
00043 #include "jsk_pcl_ros/geo_util.h"
00044 #include <pcl/filters/extract_indices.h>
00045 namespace jsk_pcl_ros
00046 {
00047 void IntermittentImageAnnotator::onInit()
00048 {
00049 DiagnosticNodelet::onInit();
00050 listener_ = TfListenerSingleton::getInstance();
00051 last_publish_time_ = ros::Time::now();
00052 pnh_->param("fixed_frame_id", fixed_frame_id_, std::string("odom"));
00053 pnh_->param("max_image_buffer", max_image_buffer_, 5);
00054 pnh_->param("rate", rate_, 1.0);
00055 pnh_->param("store_pointcloud", store_pointcloud_, false);
00056 pnh_->param("keep_organized", keep_organized_, false);
00057 pub_pose_ = pnh_->advertise<geometry_msgs::PoseStamped>(
00058 "output/direction", 1);
00059 pub_cloud_ = pnh_->advertise<sensor_msgs::PointCloud2>(
00060 "output/cloud", 1);
00061 pub_roi_ = pnh_->advertise<jsk_recognition_msgs::PosedCameraInfo>(
00062 "output/roi", 1);
00063 pub_marker_ = pnh_->advertise<visualization_msgs::Marker>(
00064 "output/marker", 1);
00065
00066 snapshot_buffer_ = boost::circular_buffer<SnapshotInformation::Ptr>(
00067 max_image_buffer_);
00068 image_transport::ImageTransport it(*pnh_);
00069 image_pub_ = it.advertise("output", 1);
00070 image_sub_ = it.subscribeCamera(
00071 "input/image", 1,
00072 &IntermittentImageAnnotator::cameraCallback,
00073 this);
00074 rect_sub_ = pnh_->subscribe("output/screenrectangle", 1,
00075 &IntermittentImageAnnotator::rectCallback,
00076 this);
00077 if (store_pointcloud_) {
00078 cloud_sub_ = pnh_->subscribe("input/cloud", 1,
00079 &IntermittentImageAnnotator::cloudCallback,
00080 this);
00081 }
00082 shutter_service_ = pnh_->advertiseService(
00083 "shutter",
00084 &IntermittentImageAnnotator::shutterCallback, this);
00085 request_service_ = pnh_->advertiseService(
00086 "request",
00087 &IntermittentImageAnnotator::requestCallback, this);
00088 clear_service_ = pnh_->advertiseService(
00089 "clear",
00090 &IntermittentImageAnnotator::clearCallback, this);
00091 }
00092
00093
00094 void IntermittentImageAnnotator::subscribe()
00095 {
00096 }
00097
00098 void IntermittentImageAnnotator::unsubscribe()
00099 {
00100 }
00101
00102 void IntermittentImageAnnotator::rectCallback(
00103 const geometry_msgs::PolygonStamped::ConstPtr& rect)
00104 {
00105 boost::mutex::scoped_lock lock(mutex_);
00106 int x0 = rect->polygon.points[0].x;
00107 int x1 = rect->polygon.points[1].x;
00108 int y0 = rect->polygon.points[0].y;
00109 int y1 = rect->polygon.points[1].y;
00110 if (x0 > x1) {
00111 std::swap(x0, x1);
00112 }
00113 if (y0 > y1) {
00114 std::swap(y0, y1);
00115 }
00116
00117 int width = latest_image_msg_->width;
00118 int x0_index = x0 / width;
00119 int x1_index = x1 / width;
00120 if (x0_index != x1_index) {
00121 JSK_NODELET_WARN("malformed rectangle");
00122 return;
00123 }
00124 else {
00125 int image_index = x0_index;
00126 JSK_NODELET_INFO("image index: %d", image_index);
00127 SnapshotInformation::Ptr info = snapshot_buffer_[image_index];
00128
00129 int width_offset = width * image_index;
00130 int x0_wo_offset = x0 - width_offset;
00131 int x1_wo_offset = x1 - width_offset;
00132 cv::Point2d mid((x0_wo_offset + x1_wo_offset) / 2.0,
00133 (y0 + y1) / 2.0);
00134 Eigen::Affine3d pose(info->camera_pose_);
00135 image_geometry::PinholeCameraModel camera_model = info->camera_;
00136 cv::Point3d mid_3d = camera_model.projectPixelTo3dRay(mid);
00137 Eigen::Vector3d ray(mid_3d.x, mid_3d.y, mid_3d.z);
00138 ray = ray / ray.norm();
00139 Eigen::Vector3d ray_global = pose.rotation() * ray;
00140 JSK_NODELET_INFO("ray: [%f, %f, %f]", ray_global[0], ray_global[1], ray_global[2]);
00141
00142 Eigen::Vector3d z = pose.rotation() * Eigen::Vector3d::UnitZ();
00143 JSK_NODELET_INFO("z: [%f, %f, %f]", z[0], z[1], z[2]);
00144 Eigen::Vector3d original_pos = pose.translation();
00145 Eigen::Quaterniond q;
00146 q.setFromTwoVectors(z, ray_global);
00147 JSK_NODELET_INFO("q: [%f, %f, %f, %f]", q.x(), q.y(), q.z(), q.w());
00148 Eigen::Affine3d output_pose = pose.rotate(q);
00149 output_pose.translation() = original_pos;
00150 geometry_msgs::PoseStamped ros_pose;
00151 tf::poseEigenToMsg(output_pose, ros_pose.pose);
00152 ros_pose.header.stamp = latest_image_msg_->header.stamp;
00153 ros_pose.header.frame_id = fixed_frame_id_;
00154 pub_pose_.publish(ros_pose);
00155
00156
00157 jsk_recognition_msgs::PosedCameraInfo camera_info;
00158 camera_info.header.stamp = latest_image_msg_->header.stamp;
00159 camera_info.header.frame_id = fixed_frame_id_;
00160 camera_info.camera_info
00161 = sensor_msgs::CameraInfo(info->camera_.cameraInfo());
00162 camera_info.camera_info.roi.x_offset = x0_wo_offset;
00163 camera_info.camera_info.roi.y_offset = y0;
00164 camera_info.camera_info.roi.width = x1_wo_offset - x0_wo_offset;
00165 camera_info.camera_info.roi.height = y1 - y0;
00166 tf::poseEigenToMsg(info->camera_pose_, camera_info.offset);
00167 pub_roi_.publish(camera_info);
00168
00169
00170
00171 cv::Point2d A(x0_wo_offset, y0);
00172 cv::Point2d B(x0_wo_offset, y1);
00173 cv::Point2d C(x1_wo_offset, y1);
00174 cv::Point2d D(x1_wo_offset, y0);
00175
00176 cv::Point3d A_3d = info->camera_.projectPixelTo3dRay(A) * 3;
00177 cv::Point3d B_3d = info->camera_.projectPixelTo3dRay(B) * 3;
00178 cv::Point3d C_3d = info->camera_.projectPixelTo3dRay(C) * 3;
00179 cv::Point3d D_3d = info->camera_.projectPixelTo3dRay(D) * 3;
00180 cv::Point3d O_3d;
00181
00182 geometry_msgs::Point A_ros, B_ros, C_ros, D_ros, O_ros;
00183 pointFromXYZToXYZ<cv::Point3d, geometry_msgs::Point>(A_3d, A_ros);
00184 pointFromXYZToXYZ<cv::Point3d, geometry_msgs::Point>(B_3d, B_ros);
00185 pointFromXYZToXYZ<cv::Point3d, geometry_msgs::Point>(C_3d, C_ros);
00186 pointFromXYZToXYZ<cv::Point3d, geometry_msgs::Point>(D_3d, D_ros);
00187 pointFromXYZToXYZ<cv::Point3d, geometry_msgs::Point>(O_3d, O_ros);
00188
00189 visualization_msgs::Marker marker;
00190 marker.header.stamp = latest_image_msg_->header.stamp;
00191 marker.header.frame_id = fixed_frame_id_;
00192 tf::poseEigenToMsg(info->camera_pose_, marker.pose);
00193 marker.type = visualization_msgs::Marker::LINE_LIST;
00194 marker.points.push_back(O_ros); marker.points.push_back(A_ros);
00195 marker.points.push_back(O_ros); marker.points.push_back(B_ros);
00196 marker.points.push_back(O_ros); marker.points.push_back(C_ros);
00197 marker.points.push_back(O_ros); marker.points.push_back(D_ros);
00198 marker.points.push_back(A_ros); marker.points.push_back(B_ros);
00199 marker.points.push_back(B_ros); marker.points.push_back(C_ros);
00200 marker.points.push_back(C_ros); marker.points.push_back(D_ros);
00201 marker.points.push_back(D_ros); marker.points.push_back(A_ros);
00202 marker.scale.x = 0.01;
00203 marker.scale.y = 0.01;
00204 marker.scale.z = 0.01;
00205 marker.color.a = 1.0;
00206 marker.color.r = 1.0;
00207 pub_marker_.publish(marker);
00208
00209
00210 if (store_pointcloud_) {
00211 publishCroppedPointCloud(info->cloud_,
00212 A_3d, B_3d, C_3d, D_3d,
00213 info->camera_pose_);
00214 }
00215 }
00216 }
00217
00218
00219 void IntermittentImageAnnotator::publishCroppedPointCloud(
00220 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
00221 const cv::Point3d& A, const cv::Point3d& B,
00222 const cv::Point3d& C, const cv::Point3d& D,
00223 const Eigen::Affine3d& pose)
00224 {
00225 Eigen::Vector3f A_eigen, B_eigen, C_eigen, D_eigen;
00226 pointFromXYZToVector<cv::Point3d, Eigen::Vector3f>(
00227 A, A_eigen);
00228 pointFromXYZToVector<cv::Point3d, Eigen::Vector3f>(
00229 B, B_eigen);
00230 pointFromXYZToVector<cv::Point3d, Eigen::Vector3f>(
00231 C, C_eigen);
00232 pointFromXYZToVector<cv::Point3d, Eigen::Vector3f>(
00233 D, D_eigen);
00234 Eigen::Affine3f posef;
00235 convertEigenAffine3(pose, posef);
00236 Eigen::Vector3f A_global = posef * A_eigen;
00237 Eigen::Vector3f B_global = posef * B_eigen;
00238 Eigen::Vector3f C_global = posef * C_eigen;
00239 Eigen::Vector3f D_global = posef * D_eigen;
00240 Eigen::Vector3f O_global = posef.translation();
00241 Vertices vertices0, vertices1, vertices2, vertices3;
00242 vertices0.push_back(O_global); vertices0.push_back(A_global); vertices0.push_back(D_global);
00243 vertices1.push_back(O_global); vertices1.push_back(B_global); vertices1.push_back(A_global);
00244 vertices2.push_back(O_global); vertices2.push_back(C_global); vertices2.push_back(B_global);
00245 vertices3.push_back(O_global); vertices3.push_back(D_global); vertices3.push_back(C_global);
00246 Polygon::Ptr plane0 (new Polygon(vertices0));
00247 Polygon::Ptr plane1 (new Polygon(vertices1));
00248 Polygon::Ptr plane2 (new Polygon(vertices2));
00249 Polygon::Ptr plane3 (new Polygon(vertices3));
00250 pcl::PointIndices::Ptr indices(new pcl::PointIndices);
00251 for (size_t i = 0; i < cloud->points.size(); i++) {
00252 pcl::PointXYZRGB p = cloud->points[i];
00253 Eigen::Vector3f pf = p.getVector3fMap();
00254 if (!isnan(p.x) && !isnan(p.y) && !isnan(p.z)) {
00255 if (plane0->signedDistanceToPoint(pf) > 0 &&
00256 plane1->signedDistanceToPoint(pf) > 0 &&
00257 plane2->signedDistanceToPoint(pf) > 0 &&
00258 plane3->signedDistanceToPoint(pf) > 0) {
00259 indices->indices.push_back(i);
00260 }
00261 }
00262 }
00263 pcl::ExtractIndices<pcl::PointXYZRGB> ex;
00264 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00265 ex.setInputCloud(cloud);
00266 ex.setKeepOrganized(keep_organized_);
00267 ex.setIndices(indices);
00268 ex.filter(*output_cloud);
00269 sensor_msgs::PointCloud2 ros_cloud;
00270 pcl::toROSMsg(*output_cloud, ros_cloud);
00271 ros_cloud.header.stamp = latest_image_msg_->header.stamp;
00272 ros_cloud.header.frame_id = fixed_frame_id_;
00273 pub_cloud_.publish(ros_cloud);
00274 }
00275
00276 void IntermittentImageAnnotator::cloudCallback(
00277 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00278 {
00279 boost::mutex::scoped_lock lock(mutex_);
00280 latest_cloud_msg_ = cloud_msg;
00281 }
00282
00283 void IntermittentImageAnnotator::cameraCallback(
00284 const sensor_msgs::Image::ConstPtr& image_msg,
00285 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00286 {
00287 boost::mutex::scoped_lock lock(mutex_);
00288 vital_checker_->poke();
00289 latest_image_msg_ = image_msg;
00290 latest_camera_info_msg_ = info_msg;
00291
00292 if (snapshot_buffer_.size() != 0) {
00293 ros::Time now = ros::Time::now();
00294 if ((now - last_publish_time_).toSec() > 1.0 / rate_) {
00295 cv::Mat concatenated_image;
00296 std::vector<cv::Mat> images;
00297
00298 for (size_t i = 0; i < snapshot_buffer_.size(); i++) {
00299 images.push_back(snapshot_buffer_[i]->image_);
00300 }
00301 cv::hconcat(images, concatenated_image);
00302 cv_bridge::CvImage concatenate_bridge(latest_camera_info_msg_->header,
00303 sensor_msgs::image_encodings::BGR8,
00304 concatenated_image);
00305 image_pub_.publish(concatenate_bridge.toImageMsg());
00306 last_publish_time_ = now;
00307 }
00308 }
00309
00310 }
00311
00312 void IntermittentImageAnnotator::waitForNextImage()
00313 {
00314 ros::Time now = ros::Time::now();
00315 ros::Rate r(10);
00316 while (ros::ok()) {
00317 {
00318 boost::mutex::scoped_lock lock(mutex_);
00319 if (latest_image_msg_ && latest_image_msg_->header.stamp > now) {
00320 return;
00321 }
00322 }
00323 r.sleep();
00324 }
00325 }
00326
00327 bool IntermittentImageAnnotator::shutterCallback(
00328 std_srvs::Empty::Request& req,
00329 std_srvs::Empty::Response& res)
00330 {
00331
00332 waitForNextImage();
00333 {
00334 boost::mutex::scoped_lock lock(mutex_);
00335 if (latest_camera_info_msg_) {
00336 SnapshotInformation::Ptr
00337 info (new SnapshotInformation());
00338
00339 try {
00340 if (listener_->waitForTransform(
00341 fixed_frame_id_,
00342 latest_camera_info_msg_->header.frame_id,
00343 latest_camera_info_msg_->header.stamp,
00344 ros::Duration(1.0))) {
00345 tf::StampedTransform transform;
00346 listener_->lookupTransform(fixed_frame_id_,
00347 latest_camera_info_msg_->header.frame_id,
00348 latest_camera_info_msg_->header.stamp,
00349 transform);
00350 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00351 latest_image_msg_,
00352 sensor_msgs::image_encodings::BGR8);
00353 Eigen::Affine3d eigen_transform;
00354 image_geometry::PinholeCameraModel camera;
00355 camera.fromCameraInfo(latest_camera_info_msg_);
00356 tf::transformTFToEigen(transform, eigen_transform);
00357 info->camera_pose_ = eigen_transform;
00358 info->camera_ = camera;
00359 info->image_ = cv_ptr->image;
00360 if (store_pointcloud_) {
00361
00362 if (!latest_cloud_msg_) {
00363 JSK_NODELET_ERROR("no pointcloud is available");
00364 return false;
00365 }
00366
00367 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00368 nontransformed_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00369 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00370 transformed_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00371 pcl::fromROSMsg(*latest_cloud_msg_, *nontransformed_cloud);
00372 if (pcl_ros::transformPointCloud(fixed_frame_id_,
00373 *nontransformed_cloud,
00374 *transformed_cloud,
00375 *listener_)) {
00376 info->cloud_ = transformed_cloud;
00377 }
00378 else {
00379 JSK_NODELET_ERROR("failed to transform pointcloud");
00380 return false;
00381 }
00382 }
00383 snapshot_buffer_.push_back(info);
00384 return true;
00385 }
00386 else {
00387 JSK_NODELET_ERROR("failed to resolve tf from %s to %s",
00388 fixed_frame_id_.c_str(),
00389 latest_camera_info_msg_->header.frame_id.c_str());
00390 return false;
00391 }
00392 }
00393 catch (tf2::ConnectivityException &e)
00394 {
00395 JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00396 return false;
00397 }
00398 catch (tf2::InvalidArgumentException &e)
00399 {
00400 JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00401 return false;
00402 }
00403 }
00404 else {
00405 JSK_NODELET_ERROR("not yet camera message is available");
00406 return false;
00407 }
00408 }
00409 }
00410
00411 bool IntermittentImageAnnotator::clearCallback(
00412 std_srvs::Empty::Request& req,
00413 std_srvs::Empty::Response& res)
00414 {
00415 boost::mutex::scoped_lock lock(mutex_);
00416 snapshot_buffer_.clear();
00417 return true;
00418 }
00419
00420 bool IntermittentImageAnnotator::requestCallback(
00421 std_srvs::Empty::Request& req,
00422 std_srvs::Empty::Response& res)
00423 {
00424
00425 boost::mutex::scoped_lock lock(mutex_);
00426 if (snapshot_buffer_.size() == 0) {
00427 JSK_NODELET_ERROR("no image is stored");
00428 return false;
00429 }
00430 else {
00431 cv::Mat concatenated_image;
00432 std::vector<cv::Mat> images;
00433 JSK_ROS_INFO("%lu images", snapshot_buffer_.size());
00434 for (size_t i = 0; i < snapshot_buffer_.size(); i++) {
00435 images.push_back(snapshot_buffer_[i]->image_);
00436 }
00437 cv::hconcat(images, concatenated_image);
00438 cv_bridge::CvImage concatenate_bridge(latest_camera_info_msg_->header,
00439 sensor_msgs::image_encodings::BGR8,
00440 concatenated_image);
00441 image_pub_.publish(concatenate_bridge.toImageMsg());
00442 return true;
00443 }
00444 }
00445
00446 void IntermittentImageAnnotator::updateDiagnostic(
00447 diagnostic_updater::DiagnosticStatusWrapper &stat)
00448 {
00449 if (vital_checker_->isAlive()) {
00450 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00451 "IntermittentImageAnnotator running");
00452 }
00453 else {
00454 jsk_topic_tools::addDiagnosticErrorSummary(
00455 "IntermittentImageAnnotator", vital_checker_, stat);
00456 }
00457 }
00458 }
00459
00460 #include <pluginlib/class_list_macros.h>
00461 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::IntermittentImageAnnotator, nodelet::Nodelet);