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 #include "jsk_pcl_ros/normal_direction_filter.h"
00037 #include "jsk_recognition_utils/pcl_conversion_util.h"
00038 #include <jsk_topic_tools/rosparam_utils.h>
00039 #include <eigen_conversions/eigen_msg.h>
00040
00041 namespace jsk_pcl_ros
00042 {
00043 void NormalDirectionFilter::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 pnh_->param("use_imu", use_imu_, false);
00047 if (!use_imu_) {
00048 std::vector<double> direction;
00049 if (!jsk_topic_tools::readVectorParameter(*pnh_, "direction", direction)) {
00050 NODELET_ERROR("You need to specify ~direction");
00051 return;
00052 }
00053 jsk_recognition_utils::pointFromVectorToVector<std::vector<double>, Eigen::Vector3f>(
00054 direction, static_direction_);
00055 }
00056 else {
00057 tf_listener_ = TfListenerSingleton::getInstance();
00058 }
00059
00060 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00061 dynamic_reconfigure::Server<Config>::CallbackType f =
00062 boost::bind (
00063 &NormalDirectionFilter::configCallback, this, _1, _2);
00064 srv_->setCallback (f);
00065 pnh_->param("queue_size", queue_size_, 200);
00066 pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
00067 onInitPostProcess();
00068 }
00069
00070
00071 void NormalDirectionFilter::configCallback(Config &config, uint32_t level)
00072 {
00073 boost::mutex::scoped_lock lock(mutex_);
00074 eps_angle_ = config.eps_angle;
00075 angle_offset_ = config.angle_offset;
00076 }
00077
00078 void NormalDirectionFilter::subscribe()
00079 {
00080 if (!use_imu_) {
00081 sub_ = pnh_->subscribe("input", 1, &NormalDirectionFilter::filter, this);
00082 }
00083 else {
00084 sub_input_.subscribe(*pnh_, "input", 1);
00085 sub_imu_.subscribe(*pnh_, "input_imu", 1);
00086 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00087 sync_->connectInput(sub_input_, sub_imu_);
00088 sync_->registerCallback(boost::bind(&NormalDirectionFilter::filter, this, _1, _2));
00089 }
00090 }
00091
00092 void NormalDirectionFilter::unsubscribe()
00093 {
00094 if (!use_imu_) {
00095 sub_.shutdown();
00096 }
00097 else {
00098 sub_input_.unsubscribe();
00099 sub_imu_.unsubscribe();
00100 }
00101 }
00102
00103 void NormalDirectionFilter::filterIndices(
00104 const pcl::PointCloud<pcl::Normal>::Ptr& normal_cloud,
00105 const Eigen::Vector3f& direction,
00106 pcl::PointIndices& indices)
00107 {
00108 for (size_t i = 0; i < normal_cloud->points.size(); i++) {
00109 Eigen::Vector3f normal = normal_cloud->points[i].getNormalVector3fMap().normalized();
00110 if (!std::isnan(normal[0]) &&
00111 !std::isnan(normal[1]) &&
00112 !std::isnan(normal[2])) {
00113 double dot = std::abs(normal.dot(direction));
00114 if (dot < -1.0) {
00115 dot = -1.0;
00116 }
00117 else if (dot > 1.0) {
00118 dot = 1.0;
00119 }
00120 double angle = acos(dot);
00121 double angle_diff = std::abs(angle - angle_offset_);
00122 if (angle_diff < eps_angle_) {
00123 indices.indices.push_back(i);
00124 }
00125 }
00126 }
00127 }
00128
00129 void NormalDirectionFilter::filter(
00130 const sensor_msgs::PointCloud2::ConstPtr& msg,
00131 const sensor_msgs::Imu::ConstPtr& imu_msg)
00132 {
00133 boost::mutex::scoped_lock lock(mutex_);
00134 vital_checker_->poke();
00135 pcl::PointCloud<pcl::Normal>::Ptr normal(new pcl::PointCloud<pcl::Normal>);
00136 pcl::fromROSMsg(*msg, *normal);
00137 geometry_msgs::Vector3Stamped stamped_imu, transformed_imu;
00138 stamped_imu.header = imu_msg->header;
00139 stamped_imu.vector = imu_msg->linear_acceleration;
00140 try
00141 {
00142 tf_listener_->waitForTransform(msg->header.frame_id, imu_msg->header.frame_id, imu_msg->header.stamp,
00143 ros::Duration(0.1));
00144 tf_listener_->transformVector(
00145 msg->header.frame_id, stamped_imu, transformed_imu);
00146 Eigen::Vector3d imu_vectord;
00147 Eigen::Vector3f imu_vector;
00148 tf::vectorMsgToEigen(transformed_imu.vector, imu_vectord);
00149 jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector3d, Eigen::Vector3f>(
00150 imu_vectord, imu_vector);
00151 imu_vector.normalize();
00152 pcl::PointIndices indices;
00153 filterIndices(normal, imu_vector, indices);
00154 pcl_msgs::PointIndices ros_indices;
00155 pcl_conversions::fromPCL(indices, ros_indices);
00156 ros_indices.header = msg->header;
00157 pub_.publish(ros_indices);
00158 }
00159 catch (tf2::ConnectivityException &e)
00160 {
00161 NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00162 }
00163 catch (tf2::InvalidArgumentException &e)
00164 {
00165 NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00166 }
00167 catch (tf2::ExtrapolationException &e)
00168 {
00169 NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00170 }
00171 }
00172
00173 void NormalDirectionFilter::filter(
00174 const sensor_msgs::PointCloud2::ConstPtr& msg)
00175 {
00176 boost::mutex::scoped_lock lock(mutex_);
00177 vital_checker_->poke();
00178 pcl::PointCloud<pcl::Normal>::Ptr normal(new pcl::PointCloud<pcl::Normal>);
00179 pcl::fromROSMsg(*msg, *normal);
00180
00181 pcl::PointIndices indices;
00182 filterIndices(normal, static_direction_, indices);
00183 pcl_msgs::PointIndices ros_indices;
00184 pcl_conversions::fromPCL(indices, ros_indices);
00185 ros_indices.header = msg->header;
00186 pub_.publish(ros_indices);
00187 }
00188
00189 }
00190
00191 #include <pluginlib/class_list_macros.h>
00192 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::NormalDirectionFilter, nodelet::Nodelet);