Go to the documentation of this file.
35 #define BOOST_PARAMETER_MAX_ARITY 7
52 const sensor_msgs::CameraInfo& info,
double distance,
53 pcl::PointCloud<pcl::PointXYZ>&
cloud)
57 cloud.points.resize(info.width * info.height);
58 cloud.is_dense =
true;
59 for (
size_t j = 0; j < info.height; j++) {
60 for (
size_t i = 0;
i < info.width;
i++) {
66 cloud.points[j * info.width +
i] =
p;
69 cloud.width = info.width;
70 cloud.height = info.height;
75 DiagnosticNodelet::onInit();
76 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
77 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
79 srv_->setCallback (
f);
81 pub_ = advertise<sensor_msgs::PointCloud2>(
89 sub_ = pnh_->subscribe(
99 Config &config, uint32_t level)
106 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
109 vital_checker_->poke();
110 pcl::PointCloud<pcl::PointXYZ>::Ptr
111 cloud(
new pcl::PointCloud<pcl::PointXYZ>);
113 sensor_msgs::PointCloud2 ros_cloud;
115 ros_cloud.header =
info_msg->header;
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()
PlanarPointCloudSimulator impl_
virtual void unsubscribe()
PlanarPointCloudSimulator()
PlanarPointCloudSimulatorConfig Config
cv::Point3d projectPixelTo3dRay(const cv::Point2d &uv_rect) const
void publish(const boost::shared_ptr< M > &message) const
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
Nodelet implementation of jsk_pcl/PlanarPointCloudSimulator.
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
virtual void generate(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
Callback function for ~input.
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PlanarPointCloudSimulatorNodelet, nodelet::Nodelet)
virtual void configCallback(Config &config, uint32_t level)
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43