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

#include <container_occupancy_detector.h>

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

Public Types

typedef message_filters::sync_policies::ApproximateTime< jsk_recognition_msgs::BoundingBoxArray, sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy
 
typedef message_filters::sync_policies::ExactTime< jsk_recognition_msgs::BoundingBoxArray, sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
 

Public Member Functions

 ContainerOccupancyDetector ()
 
virtual ~ContainerOccupancyDetector ()
 

Protected Member Functions

virtual void calculate (const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &boxes_msg, const sensor_msgs::PointCloud2::ConstPtr &points_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &point_indices_msg)
 
virtual void onInit ()
 
virtual bool pointsTransform (const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &boxes_msg, const sensor_msgs::PointCloud2::ConstPtr &points_msg)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 

Protected Attributes

std::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > ap_sync_
 
bool approximate_sync_
 
ros::Publisher boxes_occupancy_pub_
 
boost::mutex mutex_
 
jsk_recognition_utils::Counter pass_counter_
 
pcl::PCLPointCloud2Ptr pcl_pc2_ptr_
 
pcl::PointCloud< pcl::PointXYZ >::Ptr pcl_xyz_ptr_
 
int queue_size_
 
jsk_recognition_utils::Counter remove_counter_
 
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_boxes_
 
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_point_indices_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_points_
 
std::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 
tf2_ros::Buffer tf_buffer_
 
tf2_ros::TransformListenertf_listener_
 
sensor_msgs::PointCloud2::Ptr transformed_points_msg_
 

Detailed Description

Definition at line 96 of file container_occupancy_detector.h.

Member Typedef Documentation

◆ ApproximateSyncPolicy

typedef message_filters::sync_policies::ApproximateTime< jsk_recognition_msgs::BoundingBoxArray, sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > jsk_pcl_ros::ContainerOccupancyDetector::ApproximateSyncPolicy

Definition at line 139 of file container_occupancy_detector.h.

◆ SyncPolicy

typedef message_filters::sync_policies::ExactTime< jsk_recognition_msgs::BoundingBoxArray, sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > jsk_pcl_ros::ContainerOccupancyDetector::SyncPolicy

Definition at line 134 of file container_occupancy_detector.h.

Constructor & Destructor Documentation

◆ ContainerOccupancyDetector()

jsk_pcl_ros::ContainerOccupancyDetector::ContainerOccupancyDetector ( )
inline

Definition at line 140 of file container_occupancy_detector.h.

◆ ~ContainerOccupancyDetector()

jsk_pcl_ros::ContainerOccupancyDetector::~ContainerOccupancyDetector ( )
virtual

Definition at line 86 of file container_occupancy_detector_nodelet.cpp.

Member Function Documentation

◆ calculate()

void jsk_pcl_ros::ContainerOccupancyDetector::calculate ( const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &  boxes_msg,
const sensor_msgs::PointCloud2::ConstPtr &  points_msg,
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &  point_indices_msg 
)
protectedvirtual

Definition at line 122 of file container_occupancy_detector_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::ContainerOccupancyDetector::onInit ( )
protectedvirtual

Definition at line 76 of file container_occupancy_detector_nodelet.cpp.

◆ pointsTransform()

bool jsk_pcl_ros::ContainerOccupancyDetector::pointsTransform ( const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &  boxes_msg,
const sensor_msgs::PointCloud2::ConstPtr &  points_msg 
)
protectedvirtual

Definition at line 176 of file container_occupancy_detector_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::ContainerOccupancyDetector::subscribe ( )
protectedvirtual

Definition at line 101 of file container_occupancy_detector_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::ContainerOccupancyDetector::unsubscribe ( )
protectedvirtual

Definition at line 116 of file container_occupancy_detector_nodelet.cpp.

◆ updateDiagnostic()

void jsk_pcl_ros::ContainerOccupancyDetector::updateDiagnostic ( diagnostic_updater::DiagnosticStatusWrapper stat)
protectedvirtual

Definition at line 198 of file container_occupancy_detector_nodelet.cpp.

Member Data Documentation

◆ ap_sync_

std::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_pcl_ros::ContainerOccupancyDetector::ap_sync_
protected

Definition at line 167 of file container_occupancy_detector.h.

◆ approximate_sync_

bool jsk_pcl_ros::ContainerOccupancyDetector::approximate_sync_
protected

Definition at line 196 of file container_occupancy_detector.h.

◆ boxes_occupancy_pub_

ros::Publisher jsk_pcl_ros::ContainerOccupancyDetector::boxes_occupancy_pub_
protected

Definition at line 168 of file container_occupancy_detector.h.

◆ mutex_

boost::mutex jsk_pcl_ros::ContainerOccupancyDetector::mutex_
protected

Definition at line 169 of file container_occupancy_detector.h.

◆ pass_counter_

jsk_recognition_utils::Counter jsk_pcl_ros::ContainerOccupancyDetector::pass_counter_
protected

Definition at line 190 of file container_occupancy_detector.h.

◆ pcl_pc2_ptr_

pcl::PCLPointCloud2Ptr jsk_pcl_ros::ContainerOccupancyDetector::pcl_pc2_ptr_
protected
Initial value:
=
boost::shared_ptr<pcl::PCLPointCloud2>(new pcl::PCLPointCloud2)

Definition at line 180 of file container_occupancy_detector.h.

◆ pcl_xyz_ptr_

pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::ContainerOccupancyDetector::pcl_xyz_ptr_
protected
Initial value:
=
boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>>(new pcl::PointCloud<pcl::PointXYZ>)

Definition at line 182 of file container_occupancy_detector.h.

◆ queue_size_

int jsk_pcl_ros::ContainerOccupancyDetector::queue_size_
protected

Definition at line 195 of file container_occupancy_detector.h.

◆ remove_counter_

jsk_recognition_utils::Counter jsk_pcl_ros::ContainerOccupancyDetector::remove_counter_
protected

Definition at line 189 of file container_occupancy_detector.h.

◆ sub_boxes_

message_filters::Subscriber<jsk_recognition_msgs::BoundingBoxArray> jsk_pcl_ros::ContainerOccupancyDetector::sub_boxes_
protected

Definition at line 163 of file container_occupancy_detector.h.

◆ sub_point_indices_

message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::ContainerOccupancyDetector::sub_point_indices_
protected

Definition at line 165 of file container_occupancy_detector.h.

◆ sub_points_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::ContainerOccupancyDetector::sub_points_
protected

Definition at line 164 of file container_occupancy_detector.h.

◆ sync_

std::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::ContainerOccupancyDetector::sync_
protected

Definition at line 166 of file container_occupancy_detector.h.

◆ tf_buffer_

tf2_ros::Buffer jsk_pcl_ros::ContainerOccupancyDetector::tf_buffer_
protected

Definition at line 170 of file container_occupancy_detector.h.

◆ tf_listener_

tf2_ros::TransformListener* jsk_pcl_ros::ContainerOccupancyDetector::tf_listener_
protected

Definition at line 171 of file container_occupancy_detector.h.

◆ transformed_points_msg_

sensor_msgs::PointCloud2::Ptr jsk_pcl_ros::ContainerOccupancyDetector::transformed_points_msg_
protected
Initial value:
=
boost::shared_ptr<sensor_msgs::PointCloud2>(new sensor_msgs::PointCloud2)

Definition at line 172 of file container_occupancy_detector.h.


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


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