37 #ifndef JSK_PCL_ROS_UTILS_PLANAR_POINTCLOUD_SIMULATOR_H_ 38 #define JSK_PCL_ROS_UTILS_PLANAR_POINTCLOUD_SIMULATOR_H_ 42 #include <jsk_pcl_ros_utils/PlanarPointCloudSimulatorConfig.h> 43 #include <dynamic_reconfigure/server.h> 44 #include <sensor_msgs/PointCloud2.h> 45 #include <sensor_msgs/CameraInfo.h> 64 const sensor_msgs::CameraInfo& info,
double distance,
65 pcl::PointCloud<pcl::PointXYZ>&
cloud);
78 typedef PlanarPointCloudSimulatorConfig
Config;
80 DiagnosticNodelet(
"PlanarPointCloudSimulatorNodelet") {}
82 virtual void onInit();
84 virtual void unsubscribe();
90 const sensor_msgs::CameraInfo::ConstPtr&
info_msg);
92 virtual void configCallback(Config &
config, uint32_t level);
boost::shared_ptr< PlanarPointCloudSimulator > Ptr
Nodelet implementation of jsk_pcl/PlanarPointCloudSimulator.
virtual void generate(const sensor_msgs::CameraInfo &info, double distance, pcl::PointCloud< pcl::PointXYZ > &cloud)
Generate a pointcloud according to width, height and distance.
virtual ~PlanarPointCloudSimulator()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
PlanarPointCloudSimulatorNodelet()
Utility class to generate pointcloud of depth camera and stereo camera.
PlanarPointCloudSimulator()
PlanarPointCloudSimulatorConfig Config
PlanarPointCloudSimulator impl_