This is a class for jsk_pcl/SphericalPointCloudSimulator nodelet.
More...
#include <spherical_pointcloud_simulator.h>
|
typedef SphericalPointCloudSimulatorConfig | Config |
|
This is a class for jsk_pcl/SphericalPointCloudSimulator nodelet.
Definition at line 83 of file spherical_pointcloud_simulator.h.
◆ Config
◆ SphericalPointCloudSimulator()
jsk_pcl_ros_utils::SphericalPointCloudSimulator::SphericalPointCloudSimulator |
( |
| ) |
|
|
inline |
◆ configCallback()
void jsk_pcl_ros_utils::SphericalPointCloudSimulator::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ generate()
void jsk_pcl_ros_utils::SphericalPointCloudSimulator::generate |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
◆ getPlane()
Eigen::Affine3f jsk_pcl_ros_utils::SphericalPointCloudSimulator::getPlane |
( |
double |
phi | ) |
|
|
protectedvirtual |
◆ 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 |
◆ subscribe()
void jsk_pcl_ros_utils::SphericalPointCloudSimulator::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ timerCallback()
void jsk_pcl_ros_utils::SphericalPointCloudSimulator::timerCallback |
( |
const ros::TimerEvent & |
event | ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros_utils::SphericalPointCloudSimulator::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ fps_
double jsk_pcl_ros_utils::SphericalPointCloudSimulator::fps_ |
|
protected |
◆ frame_id_
std::string jsk_pcl_ros_utils::SphericalPointCloudSimulator::frame_id_ |
|
protected |
◆ max_phi_
double jsk_pcl_ros_utils::SphericalPointCloudSimulator::max_phi_ |
|
protected |
◆ min_phi_
double jsk_pcl_ros_utils::SphericalPointCloudSimulator::min_phi_ |
|
protected |
◆ mutex_
boost::mutex jsk_pcl_ros_utils::SphericalPointCloudSimulator::mutex_ |
|
protected |
◆ pub_
◆ r_
double jsk_pcl_ros_utils::SphericalPointCloudSimulator::r_ |
|
protected |
◆ rotate_velocity_
double jsk_pcl_ros_utils::SphericalPointCloudSimulator::rotate_velocity_ |
|
protected |
◆ scan_num_
int jsk_pcl_ros_utils::SphericalPointCloudSimulator::scan_num_ |
|
protected |
◆ scan_range_
double jsk_pcl_ros_utils::SphericalPointCloudSimulator::scan_range_ |
|
protected |
◆ srv_
◆ sub_
◆ timer_
ros::Timer jsk_pcl_ros_utils::SphericalPointCloudSimulator::timer_ |
|
protected |
The documentation for this class was generated from the following files: