Go to the documentation of this file.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_topic_tools/log_utils.h>
00037 #include "jsk_pcl_ros/transform_pointcloud_in_bounding_box.h"
00038 #include <eigen_conversions/eigen_msg.h>
00039 #include "jsk_pcl_ros/pcl_conversion_util.h"
00040 #include <pcl/common/transforms.h>
00041
00042 namespace jsk_pcl_ros
00043 {
00044 void TransformPointcloudInBoundingBox::onInit()
00045 {
00046 PCLNodelet::onInit();
00047 tf_listener_ = TfListenerSingleton::getInstance();
00049
00051 pub_cloud_ = pnh_->advertise<sensor_msgs::PointCloud2>("output", 1);
00052 pub_offset_pose_ = pnh_->advertise<geometry_msgs::PoseStamped>(
00053 "output_offset", 1);
00054
00056
00058 sub_input_.subscribe(*pnh_, "input", 1);
00059 sub_box_.subscribe(*pnh_, "input_box", 1);
00060 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00061 sync_->connectInput(sub_input_, sub_box_);
00062 sync_->registerCallback(boost::bind(
00063 &TransformPointcloudInBoundingBox::transform,
00064 this, _1, _2));
00065 }
00066
00067 void TransformPointcloudInBoundingBox::transform(
00068 const sensor_msgs::PointCloud2::ConstPtr& msg,
00069 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
00070 {
00071 try
00072 {
00073 pcl::PointCloud<PointT> output;
00074 Eigen::Affine3f offset;
00075 transformPointcloudInBoundingBox<PointT>(
00076 *box_msg, *msg,
00077 output, offset,
00078 *tf_listener_);
00079 sensor_msgs::PointCloud2 ros_output;
00080 pcl::toROSMsg(output, ros_output);
00081 pub_cloud_.publish(ros_output);
00082
00083 }
00084 catch (tf2::ConnectivityException &e)
00085 {
00086 JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00087 }
00088 catch (tf2::InvalidArgumentException &e)
00089 {
00090 JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00091 }
00092 }
00093 }
00094
00095 #include <pluginlib/class_list_macros.h>
00096 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::TransformPointcloudInBoundingBox,
00097 nodelet::Nodelet);