transform_pointcloud_in_bounding_box_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 #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     // pulishers
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     // Subscription
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       //pub_offset_pose_.publish(box_pose_respected_to_cloud);
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);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48