Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_UTILS_SPHERICAL_POINTCLOUD_SIMULATOR_H_
38 #define JSK_PCL_ROS_UTILS_SPHERICAL_POINTCLOUD_SIMULATOR_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
41 #include <jsk_pcl_ros_utils/SphericalPointCloudSimulatorConfig.h>
43 #include <dynamic_reconfigure/server.h>
51 class SphericalPointCloudSimulator:
public jsk_topic_tools::DiagnosticNodelet
54 typedef SphericalPointCloudSimulatorConfig
Config;
56 DiagnosticNodelet(
"SphericalPointCloudSimulator") {}
84 const sensor_msgs::PointCloud2::ConstPtr& msg);
101 double r,
double theta,
const Eigen::Affine3f& trans);
106 virtual Eigen::Affine3f
getPlane(
double phi);
virtual void subscribe()
Subscribe another pointcloud to synchronize timestamp.
virtual void unsubscribe()
Shutdown subscribers.
SphericalPointCloudSimulator()
virtual void onInit()
Initialization function.
virtual void configCallback(Config &config, uint32_t level)
dynamic_reconfigure callback
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
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 generate(const sensor_msgs::PointCloud2::ConstPtr &msg)
Callback function for ~input topic.
SphericalPointCloudSimulatorConfig Config
virtual Eigen::Affine3f getPlane(double phi)
Transformation for scan plane specified by phi angle.
std::string frame_id_
frame_id of output pointcloud. If it is empty string, frame_id of ~input is copied.
virtual void timerCallback(const ros::TimerEvent &event)
Timer callback for fixed rate publishing.
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43