#include <pcl/point_types.h>#include <boost/accumulators/accumulators.hpp>#include <boost/accumulators/statistics/stats.hpp>#include <boost/accumulators/statistics/min.hpp>#include <boost/accumulators/statistics/max.hpp>#include <boost/accumulators/statistics/variance.hpp>#include <boost/accumulators/statistics/count.hpp>#include <set>#include <map>#include <sensor_msgs/PointCloud2.h>#include <ros/ros.h>#include <pcl/PointIndices.h>#include <std_msgs/ColorRGBA.h>#include <jsk_topic_tools/time_accumulator.h>#include <jsk_topic_tools/timered_diagnostic_updater.h>#include <boost/circular_buffer.hpp>#include <jsk_topic_tools/vital_checker.h>#include <pcl/filters/extract_indices.h>#include <yaml-cpp/yaml.h>

Go to the source code of this file.
Classes | |
| class | jsk_recognition_utils::Counter |
| class | jsk_recognition_utils::SeriesedBoolean |
Namespaces | |
| namespace | jsk_recognition_utils |
Typedefs | |
| typedef std::map< int, std::vector< int > > | jsk_recognition_utils::IntegerGraphMap |
| typedef jsk_topic_tools::TimeredDiagnosticUpdater | jsk_recognition_utils::TimeredDiagnosticUpdater |
Functions | |
| void | jsk_recognition_utils::_buildGroupFromGraphMap (IntegerGraphMap graph_map, const int from_index, std::vector< int > &to_indices, std::set< int > &output_set) |
| std::vector< int > | jsk_recognition_utils::addIndices (const std::vector< int > &a, const std::vector< int > &b) |
| pcl::PointIndices::Ptr | jsk_recognition_utils::addIndices (const pcl::PointIndices &a, const pcl::PointIndices &b) |
| template<class T > | |
| void | jsk_recognition_utils::addSet (std::set< T > &output, const std::set< T > &new_set) |
| Eigen::Affine3f | jsk_recognition_utils::affineFromYAMLNode (const YAML::Node &pose) |
| template<class T > | |
| void | jsk_recognition_utils::appendVector (std::vector< T > &a, const std::vector< T > &b) |
| void | jsk_recognition_utils::buildAllGroupsSetFromGraphMap (IntegerGraphMap graph_map, std::vector< std::set< int > > &output_sets) |
| void | jsk_recognition_utils::buildGroupFromGraphMap (IntegerGraphMap graph_map, const int from_index, std::vector< int > &to_indices, std::set< int > &output_set) |
| std_msgs::ColorRGBA | jsk_recognition_utils::colorCategory20 (int i) |
| template<class PointT > | |
| std::vector< typename pcl::PointCloud< PointT >::Ptr > | jsk_recognition_utils::convertToPointCloudArray (const typename pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< pcl::PointIndices::Ptr > &indices) |
| template<class T > | |
| pcl::PointCloud< pcl::PointXYZ > ::Ptr | jsk_recognition_utils::convertToXYZCloud (const pcl::PointCloud< T > &cloud) |
| std::vector< int > | jsk_recognition_utils::subIndices (const std::vector< int > &a, const std::vector< int > &b) |
| pcl::PointIndices::Ptr | jsk_recognition_utils::subIndices (const pcl::PointIndices &a, const pcl::PointIndices &b) |
Variables | |
| boost::mutex | jsk_recognition_utils::global_chull_mutex |