planar_pointcloud_simulator_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/o2r 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 #define BOOST_PARAMETER_MAX_ARITY 7
38 
39 namespace jsk_pcl_ros_utils
40 {
42  {
43 
44  }
45 
47  {
48 
49  }
50 
52  const sensor_msgs::CameraInfo& info, double distance,
53  pcl::PointCloud<pcl::PointXYZ>& cloud)
54  {
56  model.fromCameraInfo(info);
57  cloud.points.resize(info.width * info.height);
58  cloud.is_dense = true;
59  for (size_t j = 0; j < info.height; j++) {
60  for (size_t i = 0; i < info.width; i++) {
61  cv::Point3d ray = model.projectPixelTo3dRay(cv::Point2d(i, j));
62  pcl::PointXYZ p;
63  p.x = ray.x * distance;
64  p.y = ray.y * distance;
65  p.z = ray.z * distance;
66  cloud.points[j * info.width + i] = p;
67  }
68  }
69  cloud.width = info.width;
70  cloud.height = info.height;
71  }
72 
74  {
75  DiagnosticNodelet::onInit();
76  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
77  typename dynamic_reconfigure::Server<Config>::CallbackType f =
78  boost::bind (&PlanarPointCloudSimulatorNodelet::configCallback, this, _1, _2);
79  srv_->setCallback (f);
80 
81  pub_ = advertise<sensor_msgs::PointCloud2>(
82  *pnh_, "output", 1);
83 
84  onInitPostProcess();
85  }
86 
88  {
89  sub_ = pnh_->subscribe(
91  }
92 
94  {
95  sub_.shutdown();
96  }
97 
99  Config &config, uint32_t level)
100  {
101  boost::mutex::scoped_lock lock(mutex_);
102  distance_ = config.distance;
103  }
104 
106  const sensor_msgs::CameraInfo::ConstPtr& info_msg)
107  {
108  boost::mutex::scoped_lock lock(mutex_);
109  vital_checker_->poke();
110  pcl::PointCloud<pcl::PointXYZ>::Ptr
111  cloud(new pcl::PointCloud<pcl::PointXYZ>);
112  impl_.generate(*info_msg, distance_, *cloud);
113  sensor_msgs::PointCloud2 ros_cloud;
114  pcl::toROSMsg(*cloud, ros_cloud);
115  ros_cloud.header = info_msg->header;
116  pub_.publish(ros_cloud);
117  }
118 
119 }
120 
f
lock
Nodelet implementation of jsk_pcl/PlanarPointCloudSimulator.
cv::Point3d projectPixelTo3dRay(const cv::Point2d &uv_rect) const
virtual void generate(const sensor_msgs::CameraInfo &info, double distance, pcl::PointCloud< pcl::PointXYZ > &cloud)
Generate a pointcloud according to width, height and distance.
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PlanarPointCloudSimulatorNodelet, nodelet::Nodelet)
virtual void generate(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
Callback function for ~input.
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
struct svm_model * model
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
p
boost::mutex mutex_


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15