capture_stereo_synchronizer_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_pcl_ros/capture_stereo_synchronizer.h"
00038 #include <pcl/common/angles.h>
00039 #include <eigen_conversions/eigen_msg.h>
00040 #include <std_msgs/Int32.h>
00041 
00042 namespace jsk_pcl_ros
00043 {
00044   void CaptureStereoSynchronizer::onInit()
00045   {
00046     DiagnosticNodelet::onInit();
00047     counter_ = 0;
00048     pnh_->param("rotational_bin_size", rotational_bin_size_, pcl::deg2rad(10.0));
00049     pnh_->param("positional_bin_size", positional_bin_size_, 0.1);
00050     pub_pose_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output/pose", 1);
00051     pub_mask_ = advertise<sensor_msgs::Image>(*pnh_, "output/mask", 1);
00052     poses_.resize(0);
00053     pub_mask_indices_ = advertise<PCLIndicesMsg>(
00054       *pnh_, "output/mask_indices", 1);
00055     pub_left_image_ = advertise<sensor_msgs::Image>(
00056       *pnh_, "output/left_image", 1);
00057     pub_left_cam_info_ = advertise<sensor_msgs::CameraInfo>(
00058       *pnh_, "output/left_camera_info", 1);
00059     pub_right_cam_info_ = advertise<sensor_msgs::CameraInfo>(
00060       *pnh_, "output/right_camera_info", 1);
00061     pub_disparity_ = advertise<stereo_msgs::DisparityImage>(
00062       *pnh_, "output/disparity", 1);
00063     pub_count_ = advertise<std_msgs::Int32>(
00064       *pnh_, "output/count", 1);
00065     onInitPostProcess();
00066  }
00067 
00068   bool CaptureStereoSynchronizer::checkNearPose(
00069     const geometry_msgs::Pose& new_pose)
00070   {
00071     Eigen::Affine3d new_affine;
00072     tf::poseMsgToEigen(new_pose, new_affine);
00073     for (size_t i = 0; i < poses_.size(); i++) {
00074       // convert pose into eigen
00075       Eigen::Affine3d affine;
00076       tf::poseMsgToEigen(poses_[i], affine);
00077       // compute difference
00078       Eigen::Affine3d diff = affine.inverse() * new_affine;
00079       double positional_difference = diff.translation().norm();
00080       if (positional_difference < positional_bin_size_) {
00081         Eigen::AngleAxisd rotational_difference(diff.rotation());
00082         if (rotational_difference.angle() < rotational_bin_size_) {
00083           return true;
00084         }
00085       }
00086     }
00087     return false;
00088   }
00089   
00090   void CaptureStereoSynchronizer::subscribe()
00091   {
00092     sub_pose_.subscribe(*pnh_, "input/pose", 1);
00093     sub_mask_.subscribe(*pnh_, "input/mask", 1);
00094     sub_mask_indices_.subscribe(*pnh_, "input/mask_indices", 1);
00095     sub_left_image_.subscribe(*pnh_, "input/left_image", 1);
00096     sub_left_cam_info_.subscribe(*pnh_, "input/left_camera_info", 1);
00097     sub_right_cam_info_.subscribe(*pnh_, "input/right_camera_info", 1);
00098     sub_disparity_.subscribe(*pnh_, "input/disparity", 1);
00099     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00100     sync_->connectInput(sub_pose_,
00101                         sub_mask_,
00102                         sub_mask_indices_,
00103                         sub_left_image_,
00104                         sub_left_cam_info_,
00105                         sub_right_cam_info_,
00106                         sub_disparity_);
00107     sync_->registerCallback(boost::bind(&CaptureStereoSynchronizer::republish,
00108                                         this,
00109                                         _1,
00110                                         _2,
00111                                         _3,
00112                                         _4,
00113                                         _5,
00114                                         _6,
00115                                         _7));
00116   }
00117 
00118   void CaptureStereoSynchronizer::unsubscribe()
00119   {
00120     sub_pose_.unsubscribe();
00121     sub_mask_.unsubscribe();
00122     sub_mask_indices_.unsubscribe();
00123     sub_left_image_.unsubscribe();
00124     sub_left_cam_info_.unsubscribe();
00125     sub_right_cam_info_.unsubscribe();
00126     sub_disparity_.unsubscribe();
00127   }
00128 
00129   void CaptureStereoSynchronizer::republish(
00130     const geometry_msgs::PoseStamped::ConstPtr& pose,
00131     const sensor_msgs::Image::ConstPtr& mask,
00132     const PCLIndicesMsg::ConstPtr& mask_indices,
00133     const sensor_msgs::Image::ConstPtr& left_image,
00134     const sensor_msgs::CameraInfo::ConstPtr& left_cam_info,
00135     const sensor_msgs::CameraInfo::ConstPtr& right_cam_info,
00136     const stereo_msgs::DisparityImage::ConstPtr& disparity)
00137   {
00138     if (checkNearPose(pose->pose)) {
00139       ROS_DEBUG("too near");
00140     }
00141     else {
00142       ROS_INFO("%d sample", counter_++);
00143       poses_.push_back(pose->pose);
00144       pub_pose_.publish(pose);
00145       pub_mask_.publish(mask);
00146       pub_mask_indices_.publish(mask_indices);
00147       pub_left_image_.publish(left_image);
00148       pub_left_cam_info_.publish(left_cam_info);
00149       pub_right_cam_info_.publish(right_cam_info);
00150       pub_disparity_.publish(disparity);
00151     }
00152     std_msgs::Int32 count;
00153     count.data = counter_;
00154     pub_count_.publish(count);
00155   }
00156 }
00157 
00158 #include <pluginlib/class_list_macros.h>
00159 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::CaptureStereoSynchronizer, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:42