pointcloud_localization_nodelet.cpp
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 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <jsk_recognition_msgs/ICPAlign.h>
40 #include <pcl_ros/transforms.h>
41 #include <pcl/filters/voxel_grid.h>
42 #include <pcl/filters/passthrough.h>
43 
44 namespace jsk_pcl_ros
45 {
47  {
48  pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
49  DiagnosticNodelet::onInit();
51  // initialize localize_transform_ as identity
53  pnh_->param("global_frame", global_frame_, std::string("map"));
54  pnh_->param("odom_frame", odom_frame_, std::string("odom"));
55  pnh_->param("leaf_size", leaf_size_, 0.01);
56  pnh_->param("initialize_from_tf", initialize_from_tf_, false);
57  if (initialize_from_tf_) {
58  pnh_->param("initialize_tf", initialize_tf_, std::string("odom_on_ground"));
59  }
60  pnh_->param("clip_unseen_pointcloud", clip_unseen_pointcloud_, false);
62  pnh_->param("sensor_frame", sensor_frame_, std::string("BODY"));
63  }
64  pnh_->param("use_normal", use_normal_, false);
65  double cloud_rate;
66  pnh_->param("cloud_rate", cloud_rate, 10.0);
67  double tf_rate;
68  pnh_->param("tf_rate", tf_rate, 20.0);
69  pub_cloud_ = pnh_->advertise<sensor_msgs::PointCloud2>("output", 1);
70  // always subscribe pointcloud...?
71  sub_ = pnh_->subscribe("input", 1, &PointCloudLocalization::cloudCallback, this);
72  localization_srv_ = pnh_->advertiseService(
74  update_offset_srv_ = pnh_->advertiseService(
75  "update_offset", &PointCloudLocalization::updateOffsetCallback, this);
76 
77  // timer to publish cloud
78  cloud_timer_ = pnh_->createTimer(
79  ros::Duration(1.0 / cloud_rate),
80  boost::bind(&PointCloudLocalization::cloudTimerCallback, this, _1));
81  // timer to publish tf
82  tf_timer_ = pnh_->createTimer(
83  ros::Duration(1.0 / tf_rate),
84  boost::bind(&PointCloudLocalization::tfTimerCallback, this, _1));
85 
86  onInitPostProcess();
87  }
88 
90  {
91  // dummy
92  }
93 
95  {
96  // dummy
97  }
98 
100  pcl::PointCloud<pcl::PointNormal>::Ptr in_cloud,
101  pcl::PointCloud<pcl::PointNormal>& out_cloud)
102  {
103  pcl::VoxelGrid<pcl::PointNormal> vg;
104  vg.setInputCloud(in_cloud);
105  vg.setLeafSize(leaf_size_, leaf_size_, leaf_size_);
106  vg.filter(out_cloud);
107  }
108 
110  const ros::TimerEvent& event)
111  {
112  boost::mutex::scoped_lock lock(mutex_);
113  ros::Time stamp = event.current_real;
114  if (all_cloud_) {
115  sensor_msgs::PointCloud2 ros_cloud;
116  pcl::toROSMsg(*all_cloud_, ros_cloud);
117  ros_cloud.header.stamp = stamp;
118  ros_cloud.header.frame_id = global_frame_;
119  pub_cloud_.publish(ros_cloud);
120  }
121  }
122 
124  const ros::TimerEvent& event)
125  {
126  boost::mutex::scoped_lock lock(tf_mutex_);
127  try {
128  ros::Time stamp = event.current_real;
130  // Update localize_transform_ to points initialize_tf
132  tf_listener_,
135 
136  }
138  stamp,
140  odom_frame_));
141  }
142  catch (tf2::TransformException& e) {
143  NODELET_FATAL("Failed to lookup transformation: %s", e.what());
144  }
145  }
146 
148  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
149  {
150  vital_checker_->poke();
151  boost::mutex::scoped_lock lock(mutex_);
152  //NODELET_INFO("cloudCallback");
153  latest_cloud_ = cloud_msg;
154  if (localize_requested_){
155  NODELET_INFO("localization is requested");
156  try {
157  pcl::PointCloud<pcl::PointNormal>::Ptr
158  local_cloud (new pcl::PointCloud<pcl::PointNormal>);
159  pcl::fromROSMsg(*latest_cloud_, *local_cloud);
160  NODELET_INFO("waiting for tf transformation from %s tp %s",
161  latest_cloud_->header.frame_id.c_str(),
162  global_frame_.c_str());
164  latest_cloud_->header.frame_id,
166  latest_cloud_->header.stamp,
167  ros::Duration(1.0))) {
168  pcl::PointCloud<pcl::PointNormal>::Ptr
169  input_cloud (new pcl::PointCloud<pcl::PointNormal>);
170  if (use_normal_) {
172  *local_cloud,
173  *input_cloud,
174  *tf_listener_);
175  }
176  else {
178  *local_cloud,
179  *input_cloud,
180  *tf_listener_);
181  }
182  pcl::PointCloud<pcl::PointNormal>::Ptr
183  input_downsampled_cloud (new pcl::PointCloud<pcl::PointNormal>);
184  applyDownsampling(input_cloud, *input_downsampled_cloud);
185  if (isFirstTime()) {
186  all_cloud_ = input_downsampled_cloud;
187  first_time_ = false;
188  }
189  else {
190  // run ICP
191  ros::ServiceClient client
192  = pnh_->serviceClient<jsk_recognition_msgs::ICPAlign>("icp_align");
193  jsk_recognition_msgs::ICPAlign icp_srv;
194 
196  // Before running ICP, remove pointcloud where we cannot see
197  // First, transform reference pointcloud, that is all_cloud_, into
198  // sensor frame.
199  // And after that, remove points which are x < 0.
200  tf::StampedTransform global_sensor_tf_transform
202  tf_listener_,
205  cloud_msg->header.stamp,
206  ros::Duration(1.0));
207  Eigen::Affine3f global_sensor_transform;
208  tf::transformTFToEigen(global_sensor_tf_transform,
209  global_sensor_transform);
210  pcl::PointCloud<pcl::PointNormal>::Ptr sensor_cloud
211  (new pcl::PointCloud<pcl::PointNormal>);
212  pcl::transformPointCloudWithNormals(
213  *all_cloud_,
214  *sensor_cloud,
215  global_sensor_transform.inverse());
216  // Remove negative-x points
217  pcl::PassThrough<pcl::PointNormal> pass;
218  pass.setInputCloud(sensor_cloud);
219  pass.setFilterFieldName("x");
220  pass.setFilterLimits(0.0, 100.0);
221  pcl::PointCloud<pcl::PointNormal>::Ptr filtered_cloud
222  (new pcl::PointCloud<pcl::PointNormal>);
223  pass.filter(*filtered_cloud);
224  NODELET_INFO("clipping: %lu -> %lu", sensor_cloud->points.size(), filtered_cloud->points.size());
225  // Convert the pointcloud to global frame again
226  pcl::PointCloud<pcl::PointNormal>::Ptr global_filtered_cloud
227  (new pcl::PointCloud<pcl::PointNormal>);
228  pcl::transformPointCloudWithNormals(
229  *filtered_cloud,
230  *global_filtered_cloud,
231  global_sensor_transform);
232  pcl::toROSMsg(*global_filtered_cloud,
233  icp_srv.request.target_cloud);
234  }
235  else {
237  icp_srv.request.target_cloud);
238  }
239  pcl::toROSMsg(*input_downsampled_cloud,
240  icp_srv.request.reference_cloud);
241 
242  if (client.call(icp_srv)) {
243  Eigen::Affine3f transform;
244  tf::poseMsgToEigen(icp_srv.response.result.pose, transform);
245  Eigen::Vector3f transform_pos(transform.translation());
246  float roll, pitch, yaw;
247  pcl::getEulerAngles(transform, roll, pitch, yaw);
248  NODELET_INFO("aligned parameter --");
249  NODELET_INFO(" - pos: [%f, %f, %f]",
250  transform_pos[0],
251  transform_pos[1],
252  transform_pos[2]);
253  NODELET_INFO(" - rot: [%f, %f, %f]", roll, pitch, yaw);
254  pcl::PointCloud<pcl::PointNormal>::Ptr
255  transformed_input_cloud (new pcl::PointCloud<pcl::PointNormal>);
256  if (use_normal_) {
257  pcl::transformPointCloudWithNormals(*input_cloud,
258  *transformed_input_cloud,
259  transform);
260  }
261  else {
262  pcl::transformPointCloud(*input_cloud,
263  *transformed_input_cloud,
264  transform);
265  }
266  pcl::PointCloud<pcl::PointNormal>::Ptr
267  concatenated_cloud (new pcl::PointCloud<pcl::PointNormal>);
268  *concatenated_cloud = *all_cloud_ + *transformed_input_cloud;
269  // update *all_cloud
270  applyDownsampling(concatenated_cloud, *all_cloud_);
271  // update localize_transform_
272  tf::Transform icp_transform;
273  tf::transformEigenToTF(transform, icp_transform);
274  {
275  boost::mutex::scoped_lock tf_lock(tf_mutex_);
276  localize_transform_ = localize_transform_ * icp_transform;
277  }
278  }
279  else {
280  NODELET_ERROR("Failed to call ~icp_align");
281  return;
282  }
283  }
284  localize_requested_ = false;
285  }
286  else {
287  NODELET_WARN("No tf transformation is available");
288  }
289  }
290  catch (tf2::ConnectivityException &e)
291  {
292  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
293  return;
294  }
296  {
297  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
298  return;
299  }
300  }
301  }
302 
304  {
305  return first_time_;
306  }
307 
309  std_srvs::Empty::Request& req,
310  std_srvs::Empty::Response& res)
311  {
312  NODELET_INFO("localize!");
313  boost::mutex::scoped_lock lock(mutex_);
314  localize_requested_ = true;
315  return true;
316  }
317 
319  jsk_recognition_msgs::UpdateOffset::Request& req,
320  jsk_recognition_msgs::UpdateOffset::Response& res)
321  {
322  boost::mutex::scoped_lock lock(mutex_);
323  geometry_msgs::TransformStamped next_pose = req.transformation;
324  // convert geometry_msgs::TransformStamped into tf::Transform
325  tf::StampedTransform tf_transform;
326  tf::transformStampedMsgToTF(next_pose, tf_transform);
327  // TODO: resolve tf
328  localize_transform_ = tf_transform;
329  return true;
330  }
331 }
332 
tf::poseMsgToEigen
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
jsk_pcl_ros::PointCloudLocalization::localize_transform_
tf::Transform localize_transform_
Definition: pointcloud_localization.h:204
NODELET_FATAL
#define NODELET_FATAL(...)
jsk_pcl_ros::PointCloudLocalization::isFirstTime
virtual bool isFirstTime()
return true if it is the first time to localize
Definition: pointcloud_localization_nodelet.cpp:303
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_pcl_ros::PointCloudLocalization::cloudTimerCallback
virtual void cloudTimerCallback(const ros::TimerEvent &event)
cloud periodic timer callback
Definition: pointcloud_localization_nodelet.cpp:109
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
tf::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
tf::transformEigenToTF
void transformEigenToTF(Eigen::Affine3f &eigen, tf::Transform &t)
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
attention_pose_set.stamp
stamp
Definition: attention_pose_set.py:15
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
NODELET_WARN
#define NODELET_WARN(...)
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
tf::StampedTransform
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
transforms.h
jsk_pcl_ros::PointCloudLocalization
Definition: pointcloud_localization.h:84
class_list_macros.h
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
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
pointcloud_localization.h
tf::transformTFToEigen
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
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::ServiceClient
_1
boost::arg< 1 > _1
tf::transformStampedMsgToTF
static void transformStampedMsgToTF(const geometry_msgs::TransformStamped &msg, StampedTransform &bt)
tf::Transformer::waitForTransform
bool waitForTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
ros::TimerEvent
tf::Transform
jsk_pcl_ros::PointCloudLocalization::tf_timer_
ros::Timer tf_timer_
Definition: pointcloud_localization.h:182
pcl_conversion_util.h
tf2::ConnectivityException
NODELET_INFO
#define NODELET_INFO(...)
pcl_ros::transformPointCloud
void transformPointCloud(const Eigen::Matrix4f &transform, const sensor_msgs::PointCloud2 &in, sensor_msgs::PointCloud2 &out)
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
nodelet::Nodelet
ros::Time
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
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
jsk_pcl_ros::PointCloudLocalization::all_cloud_
pcl::PointCloud< pcl::PointNormal >::Ptr all_cloud_
Definition: pointcloud_localization.h:183
tf::Transform::setIdentity
void setIdentity()
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
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros::PointCloudLocalization::tf_mutex_
boost::mutex tf_mutex_
Definition: pointcloud_localization.h:175
pcl_ros::transformPointCloudWithNormals
void transformPointCloudWithNormals(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const geometry_msgs::Transform &transform)
jsk_recognition_utils::TfListenerSingleton::getInstance
static tf::TransformListener * getInstance()
jsk_pcl_ros::PointCloudLocalization::cloud_timer_
ros::Timer cloud_timer_
Definition: pointcloud_localization.h:181
lookupTransformWithDuration
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
tf2::InvalidArgumentException
tf2::TransformException
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
ros::Duration
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
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
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::PointCloudLocalization, nodelet::Nodelet)
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
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