pointcloud_localization.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_POINTCLOUD_LOCALIZATION
38 #define JSK_PCL_ROS_POINTCLOUD_LOCALIZATION
42 #include <jsk_topic_tools/diagnostic_nodelet.h>
43 #include <std_srvs/Empty.h>
44 #include <sensor_msgs/PointCloud2.h>
45 #include <geometry_msgs/PoseStamped.h>
46 #include <pcl/point_cloud.h>
47 #include <pcl/point_types.h>
48 #include <jsk_recognition_msgs/UpdateOffset.h>
49 
50 namespace jsk_pcl_ros
51 {
52  class PointCloudLocalization: public jsk_topic_tools::DiagnosticNodelet
53  {
54  public:
56  first_time_(true), localize_requested_(false),
57  DiagnosticNodelet("PointCloudLocalization") {}
58  protected:
59  virtual void onInit();
60  virtual void subscribe();
61  virtual void unsubscribe();
62 
67  virtual void cloudCallback(
68  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
69 
74  virtual bool localizationRequest(
75  std_srvs::Empty::Request& req,
76  std_srvs::Empty::Response& res);
77 
82  virtual void cloudTimerCallback(
83  const ros::TimerEvent& event);
84 
89  virtual void tfTimerCallback(
90  const ros::TimerEvent& event);
91 
96  virtual bool isFirstTime();
97 
102  virtual bool updateOffsetCallback(
103  jsk_recognition_msgs::UpdateOffset::Request& req,
104  jsk_recognition_msgs::UpdateOffset::Response& res);
105 
106  virtual void applyDownsampling(
107  pcl::PointCloud<pcl::PointNormal>::Ptr in_cloud,
108  pcl::PointCloud<pcl::PointNormal>& out_cloud);
109 
119  pcl::PointCloud<pcl::PointNormal>::Ptr all_cloud_;
120  sensor_msgs::PointCloud2::ConstPtr latest_cloud_;
122  bool localize_requested_;
123  std::string sensor_frame_;
125  bool initialize_from_tf_;
126  std::string initialize_tf_;
131  std::string global_frame_;
132  std::string odom_frame_;
133 
138  bool use_normal_;
139  double leaf_size_;
141  bool first_time_;
142  private:
143 
144  };
145 }
146 
147 #endif
jsk_pcl_ros::PointCloudLocalization::localize_transform_
tf::Transform localize_transform_
Definition: pointcloud_localization.h:204
jsk_pcl_ros::PointCloudLocalization::isFirstTime
virtual bool isFirstTime()
return true if it is the first time to localize
Definition: pointcloud_localization_nodelet.cpp:303
jsk_pcl_ros::PointCloudLocalization::cloudTimerCallback
virtual void cloudTimerCallback(const ros::TimerEvent &event)
cloud periodic timer callback
Definition: pointcloud_localization_nodelet.cpp:109
ros::Publisher
jsk_pcl_ros::PointCloudLocalization::clip_unseen_pointcloud_
bool clip_unseen_pointcloud_
Definition: pointcloud_localization.h:188
jsk_pcl_ros::PointCloudLocalization::first_time_
bool first_time_
Definition: pointcloud_localization.h:205
jsk_pcl_ros::PointCloudLocalization::updateOffsetCallback
virtual bool updateOffsetCallback(jsk_recognition_msgs::UpdateOffset::Request &req, jsk_recognition_msgs::UpdateOffset::Response &res)
callback function for ~update_offset service
Definition: pointcloud_localization_nodelet.cpp:318
jsk_pcl_ros::PointCloudLocalization::sensor_frame_
std::string sensor_frame_
Definition: pointcloud_localization.h:187
jsk_pcl_ros::PointCloudLocalization::update_offset_srv_
ros::ServiceServer update_offset_srv_
Definition: pointcloud_localization.h:180
jsk_pcl_ros::PointCloudLocalization::PointCloudLocalization
PointCloudLocalization()
Definition: pointcloud_localization.h:119
tf_listener_singleton.h
transform_broadcaster.h
ros::ServiceServer
jsk_pcl_ros::PointCloudLocalization::localize_requested_
bool localize_requested_
Definition: pointcloud_localization.h:186
jsk_pcl_ros::PointCloudLocalization::pub_cloud_
ros::Publisher pub_cloud_
Definition: pointcloud_localization.h:177
jsk_pcl_ros::PointCloudLocalization::mutex_
boost::mutex mutex_
Definition: pointcloud_localization.h:174
tf_eigen.h
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::PointCloudLocalization::initialize_from_tf_
bool initialize_from_tf_
Definition: pointcloud_localization.h:189
tf::TransformBroadcaster
jsk_pcl_ros::PointCloudLocalization::leaf_size_
double leaf_size_
Definition: pointcloud_localization.h:203
jsk_pcl_ros::PointCloudLocalization::localizationRequest
virtual bool localizationRequest(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
callback function of ~localize service.
Definition: pointcloud_localization_nodelet.cpp:308
jsk_pcl_ros::PointCloudLocalization::initialize_tf_
std::string initialize_tf_
Definition: pointcloud_localization.h:190
jsk_pcl_ros::PointCloudLocalization::applyDownsampling
virtual void applyDownsampling(pcl::PointCloud< pcl::PointNormal >::Ptr in_cloud, pcl::PointCloud< pcl::PointNormal > &out_cloud)
Definition: pointcloud_localization_nodelet.cpp:99
jsk_pcl_ros::PointCloudLocalization::tf_listener_
tf::TransformListener * tf_listener_
Definition: pointcloud_localization.h:178
ros::TimerEvent
tf::Transform
jsk_pcl_ros::PointCloudLocalization::tf_timer_
ros::Timer tf_timer_
Definition: pointcloud_localization.h:182
jsk_pcl_ros::PointCloudLocalization::tf_broadcast_
tf::TransformBroadcaster tf_broadcast_
Definition: pointcloud_localization.h:185
jsk_pcl_ros::PointCloudLocalization::cloudCallback
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
callback function of ~input topic.
Definition: pointcloud_localization_nodelet.cpp:147
jsk_pcl_ros::PointCloudLocalization::localization_srv_
ros::ServiceServer localization_srv_
Definition: pointcloud_localization.h:179
jsk_pcl_ros::PointCloudLocalization::tfTimerCallback
virtual void tfTimerCallback(const ros::TimerEvent &event)
tf periodic timer callback
Definition: pointcloud_localization_nodelet.cpp:123
jsk_pcl_ros::PointCloudLocalization::all_cloud_
pcl::PointCloud< pcl::PointNormal >::Ptr all_cloud_
Definition: pointcloud_localization.h:183
tf::TransformListener
jsk_pcl_ros::PointCloudLocalization::sub_
ros::Subscriber sub_
Definition: pointcloud_localization.h:176
jsk_pcl_ros::PointCloudLocalization::onInit
virtual void onInit()
Definition: pointcloud_localization_nodelet.cpp:46
jsk_pcl_ros::PointCloudLocalization::tf_mutex_
boost::mutex tf_mutex_
Definition: pointcloud_localization.h:175
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::PointCloudLocalization::cloud_timer_
ros::Timer cloud_timer_
Definition: pointcloud_localization.h:181
jsk_pcl_ros::PointCloudLocalization::subscribe
virtual void subscribe()
Definition: pointcloud_localization_nodelet.cpp:89
jsk_pcl_ros::PointCloudLocalization::global_frame_
std::string global_frame_
Publishes tf transformation of global_frame_ -> odom_frame_.
Definition: pointcloud_localization.h:195
jsk_pcl_ros::PointCloudLocalization::odom_frame_
std::string odom_frame_
Definition: pointcloud_localization.h:196
jsk_pcl_ros::PointCloudLocalization::unsubscribe
virtual void unsubscribe()
Definition: pointcloud_localization_nodelet.cpp:94
ros::Timer
jsk_pcl_ros::PointCloudLocalization::latest_cloud_
sensor_msgs::PointCloud2::ConstPtr latest_cloud_
Definition: pointcloud_localization.h:184
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
ros::Subscriber
jsk_pcl_ros::PointCloudLocalization::use_normal_
bool use_normal_
Resolution of voxel grid.
Definition: pointcloud_localization.h:202


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45