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 #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 }
00066
00067 bool CaptureStereoSynchronizer::checkNearPose(
00068 const geometry_msgs::Pose& new_pose)
00069 {
00070 Eigen::Affine3d new_affine;
00071 tf::poseMsgToEigen(new_pose, new_affine);
00072 for (size_t i = 0; i < poses_.size(); i++) {
00073
00074 Eigen::Affine3d affine;
00075 tf::poseMsgToEigen(poses_[i], affine);
00076
00077 Eigen::Affine3d diff = affine.inverse() * new_affine;
00078 double positional_difference = diff.translation().norm();
00079 if (positional_difference < positional_bin_size_) {
00080 Eigen::AngleAxisd rotational_difference(diff.rotation());
00081 if (rotational_difference.angle() < rotational_bin_size_) {
00082 return true;
00083 }
00084 }
00085 }
00086 return false;
00087 }
00088
00089 void CaptureStereoSynchronizer::subscribe()
00090 {
00091 sub_pose_.subscribe(*pnh_, "input/pose", 1);
00092 sub_mask_.subscribe(*pnh_, "input/mask", 1);
00093 sub_mask_indices_.subscribe(*pnh_, "input/mask_indices", 1);
00094 sub_left_image_.subscribe(*pnh_, "input/left_image", 1);
00095 sub_left_cam_info_.subscribe(*pnh_, "input/left_camera_info", 1);
00096 sub_right_cam_info_.subscribe(*pnh_, "input/right_camera_info", 1);
00097 sub_disparity_.subscribe(*pnh_, "input/disparity", 1);
00098 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00099 sync_->connectInput(sub_pose_,
00100 sub_mask_,
00101 sub_mask_indices_,
00102 sub_left_image_,
00103 sub_left_cam_info_,
00104 sub_right_cam_info_,
00105 sub_disparity_);
00106 sync_->registerCallback(boost::bind(&CaptureStereoSynchronizer::republish,
00107 this,
00108 _1,
00109 _2,
00110 _3,
00111 _4,
00112 _5,
00113 _6,
00114 _7));
00115 }
00116
00117 void CaptureStereoSynchronizer::unsubscribe()
00118 {
00119 sub_pose_.unsubscribe();
00120 sub_mask_.unsubscribe();
00121 sub_mask_indices_.unsubscribe();
00122 sub_left_image_.unsubscribe();
00123 sub_left_cam_info_.unsubscribe();
00124 sub_right_cam_info_.unsubscribe();
00125 sub_disparity_.unsubscribe();
00126 }
00127
00128 void CaptureStereoSynchronizer::updateDiagnostic(
00129 diagnostic_updater::DiagnosticStatusWrapper &stat)
00130 {
00131 if (vital_checker_->isAlive()) {
00132 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00133 "CaptureStreoSynchronizer running");
00134 }
00135 else {
00136 jsk_topic_tools::addDiagnosticErrorSummary(
00137 "CaptureStreoSynchronizer", vital_checker_, stat);
00138 }
00139 }
00140
00141 void CaptureStereoSynchronizer::republish(
00142 const geometry_msgs::PoseStamped::ConstPtr& pose,
00143 const sensor_msgs::Image::ConstPtr& mask,
00144 const PCLIndicesMsg::ConstPtr& mask_indices,
00145 const sensor_msgs::Image::ConstPtr& left_image,
00146 const sensor_msgs::CameraInfo::ConstPtr& left_cam_info,
00147 const sensor_msgs::CameraInfo::ConstPtr& right_cam_info,
00148 const stereo_msgs::DisparityImage::ConstPtr& disparity)
00149 {
00150 if (checkNearPose(pose->pose)) {
00151 JSK_ROS_DEBUG("too near");
00152 }
00153 else {
00154 JSK_ROS_INFO("%d sample", counter_++);
00155 poses_.push_back(pose->pose);
00156 pub_pose_.publish(pose);
00157 pub_mask_.publish(mask);
00158 pub_mask_indices_.publish(mask_indices);
00159 pub_left_image_.publish(left_image);
00160 pub_left_cam_info_.publish(left_cam_info);
00161 pub_right_cam_info_.publish(right_cam_info);
00162 pub_disparity_.publish(disparity);
00163 }
00164 std_msgs::Int32 count;
00165 count.data = counter_;
00166 pub_count_.publish(count);
00167 }
00168 }
00169
00170 #include <pluginlib/class_list_macros.h>
00171 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::CaptureStereoSynchronizer, nodelet::Nodelet);