pointcloud_relative_from_pose_stamped_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, 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 
00038 #include "jsk_pcl_ros_utils/pointcloud_relative_from_pose_stamped.h"
00039 #include <jsk_recognition_utils/tf_listener_singleton.h>
00040 #include <jsk_recognition_utils/pcl_conversion_util.h>
00041 #include <jsk_recognition_utils/pcl_ros_util.h>
00042 #include <pcl/common/transforms.h>
00043 
00044 namespace jsk_pcl_ros_utils
00045 {
00046   void PointCloudRelativeFromPoseStamped::onInit()
00047   {
00048     DiagnosticNodelet::onInit();
00049     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00050     onInitPostProcess();
00051   }
00052   
00053   void PointCloudRelativeFromPoseStamped::subscribe()
00054   {
00055     sub_cloud_.subscribe(*pnh_, "input", 1);
00056     sub_pose_.subscribe(*pnh_, "input/pose", 1);
00057     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00058     sync_->connectInput(sub_cloud_, sub_pose_);
00059     sync_->registerCallback(boost::bind(&PointCloudRelativeFromPoseStamped::transform, this, _1, _2));
00060   }
00061   
00062   void PointCloudRelativeFromPoseStamped::unsubscribe()
00063   {
00064     sub_cloud_.unsubscribe();
00065     sub_pose_.unsubscribe();
00066   }
00067 
00068   void PointCloudRelativeFromPoseStamped::transform(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00069                                                     const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
00070   {
00071     vital_checker_->poke();
00072     if (!jsk_recognition_utils::isSameFrameId(cloud_msg->header.frame_id,
00073                                              pose_msg->header.frame_id)) {
00074       NODELET_ERROR("frame_id does not match. cloud: %s, pose: %s",
00075                         cloud_msg->header.frame_id.c_str(),
00076                         pose_msg->header.frame_id.c_str());
00077       return;
00078     }
00079     Eigen::Affine3f transform;
00080     tf::poseMsgToEigen(pose_msg->pose, transform);
00081     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00082     pcl::PointCloud<pcl::PointXYZ>::Ptr transformed_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00083     pcl::fromROSMsg(*cloud_msg, *cloud);
00084     Eigen::Affine3f inverse_transform = transform.inverse();
00085     pcl::transformPointCloud(*cloud, *transformed_cloud, inverse_transform);
00086     sensor_msgs::PointCloud2 ros_cloud;
00087     pcl::toROSMsg(*transformed_cloud, ros_cloud);
00088     ros_cloud.header = cloud_msg->header;
00089     pub_.publish(ros_cloud);
00090   }
00091 }
00092 
00093 #include <pluginlib/class_list_macros.h>
00094 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped, nodelet::Nodelet);


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:05