Go to the documentation of this file.
36 #define BOOST_PARAMETER_MAX_ARITY 7
44 DiagnosticNodelet::onInit();
46 pub_ = advertise<PCLIndicesMsg>(*pnh_,
"output", 1);
67 async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(100);
74 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
76 sync_->registerCallback(
89 const PCLIndicesMsg::ConstPtr& src1,
90 const PCLIndicesMsg::ConstPtr& src2)
92 vital_checker_->poke();
93 pcl::PointIndices
a,
b;
100 ros_indices.header =
src1->header;
pcl::PointIndices PCLIndicesMsg
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
virtual void add(const PCLIndicesMsg::ConstPtr &src1, const PCLIndicesMsg::ConstPtr &src2)
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::AddPointIndices, nodelet::Nodelet)
virtual void unsubscribe()
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
pcl::PointIndices::Ptr addIndices(const pcl::PointIndices &a, const pcl::PointIndices &b)
message_filters::Subscriber< PCLIndicesMsg > sub_src1_
message_filters::Subscriber< PCLIndicesMsg > sub_src2_
virtual ~AddPointIndices()
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43