#include <handle_estimator.h>
Definition at line 90 of file handle_estimator.h.
◆ SyncPolicy
◆ HandleType
Enumerator |
---|
NO_HANDLE | |
HANDLE_SMALL_ENOUGH_STAND_ON_PLANE | |
HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_Y_LONGEST | |
HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_X_LONGEST | |
Definition at line 127 of file handle_estimator.h.
◆ ~HandleEstimator()
jsk_pcl_ros::HandleEstimator::~HandleEstimator |
( |
| ) |
|
|
virtual |
◆ estimate()
void jsk_pcl_ros::HandleEstimator::estimate |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg, |
|
|
const jsk_recognition_msgs::BoundingBox::ConstPtr & |
box_msg |
|
) |
| |
|
protectedvirtual |
◆ estimateHandle()
void jsk_pcl_ros::HandleEstimator::estimateHandle |
( |
const HandleType & |
handle_type, |
|
|
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg, |
|
|
const jsk_recognition_msgs::BoundingBox::ConstPtr & |
box_msg |
|
) |
| |
|
protectedvirtual |
◆ handleSmallEnoughLieOnPlane()
void jsk_pcl_ros::HandleEstimator::handleSmallEnoughLieOnPlane |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg, |
|
|
const jsk_recognition_msgs::BoundingBox::ConstPtr & |
box_msg, |
|
|
bool |
y_longest |
|
) |
| |
|
protectedvirtual |
◆ handleSmallEnoughStandOnPlane()
void jsk_pcl_ros::HandleEstimator::handleSmallEnoughStandOnPlane |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg, |
|
|
const jsk_recognition_msgs::BoundingBox::ConstPtr & |
box_msg |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros::HandleEstimator::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ selectedIndexCallback()
void jsk_pcl_ros::HandleEstimator::selectedIndexCallback |
( |
const jsk_recognition_msgs::Int32StampedConstPtr & |
index | ) |
|
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::HandleEstimator::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::HandleEstimator::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ angle_divide_num_
int jsk_pcl_ros::HandleEstimator::angle_divide_num_ |
|
protected |
◆ approach_offset_
double jsk_pcl_ros::HandleEstimator::approach_offset_ |
|
protected |
◆ gripper_size_
double jsk_pcl_ros::HandleEstimator::gripper_size_ |
|
protected |
◆ output_buf
boost::circular_buffer<boost::tuple<geometry_msgs::PoseArray, geometry_msgs::PoseArray> > jsk_pcl_ros::HandleEstimator::output_buf |
|
protected |
◆ pub_
◆ pub_best_
◆ pub_preapproach_
◆ pub_selected_
◆ pub_selected_preapproach_
ros::Publisher jsk_pcl_ros::HandleEstimator::pub_selected_preapproach_ |
|
protected |
◆ sub_box_
◆ sub_index_
◆ sub_input_
◆ sync_
◆ tf_listener_
The documentation for this class was generated from the following files: