spherical_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/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 #define BOOST_PARAMETER_MAX_ARITY 7
37 
38 namespace jsk_pcl_ros_utils
39 {
41  {
42  DiagnosticNodelet::onInit();
43  pnh_->getParam("frame_id", frame_id_);
44  rotate_velocity_ = 0.5;
45  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
46  typename dynamic_reconfigure::Server<Config>::CallbackType f =
47  boost::bind (&SphericalPointCloudSimulator::configCallback, this, _1, _2);
48  srv_->setCallback (f);
49 
50  double rate;
51  if (pnh_->getParam("rate", rate)) {
52  timer_ = pnh_->createTimer(
53  ros::Duration(1 / rate), boost::bind(
55  this,
56  _1));
57  }
58  pub_ = advertise<sensor_msgs::PointCloud2>(
59  *pnh_, "output", 1);
60  onInitPostProcess();
61  }
62 
64  {
65  sub_ = pnh_->subscribe(
66  "input", 1, &SphericalPointCloudSimulator::generate, this);
67  }
68 
70  {
71  sub_.shutdown();
72  }
73 
75  Config &config, uint32_t level)
76  {
77  boost::mutex::scoped_lock lock(mutex_);
78  r_ = config.r;
79  min_phi_ = config.min_phi;
80  max_phi_ = config.max_phi;
81  scan_range_ = config.scan_range;
82  scan_num_ = config.scan_num;
83  fps_ = config.fps;
84  }
85 
87  const ros::TimerEvent& event)
88  {
89  // make up pointcloud and call generate
90  sensor_msgs::PointCloud2 dummy_cloud;
91  dummy_cloud.header.stamp = ros::Time::now();
92  dummy_cloud.header.frame_id = "map"; // default is map
93  generate(boost::make_shared<sensor_msgs::PointCloud2>(dummy_cloud));
94  }
95 
97  const sensor_msgs::PointCloud2::ConstPtr& msg)
98  {
99  boost::mutex::scoped_lock lock(mutex_);
100  vital_checker_->poke();
101  pcl::PointCloud<pcl::PointXYZ>::Ptr
102  cloud (new pcl::PointCloud<pcl::PointXYZ>);
103  // 40fps
104  int phi_num = 2 * M_PI / rotate_velocity_ * fps_;
105  int point_num = phi_num * scan_num_;
106  cloud->points.resize(point_num);
107  int i = 0;
108  for (int phi_i = 0; phi_i < phi_num; phi_i++) {
109  double phi = (float)phi_i / phi_num * (max_phi_ - min_phi_) + min_phi_;
110  Eigen::Affine3f trans = getPlane(phi);
111  for (int theta_i = 0; theta_i < scan_num_; theta_i++) {
112  double theta = theta_i * scan_range_ / scan_num_ - scan_range_ / 2.0;
113  pcl::PointXYZ p = getPoint(r_, theta, trans);
114  cloud->points[i] = p;
115  i++;
116  }
117  }
118  sensor_msgs::PointCloud2 ros_cloud;
119  pcl::toROSMsg(*cloud, ros_cloud);
120  ros_cloud.header.stamp = msg->header.stamp;
121  if (!frame_id_.empty()) {
122  ros_cloud.header.frame_id = frame_id_;
123  }
124  else {
125  ros_cloud.header.frame_id = cloud->header.frame_id;
126  }
127  pub_.publish(ros_cloud);
128  }
129 
130  Eigen::Affine3f SphericalPointCloudSimulator::getPlane(double phi)
131  {
132  Eigen::Vector3f norm(0, sin(phi), cos(phi));
133  Eigen::Quaternionf rot;
134  rot.setFromTwoVectors(Eigen::Vector3f::UnitZ(), norm);
135  Eigen::Affine3f trans = Eigen::Affine3f::Identity();
136  trans = trans * rot;
137  return trans;
138  }
139 
141  double r, double theta, const Eigen::Affine3f& trans)
142  {
143  Eigen::Vector3f local_p(r * cos(theta), r * sin(theta), 0);
144  Eigen::Vector3f world_p = trans * local_p;
145  pcl::PointXYZ p;
146  p.getVector3fMap() = world_p;
147  return p;
148  }
149 
150 }
151 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
rot
rot
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::SphericalPointCloudSimulator, nodelet::Nodelet)
msg
msg
_2
boost::arg< 2 > _2
jsk_pcl_ros_utils::SphericalPointCloudSimulator::subscribe
virtual void subscribe()
Subscribe another pointcloud to synchronize timestamp.
Definition: spherical_pointcloud_simulator_nodelet.cpp:63
jsk_pcl_ros_utils::SphericalPointCloudSimulator::unsubscribe
virtual void unsubscribe()
Shutdown subscribers.
Definition: spherical_pointcloud_simulator_nodelet.cpp:69
i
int i
jsk_pcl_ros_utils::SphericalPointCloudSimulator::mutex_
boost::mutex mutex_
Definition: spherical_pointcloud_simulator.h:172
p
p
lock
lock
jsk_pcl_ros_utils::SphericalPointCloudSimulator::min_phi_
double min_phi_
Definition: spherical_pointcloud_simulator.h:187
jsk_pcl_ros_utils::SphericalPointCloudSimulator::onInit
virtual void onInit()
Initialization function.
Definition: spherical_pointcloud_simulator_nodelet.cpp:40
jsk_pcl_ros_utils::SphericalPointCloudSimulator::configCallback
virtual void configCallback(Config &config, uint32_t level)
dynamic_reconfigure callback
Definition: spherical_pointcloud_simulator_nodelet.cpp:74
theta
int theta
jsk_pcl_ros_utils::SphericalPointCloudSimulator::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: spherical_pointcloud_simulator.h:175
jsk_pcl_ros_utils::SphericalPointCloudSimulator::rotate_velocity_
double rotate_velocity_
Definition: spherical_pointcloud_simulator.h:182
ros::Subscriber::shutdown
void shutdown()
jsk_pcl_ros_utils::SphericalPointCloudSimulator::scan_range_
double scan_range_
Definition: spherical_pointcloud_simulator.h:189
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
spherical_pointcloud_simulator.h
sample_camera_info_and_pointcloud_publisher.cloud
cloud
Definition: sample_camera_info_and_pointcloud_publisher.py:30
jsk_pcl_ros_utils::SphericalPointCloudSimulator::sub_
ros::Subscriber sub_
Definition: spherical_pointcloud_simulator.h:173
class_list_macros.h
jsk_pcl_ros_utils::SphericalPointCloudSimulator::timer_
ros::Timer timer_
Definition: spherical_pointcloud_simulator.h:184
jsk_pcl_ros_utils::SphericalPointCloudSimulator::getPoint
virtual pcl::PointXYZ getPoint(double r, double theta, const Eigen::Affine3f &trans)
compute a point according to a parametric model of spherical tilting laser.
Definition: spherical_pointcloud_simulator_nodelet.cpp:140
jsk_pcl_ros_utils::SphericalPointCloudSimulator::generate
virtual void generate(const sensor_msgs::PointCloud2::ConstPtr &msg)
Callback function for ~input topic.
Definition: spherical_pointcloud_simulator_nodelet.cpp:96
_1
boost::arg< 1 > _1
sample_camera_info_and_pointcloud_publisher.rate
rate
Definition: sample_camera_info_and_pointcloud_publisher.py:10
jsk_pcl_ros_utils::SphericalPointCloudSimulator::Config
SphericalPointCloudSimulatorConfig Config
Definition: spherical_pointcloud_simulator.h:118
jsk_pcl_ros_utils::SphericalPointCloudSimulator::r_
double r_
Definition: spherical_pointcloud_simulator.h:186
ros::TimerEvent
r
S r
jsk_pcl_ros_utils::SphericalPointCloudSimulator::getPlane
virtual Eigen::Affine3f getPlane(double phi)
Transformation for scan plane specified by phi angle.
Definition: spherical_pointcloud_simulator_nodelet.cpp:130
f
f
nodelet::Nodelet
M_PI
#define M_PI
jsk_pcl_ros_utils::SphericalPointCloudSimulator::pub_
ros::Publisher pub_
Definition: spherical_pointcloud_simulator.h:174
jsk_pcl_ros_utils::SphericalPointCloudSimulator::fps_
double fps_
Definition: spherical_pointcloud_simulator.h:190
jsk_pcl_ros_utils::SphericalPointCloudSimulator
This is a class for jsk_pcl/SphericalPointCloudSimulator nodelet.
Definition: spherical_pointcloud_simulator.h:83
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros_utils::SphericalPointCloudSimulator::frame_id_
std::string frame_id_
frame_id of output pointcloud. If it is empty string, frame_id of ~input is copied.
Definition: spherical_pointcloud_simulator.h:181
jsk_pcl_ros_utils::SphericalPointCloudSimulator::timerCallback
virtual void timerCallback(const ros::TimerEvent &event)
Timer callback for fixed rate publishing.
Definition: spherical_pointcloud_simulator_nodelet.cpp:86
jsk_pcl_ros_utils::SphericalPointCloudSimulator::max_phi_
double max_phi_
Definition: spherical_pointcloud_simulator.h:188
config
config
ros::Duration
jsk_pcl_ros_utils::SphericalPointCloudSimulator::scan_num_
int scan_num_
Definition: spherical_pointcloud_simulator.h:191
ros::Time::now
static Time now()


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