This is a class for jsk_pcl/SphericalPointCloudSimulator nodelet. More...
#include <spherical_pointcloud_simulator.h>
Public Types | |
typedef SphericalPointCloudSimulatorConfig | Config |
Public Member Functions | |
SphericalPointCloudSimulator () | |
Protected Member Functions | |
virtual void | configCallback (Config &config, uint32_t level) |
dynamic_reconfigure callback | |
virtual void | generate (const sensor_msgs::PointCloud2::ConstPtr &msg) |
Callback function for ~input topic. | |
virtual Eigen::Affine3f | getPlane (double phi) |
Transformation for scan plane specified by phi angle. | |
virtual pcl::PointXYZ | getPoint (double r, double theta, const Eigen::Affine3f &trans) |
compute a point according to a parametric model of spherical tilting laser. | |
virtual void | onInit () |
Initialization function. | |
virtual void | subscribe () |
Subscribe another pointcloud to synchronize timestamp. | |
virtual void | timerCallback (const ros::TimerEvent &event) |
Timer callback for fixed rate publishing. | |
virtual void | unsubscribe () |
Shutdown subscribers. | |
Protected Attributes | |
double | fps_ |
std::string | frame_id_ |
frame_id of output pointcloud. If it is empty string, frame_id of ~input is copied. | |
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_ |
This is a class for jsk_pcl/SphericalPointCloudSimulator nodelet.
Definition at line 51 of file spherical_pointcloud_simulator.h.
typedef SphericalPointCloudSimulatorConfig jsk_pcl_ros::SphericalPointCloudSimulator::Config |
Definition at line 54 of file spherical_pointcloud_simulator.h.
Definition at line 55 of file spherical_pointcloud_simulator.h.
void jsk_pcl_ros::SphericalPointCloudSimulator::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
dynamic_reconfigure callback
Definition at line 73 of file spherical_pointcloud_simulator_nodelet.cpp.
void jsk_pcl_ros::SphericalPointCloudSimulator::generate | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) | [protected, virtual] |
Callback function for ~input topic.
Pointcloud message is used only for timestamp and frame_id.
Definition at line 95 of file spherical_pointcloud_simulator_nodelet.cpp.
Eigen::Affine3f jsk_pcl_ros::SphericalPointCloudSimulator::getPlane | ( | double | phi | ) | [protected, virtual] |
Transformation for scan plane specified by phi angle.
Definition at line 128 of file spherical_pointcloud_simulator_nodelet.cpp.
pcl::PointXYZ jsk_pcl_ros::SphericalPointCloudSimulator::getPoint | ( | double | r, |
double | theta, | ||
const Eigen::Affine3f & | trans | ||
) | [protected, virtual] |
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 138 of file spherical_pointcloud_simulator_nodelet.cpp.
void jsk_pcl_ros::SphericalPointCloudSimulator::onInit | ( | void | ) | [protected, virtual] |
Initialization function.
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 40 of file spherical_pointcloud_simulator_nodelet.cpp.
void jsk_pcl_ros::SphericalPointCloudSimulator::subscribe | ( | ) | [protected, virtual] |
Subscribe another pointcloud to synchronize timestamp.
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 62 of file spherical_pointcloud_simulator_nodelet.cpp.
void jsk_pcl_ros::SphericalPointCloudSimulator::timerCallback | ( | const ros::TimerEvent & | event | ) | [protected, virtual] |
Timer callback for fixed rate publishing.
Definition at line 85 of file spherical_pointcloud_simulator_nodelet.cpp.
void jsk_pcl_ros::SphericalPointCloudSimulator::unsubscribe | ( | ) | [protected, virtual] |
Shutdown subscribers.
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 68 of file spherical_pointcloud_simulator_nodelet.cpp.
double jsk_pcl_ros::SphericalPointCloudSimulator::fps_ [protected] |
Definition at line 126 of file spherical_pointcloud_simulator.h.
frame_id of output pointcloud. If it is empty string, frame_id of ~input is copied.
Definition at line 117 of file spherical_pointcloud_simulator.h.
double jsk_pcl_ros::SphericalPointCloudSimulator::max_phi_ [protected] |
Definition at line 124 of file spherical_pointcloud_simulator.h.
double jsk_pcl_ros::SphericalPointCloudSimulator::min_phi_ [protected] |
Definition at line 123 of file spherical_pointcloud_simulator.h.
Definition at line 108 of file spherical_pointcloud_simulator.h.
Definition at line 110 of file spherical_pointcloud_simulator.h.
double jsk_pcl_ros::SphericalPointCloudSimulator::r_ [protected] |
Definition at line 122 of file spherical_pointcloud_simulator.h.
double jsk_pcl_ros::SphericalPointCloudSimulator::rotate_velocity_ [protected] |
Definition at line 118 of file spherical_pointcloud_simulator.h.
int jsk_pcl_ros::SphericalPointCloudSimulator::scan_num_ [protected] |
Definition at line 127 of file spherical_pointcloud_simulator.h.
double jsk_pcl_ros::SphericalPointCloudSimulator::scan_range_ [protected] |
Definition at line 125 of file spherical_pointcloud_simulator.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::SphericalPointCloudSimulator::srv_ [protected] |
Definition at line 111 of file spherical_pointcloud_simulator.h.
Definition at line 109 of file spherical_pointcloud_simulator.h.
Definition at line 120 of file spherical_pointcloud_simulator.h.