spherical_pointcloud_simulator.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_UTILS_SPHERICAL_POINTCLOUD_SIMULATOR_H_
38 #define JSK_PCL_ROS_UTILS_SPHERICAL_POINTCLOUD_SIMULATOR_H_
39 
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
41 #include <jsk_pcl_ros_utils/SphericalPointCloudSimulatorConfig.h>
43 #include <dynamic_reconfigure/server.h>
44 
45 namespace jsk_pcl_ros_utils
46 {
51  class SphericalPointCloudSimulator: public jsk_topic_tools::DiagnosticNodelet
52  {
53  public:
54  typedef SphericalPointCloudSimulatorConfig Config;
56  DiagnosticNodelet("SphericalPointCloudSimulator") {}
57  protected:
61  virtual void onInit();
62 
66  virtual void subscribe();
67 
71  virtual void unsubscribe();
72 
76  virtual void configCallback(Config &config, uint32_t level);
77 
83  virtual void generate(
84  const sensor_msgs::PointCloud2::ConstPtr& msg);
85 
89  virtual void timerCallback(
90  const ros::TimerEvent& event);
91 
100  virtual pcl::PointXYZ getPoint(
101  double r, double theta, const Eigen::Affine3f& trans);
102 
106  virtual Eigen::Affine3f getPlane(double phi);
107 
108  boost::mutex mutex_;
112 
117  std::string frame_id_;
119 
121  // model parameters
122  double r_;
123  double min_phi_;
124  double max_phi_;
125  double scan_range_;
126  double fps_;
127  int scan_num_;
128 
129  private:
130 
131  };
132 }
133 
134 #endif
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
ros::Publisher
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
boost::shared_ptr
jsk_pcl_ros_utils::SphericalPointCloudSimulator::mutex_
boost::mutex mutex_
Definition: spherical_pointcloud_simulator.h:172
jsk_pcl_ros_utils::SphericalPointCloudSimulator::SphericalPointCloudSimulator
SphericalPointCloudSimulator()
Definition: spherical_pointcloud_simulator.h:119
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
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
jsk_pcl_ros_utils::SphericalPointCloudSimulator::scan_range_
double scan_range_
Definition: spherical_pointcloud_simulator.h:189
jsk_pcl_ros_utils::SphericalPointCloudSimulator::sub_
ros::Subscriber sub_
Definition: spherical_pointcloud_simulator.h:173
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
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
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
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::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
ros::Timer
jsk_pcl_ros_utils::SphericalPointCloudSimulator::scan_num_
int scan_num_
Definition: spherical_pointcloud_simulator.h:191
ros::Subscriber
pcl_conversions.h


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