pointcloud_localization.h
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 
00037 #ifndef JSK_PCL_ROS_POINTCLOUD_LOCALIZATION
00038 #define JSK_PCL_ROS_POINTCLOUD_LOCALIZATION
00039 #include <tf_conversions/tf_eigen.h>
00040 #include "jsk_pcl_ros/tf_listener_singleton.h"
00041 #include <tf/transform_broadcaster.h>
00042 #include <jsk_topic_tools/diagnostic_nodelet.h>
00043 #include <std_srvs/Empty.h>
00044 #include <sensor_msgs/PointCloud2.h>
00045 #include <geometry_msgs/PoseStamped.h>
00046 #include <pcl/point_cloud.h>
00047 #include <pcl/point_types.h>
00048 #include <jsk_pcl_ros/UpdateOffset.h>
00049 
00050 namespace jsk_pcl_ros
00051 {
00052   class PointCloudLocalization: public jsk_topic_tools::DiagnosticNodelet
00053   {
00054   public:
00055     PointCloudLocalization():
00056       first_time_(true), localize_requested_(false),
00057       DiagnosticNodelet("PointCloudLocalization") {}
00058   protected:
00059     virtual void onInit();
00060     virtual void subscribe();
00061     virtual void unsubscribe();
00062 
00067     virtual void cloudCallback(
00068       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
00069 
00074     virtual bool localizationRequest(
00075       std_srvs::Empty::Request& req,
00076       std_srvs::Empty::Response& res);
00077     
00082     virtual void cloudTimerCallback(
00083       const ros::TimerEvent& event);
00084 
00089     virtual void tfTimerCallback(
00090       const ros::TimerEvent& event);
00091     
00096     virtual bool isFirstTime();
00097 
00102     virtual bool updateOffsetCallback(
00103       jsk_pcl_ros::UpdateOffset::Request& req,
00104       jsk_pcl_ros::UpdateOffset::Response& res);
00105     
00106     virtual void applyDownsampling(
00107       pcl::PointCloud<pcl::PointNormal>::Ptr in_cloud,
00108       pcl::PointCloud<pcl::PointNormal>& out_cloud);
00109 
00110     boost::mutex mutex_;
00111     boost::mutex tf_mutex_;
00112     ros::Subscriber sub_;
00113     ros::Publisher pub_cloud_;
00114     tf::TransformListener* tf_listener_;
00115     ros::ServiceServer localization_srv_;
00116     ros::ServiceServer update_offset_srv_;
00117     ros::Timer cloud_timer_;
00118     ros::Timer tf_timer_;
00119     pcl::PointCloud<pcl::PointNormal>::Ptr all_cloud_;
00120     sensor_msgs::PointCloud2::ConstPtr latest_cloud_;
00121     tf::TransformBroadcaster tf_broadcast_;
00122     bool localize_requested_;
00123     std::string sensor_frame_;
00124     bool clip_unseen_pointcloud_;
00125     bool initialize_from_tf_;
00126     std::string initialize_tf_;
00131     std::string global_frame_;
00132     std::string odom_frame_;
00133 
00138     bool use_normal_;
00139     double leaf_size_;
00140     tf::Transform localize_transform_;
00141     bool first_time_;
00142   private:
00143     
00144   };
00145 }
00146 
00147 #endif


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