pcd_reader_with_pose_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++; indent-tabs-mode: nil; -*-
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 
39 #include <pcl/common/transforms.h>
41 #include <pcl/io/pcd_io.h>
42 #include <pcl/io/io.h>
43 
44 namespace jsk_pcl_ros_utils
45 {
47  {
48  pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
49  DiagnosticNodelet::onInit();
50  std::string file_name;
51  pnh_->param("pcd_file", file_name, std::string(""));
52  if (file_name == std::string("") || pcl::io::loadPCDFile (file_name, template_cloud_) == -1){
53  NODELET_FATAL("cannot read pcd file %s", file_name.c_str());
54  return;
55  }
56  pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
57 
58  onInitPostProcess();
59  }
61  {
62  sub_teacher_ = pnh_->subscribe("input", 1,
64  this);
65  }
67  {
68  }
70  const geometry_msgs::PoseStamped::ConstPtr& pose_stamped)
71  {
72  vital_checker_->poke();
74  Eigen::Affine3f pose_eigen;
75  tf::poseMsgToEigen(pose_stamped->pose, pose_eigen);
76  sensor_msgs::PointCloud2 ros_out;
77  Eigen::Matrix4f transform = pose_eigen.matrix();
79  ros_out.header = pose_stamped->header;
80  pub_cloud_.publish(ros_out);
81  }
82 }
83 
tf::poseMsgToEigen
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
NODELET_FATAL
#define NODELET_FATAL(...)
jsk_pcl_ros_utils::PCDReaderWithPose::poseCallback
virtual void poseCallback(const geometry_msgs::PoseStamped::ConstPtr &msg)
Definition: pcd_reader_with_pose_nodelet.cpp:101
jsk_pcl_ros_utils::PCDReaderWithPose::pub_cloud_
ros::Publisher pub_cloud_
Definition: pcd_reader_with_pose.h:123
now
now
jsk_pcl_ros_utils::PCDReaderWithPose::onInit
virtual void onInit()
Definition: pcd_reader_with_pose_nodelet.cpp:78
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
pcd_reader_with_pose.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros_utils::PCDReaderWithPose
Definition: pcd_reader_with_pose.h:80
class_list_macros.h
eigen_msg.h
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PCDReaderWithPose, nodelet::Nodelet)
pcl::io::loadPCDFile
int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
pcl_conversion_util.h
jsk_pcl_ros_utils::PCDReaderWithPose::unsubscribe
virtual void unsubscribe()
Definition: pcd_reader_with_pose_nodelet.cpp:98
pcl_ros::transformPointCloud
void transformPointCloud(const Eigen::Matrix4f &transform, const sensor_msgs::PointCloud2 &in, sensor_msgs::PointCloud2 &out)
jsk_pcl_ros_utils::PCDReaderWithPose::sub_teacher_
ros::Subscriber sub_teacher_
Definition: pcd_reader_with_pose.h:124
nodelet::Nodelet
ros::Time
jsk_pcl_ros_utils::PCDReaderWithPose::subscribe
virtual void subscribe()
Definition: pcd_reader_with_pose_nodelet.cpp:92
jsk_pcl_ros_utils::PCDReaderWithPose::template_cloud_
sensor_msgs::PointCloud2 template_cloud_
Definition: pcd_reader_with_pose.h:126
ros::Time::now
static Time now()


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43