Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros_utils::SphericalPointCloudSimulator Class Reference

This is a class for jsk_pcl/SphericalPointCloudSimulator nodelet. More...

#include <spherical_pointcloud_simulator.h>

Inheritance diagram for jsk_pcl_ros_utils::SphericalPointCloudSimulator:
Inheritance graph
[legend]

Public Types

typedef SphericalPointCloudSimulatorConfig Config
 

Public Member Functions

 SphericalPointCloudSimulator ()
 

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
 dynamic_reconfigure callback More...
 
virtual void generate (const sensor_msgs::PointCloud2::ConstPtr &msg)
 Callback function for ~input topic. More...
 
virtual Eigen::Affine3f getPlane (double phi)
 Transformation for scan plane specified by phi angle. More...
 
virtual pcl::PointXYZ getPoint (double r, double theta, const Eigen::Affine3f &trans)
 compute a point according to a parametric model of spherical tilting laser. More...
 
virtual void onInit ()
 Initialization function. More...
 
virtual void subscribe ()
 Subscribe another pointcloud to synchronize timestamp. More...
 
virtual void timerCallback (const ros::TimerEvent &event)
 Timer callback for fixed rate publishing. More...
 
virtual void unsubscribe ()
 Shutdown subscribers. More...
 

Protected Attributes

double fps_
 
std::string frame_id_
 frame_id of output pointcloud. If it is empty string, frame_id of ~input is copied. More...
 
double max_phi_
 
double min_phi_
 
boost::mutex mutex_
 
ros::Publisher pub_
 
double r_
 
double rotate_velocity_
 
int scan_num_
 
double scan_range_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
ros::Subscriber sub_
 
ros::Timer timer_
 

Detailed Description

This is a class for jsk_pcl/SphericalPointCloudSimulator nodelet.

Definition at line 83 of file spherical_pointcloud_simulator.h.

Member Typedef Documentation

◆ Config

typedef SphericalPointCloudSimulatorConfig jsk_pcl_ros_utils::SphericalPointCloudSimulator::Config

Definition at line 118 of file spherical_pointcloud_simulator.h.

Constructor & Destructor Documentation

◆ SphericalPointCloudSimulator()

jsk_pcl_ros_utils::SphericalPointCloudSimulator::SphericalPointCloudSimulator ( )
inline

Definition at line 119 of file spherical_pointcloud_simulator.h.

Member Function Documentation

◆ configCallback()

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

dynamic_reconfigure callback

Definition at line 74 of file spherical_pointcloud_simulator_nodelet.cpp.

◆ generate()

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::generate ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual

Callback function for ~input topic.

Pointcloud message is used only for timestamp and frame_id.

Definition at line 96 of file spherical_pointcloud_simulator_nodelet.cpp.

◆ getPlane()

Eigen::Affine3f jsk_pcl_ros_utils::SphericalPointCloudSimulator::getPlane ( double  phi)
protectedvirtual

Transformation for scan plane specified by phi angle.

Definition at line 130 of file spherical_pointcloud_simulator_nodelet.cpp.

◆ getPoint()

pcl::PointXYZ jsk_pcl_ros_utils::SphericalPointCloudSimulator::getPoint ( double  r,
double  theta,
const Eigen::Affine3f &  trans 
)
protectedvirtual

compute a point according to a parametric model of spherical tilting laser.

The normal of scan plane is defined as [0, sin(phi), cos(phi)]. Each point of scan is represented as follows respected to the plane: p = [r*cos(theta), r*sin(theta), 0]

Definition at line 140 of file spherical_pointcloud_simulator_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::onInit ( )
protectedvirtual

Initialization function.

Definition at line 40 of file spherical_pointcloud_simulator_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::subscribe ( )
protectedvirtual

Subscribe another pointcloud to synchronize timestamp.

Definition at line 63 of file spherical_pointcloud_simulator_nodelet.cpp.

◆ timerCallback()

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::timerCallback ( const ros::TimerEvent event)
protectedvirtual

Timer callback for fixed rate publishing.

Definition at line 86 of file spherical_pointcloud_simulator_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::unsubscribe ( )
protectedvirtual

Shutdown subscribers.

Definition at line 69 of file spherical_pointcloud_simulator_nodelet.cpp.

Member Data Documentation

◆ fps_

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::fps_
protected

Definition at line 190 of file spherical_pointcloud_simulator.h.

◆ frame_id_

std::string jsk_pcl_ros_utils::SphericalPointCloudSimulator::frame_id_
protected

frame_id of output pointcloud. If it is empty string, frame_id of ~input is copied.

Definition at line 181 of file spherical_pointcloud_simulator.h.

◆ max_phi_

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::max_phi_
protected

Definition at line 188 of file spherical_pointcloud_simulator.h.

◆ min_phi_

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::min_phi_
protected

Definition at line 187 of file spherical_pointcloud_simulator.h.

◆ mutex_

boost::mutex jsk_pcl_ros_utils::SphericalPointCloudSimulator::mutex_
protected

Definition at line 172 of file spherical_pointcloud_simulator.h.

◆ pub_

ros::Publisher jsk_pcl_ros_utils::SphericalPointCloudSimulator::pub_
protected

Definition at line 174 of file spherical_pointcloud_simulator.h.

◆ r_

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::r_
protected

Definition at line 186 of file spherical_pointcloud_simulator.h.

◆ rotate_velocity_

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::rotate_velocity_
protected

Definition at line 182 of file spherical_pointcloud_simulator.h.

◆ scan_num_

int jsk_pcl_ros_utils::SphericalPointCloudSimulator::scan_num_
protected

Definition at line 191 of file spherical_pointcloud_simulator.h.

◆ scan_range_

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::scan_range_
protected

Definition at line 189 of file spherical_pointcloud_simulator.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros_utils::SphericalPointCloudSimulator::srv_
protected

Definition at line 175 of file spherical_pointcloud_simulator.h.

◆ sub_

ros::Subscriber jsk_pcl_ros_utils::SphericalPointCloudSimulator::sub_
protected

Definition at line 173 of file spherical_pointcloud_simulator.h.

◆ timer_

ros::Timer jsk_pcl_ros_utils::SphericalPointCloudSimulator::timer_
protected

Definition at line 184 of file spherical_pointcloud_simulator.h.


The documentation for this class was generated from the following files:


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