|
virtual void | onInit () |
|
| ClusterPointIndicesDecomposer () |
|
virtual void | extract (const sensor_msgs::PointCloud2ConstPtr &point, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients) |
|
virtual void | extract (const sensor_msgs::PointCloud2ConstPtr &point, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices) |
|
virtual void | sortIndicesOrder (const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort) |
|
void | sortIndicesOrderByCloudSize (const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort) |
|
void | sortIndicesOrderByIndices (const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort) |
|
void | sortIndicesOrderByZAxis (const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort) |
|
| DiagnosticNodelet (const std::string &name) |
|
| ConnectionBasedNodelet () |
|
void | init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL) |
|
| Nodelet () |
|
virtual | ~Nodelet () |
|
|
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > | ApproximateSyncAlignPolicy |
|
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > | ApproximateSyncPolicy |
|
typedef jsk_pcl_ros::ClusterPointIndicesDecomposerConfig | Config |
|
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > | SyncAlignPolicy |
|
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > | SyncPolicy |
|
typedef boost::shared_ptr< DiagnosticNodelet > | Ptr |
|
void | addToDebugPointCloud (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, size_t i, pcl::PointCloud< pcl::PointXYZRGB > &debug_output) |
|
virtual void | allocatePublishers (size_t num) |
|
virtual bool | computeCenterAndBoundingBox (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, const std_msgs::Header header, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients, geometry_msgs::Pose ¢er_pose_msg, jsk_recognition_msgs::BoundingBox &bounding_box) |
|
virtual void | configCallback (Config &config, uint32_t level) |
|
virtual int | findNearestPlane (const Eigen::Vector4f ¢er, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients) |
|
virtual void | publishNegativeIndices (const sensor_msgs::PointCloud2ConstPtr &input, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input) |
|
virtual void | subscribe () |
|
virtual bool | transformPointCloudToAlignWithPlane (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud_transformed, const Eigen::Vector4f center, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients, Eigen::Matrix4f &m4, Eigen::Quaternionf &q, int &nearest_plane_index) |
|
virtual void | unsubscribe () |
|
virtual void | updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) |
|
ros::Publisher | advertise (ros::NodeHandle &nh, std::string topic, int queue_size) |
|
image_transport::CameraPublisher | advertiseCamera (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size) |
|
image_transport::CameraPublisher | advertiseCamera (ros::NodeHandle &nh, const std::string &topic, int queue_size) |
|
image_transport::Publisher | advertiseImage (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size) |
|
image_transport::Publisher | advertiseImage (ros::NodeHandle &nh, const std::string &topic, int queue_size) |
|
virtual void | cameraConnectionBaseCallback () |
|
virtual void | cameraConnectionCallback (const image_transport::SingleSubscriberPublisher &pub) |
|
virtual void | cameraInfoConnectionCallback (const ros::SingleSubscriberPublisher &pub) |
|
virtual void | connectionCallback (const ros::SingleSubscriberPublisher &pub) |
|
virtual void | imageConnectionCallback (const image_transport::SingleSubscriberPublisher &pub) |
|
virtual bool | isSubscribed () |
|
virtual void | onInitPostProcess () |
|
virtual void | warnNeverSubscribedCallback (const ros::WallTimerEvent &event) |
|
virtual void | warnOnInitPostProcessCalledCallback (const ros::WallTimerEvent &event) |
|
ros::CallbackQueueInterface & | getMTCallbackQueue () const |
|
ros::NodeHandle & | getMTNodeHandle () const |
|
ros::NodeHandle & | getMTPrivateNodeHandle () const |
|
const V_string & | getMyArgv () const |
|
const std::string & | getName () const |
|
ros::NodeHandle & | getNodeHandle () const |
|
ros::NodeHandle & | getPrivateNodeHandle () const |
|
const M_string & | getRemappingArgs () const |
|
ros::CallbackQueueInterface & | getSTCallbackQueue () const |
|
std::string | getSuffixedName (const std::string &suffix) const |
|
static uint32_t | colorRGBAToUInt32 (std_msgs::ColorRGBA c) |
|
bool | align_boxes_ |
|
bool | align_boxes_with_plane_ |
|
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > | async_ |
|
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncAlignPolicy > > | async_align_ |
|
ros::Publisher | box_pub_ |
|
boost::shared_ptr< tf::TransformBroadcaster > | br_ |
|
ros::Publisher | centers_pub_ |
|
jsk_recognition_utils::Counter | cluster_counter_ |
|
bool | fill_boxes_label_with_nearest_plane_index_ |
|
bool | force_to_flip_z_axis_ |
|
ros::Publisher | indices_pub_ |
|
ros::Publisher | label_pub_ |
|
ros::Publisher | mask_pub_ |
|
int | max_size_ |
|
int | min_size_ |
|
boost::mutex | mutex_ |
|
ros::Publisher | negative_indices_pub_ |
|
ros::Publisher | pc_pub_ |
|
bool | publish_clouds_ |
|
bool | publish_tf_ |
|
std::vector< ros::Publisher > | publishers_ |
|
int | queue_size_ |
|
std::string | sort_by_ |
|
boost::shared_ptr< dynamic_reconfigure::Server< Config > > | srv_ |
|
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > | sub_coefficients_ |
|
message_filters::Subscriber< sensor_msgs::PointCloud2 > | sub_input_ |
|
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > | sub_polygons_ |
|
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > | sub_target_ |
|
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > | sync_ |
|
boost::shared_ptr< message_filters::Synchronizer< SyncAlignPolicy > > | sync_align_ |
|
std::string | target_frame_id_ |
|
tf::TransformListener * | tf_listener_ |
|
std::string | tf_prefix_ |
|
bool | use_async_ |
|
bool | use_pca_ |
|
TimeredDiagnosticUpdater::Ptr | diagnostic_updater_ |
|
const std::string | name_ |
|
jsk_topic_tools::VitalChecker::Ptr | vital_checker_ |
|
bool | always_subscribe_ |
|
std::vector< image_transport::CameraPublisher > | camera_publishers_ |
|
boost::mutex | connection_mutex_ |
|
ConnectionStatus | connection_status_ |
|
bool | ever_subscribed_ |
|
std::vector< image_transport::Publisher > | image_publishers_ |
|
boost::shared_ptr< ros::NodeHandle > | nh_ |
|
bool | on_init_post_process_called_ |
|
boost::shared_ptr< ros::NodeHandle > | pnh_ |
|
std::vector< ros::Publisher > | publishers_ |
|
bool | subscribed_ |
|
ros::WallTimer | timer_warn_never_subscribed_ |
|
ros::WallTimer | timer_warn_on_init_post_process_called_ |
|
bool | verbose_connection_ |
|