Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::ExtractCuboidParticlesTopN Class Reference

#include <extract_cuboid_particles_top_n.h>

Inheritance diagram for jsk_pcl_ros::ExtractCuboidParticlesTopN:
Inheritance graph
[legend]

Public Types

typedef ExtractParticlesTopNBaseConfig Config
 
typedef boost::shared_ptr< ExtractCuboidParticlesTopNPtr
 

Public Member Functions

 ExtractCuboidParticlesTopN ()
 

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
 
virtual void extract (const sensor_msgs::PointCloud2::ConstPtr &msg)
 
virtual void onInit ()
 
virtual void publishBoxArray (const pcl::PointCloud< pcl::tracking::ParticleCuboid > &particles, const std_msgs::Header &header)
 
virtual void publishPoseArray (const pcl::PointCloud< pcl::tracking::ParticleCuboid > &particles, const std_msgs::Header &header)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 

Protected Attributes

boost::mutex mutex_
 
ros::Publisher pub_
 
ros::Publisher pub_box_array_
 
ros::Publisher pub_pose_array_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
ros::Subscriber sub_
 
double top_n_ratio_
 

Detailed Description

Definition at line 92 of file extract_cuboid_particles_top_n.h.

Member Typedef Documentation

◆ Config

typedef ExtractParticlesTopNBaseConfig jsk_pcl_ros::ExtractCuboidParticlesTopN::Config

Definition at line 96 of file extract_cuboid_particles_top_n.h.

◆ Ptr

Definition at line 95 of file extract_cuboid_particles_top_n.h.

Constructor & Destructor Documentation

◆ ExtractCuboidParticlesTopN()

jsk_pcl_ros::ExtractCuboidParticlesTopN::ExtractCuboidParticlesTopN ( )
inline

Definition at line 97 of file extract_cuboid_particles_top_n.h.

Member Function Documentation

◆ configCallback()

void jsk_pcl_ros::ExtractCuboidParticlesTopN::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 67 of file extract_cuboid_particles_top_n_nodelet.cpp.

◆ extract()

void jsk_pcl_ros::ExtractCuboidParticlesTopN::extract ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual

Definition at line 73 of file extract_cuboid_particles_top_n_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::ExtractCuboidParticlesTopN::onInit ( )
protectedvirtual

Definition at line 44 of file extract_cuboid_particles_top_n_nodelet.cpp.

◆ publishBoxArray()

void jsk_pcl_ros::ExtractCuboidParticlesTopN::publishBoxArray ( const pcl::PointCloud< pcl::tracking::ParticleCuboid > &  particles,
const std_msgs::Header header 
)
protectedvirtual

Definition at line 102 of file extract_cuboid_particles_top_n_nodelet.cpp.

◆ publishPoseArray()

void jsk_pcl_ros::ExtractCuboidParticlesTopN::publishPoseArray ( const pcl::PointCloud< pcl::tracking::ParticleCuboid > &  particles,
const std_msgs::Header header 
)
protectedvirtual

Definition at line 126 of file extract_cuboid_particles_top_n_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::ExtractCuboidParticlesTopN::subscribe ( )
protectedvirtual

Definition at line 57 of file extract_cuboid_particles_top_n_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::ExtractCuboidParticlesTopN::unsubscribe ( )
protectedvirtual

Definition at line 62 of file extract_cuboid_particles_top_n_nodelet.cpp.

Member Data Documentation

◆ mutex_

boost::mutex jsk_pcl_ros::ExtractCuboidParticlesTopN::mutex_
protected

Definition at line 111 of file extract_cuboid_particles_top_n.h.

◆ pub_

ros::Publisher jsk_pcl_ros::ExtractCuboidParticlesTopN::pub_
protected

Definition at line 112 of file extract_cuboid_particles_top_n.h.

◆ pub_box_array_

ros::Publisher jsk_pcl_ros::ExtractCuboidParticlesTopN::pub_box_array_
protected

Definition at line 113 of file extract_cuboid_particles_top_n.h.

◆ pub_pose_array_

ros::Publisher jsk_pcl_ros::ExtractCuboidParticlesTopN::pub_pose_array_
protected

Definition at line 114 of file extract_cuboid_particles_top_n.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::ExtractCuboidParticlesTopN::srv_
protected

Definition at line 116 of file extract_cuboid_particles_top_n.h.

◆ sub_

ros::Subscriber jsk_pcl_ros::ExtractCuboidParticlesTopN::sub_
protected

Definition at line 115 of file extract_cuboid_particles_top_n.h.

◆ top_n_ratio_

double jsk_pcl_ros::ExtractCuboidParticlesTopN::top_n_ratio_
protected

Definition at line 117 of file extract_cuboid_particles_top_n.h.


The documentation for this class was generated from the following files:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:46