Classes | |
class | CameraDepthSensor |
class | ConvexPolygon |
class | Counter |
class | Cube |
class | Cylinder |
class | GridIndex |
class | GridLine |
class | GridMap |
class | GridPlane |
Grid based representation of planar region. More... | |
class | Line |
Class to represent 3-D straight line. More... | |
class | Plane |
class | PointCloudSensorModel |
Super class for sensor model. It provides pure virtual method for common interfaces. More... | |
class | Polygon |
class | Segment |
class | SeriesedBoolean |
class | SpindleLaserSensor |
class | TfListenerSingleton |
class | TimeredDiagnosticUpdater |
Typedefs | |
typedef std::map< int, std::vector< int > > | IntegerGraphMap |
typedef Eigen::Vector3f | Point |
typedef boost::tuple< size_t, size_t > | PointIndexPair |
typedef boost::tuple< Point, Point > | PointPair |
typedef Eigen::Vector3f | Vertex |
typedef std::vector < Eigen::Vector3f, Eigen::aligned_allocator < Eigen::Vector3f > > | Vertices |
Functions | |
void | _buildGroupFromGraphMap (IntegerGraphMap graph_map, const int from_index, std::vector< int > &to_indices, std::set< int > &output_set) |
void | addDiagnosticBooleanStat (const std::string &string_prefix, const bool value, diagnostic_updater::DiagnosticStatusWrapper &stat) |
void | addDiagnosticErrorSummary (const std::string &string_prefix, jsk_topic_tools::VitalChecker::Ptr vital_checker, diagnostic_updater::DiagnosticStatusWrapper &stat) |
void | addDiagnosticInformation (const std::string &string_prefix, jsk_topic_tools::TimeAccumulator &accumulator, diagnostic_updater::DiagnosticStatusWrapper &stat) |
std::vector< int > | addIndices (const std::vector< int > &a, const std::vector< int > &b) |
pcl::PointIndices::Ptr | addIndices (const pcl::PointIndices &a, const pcl::PointIndices &b) |
template<class T > | |
void | addSet (std::set< T > &output, const std::set< T > &new_set) |
Eigen::Affine3f | affineFromYAMLNode (const YAML::Node &pose) |
template<class T > | |
void | appendVector (std::vector< T > &a, const std::vector< T > &b) |
template<class PointT > | |
jsk_recognition_msgs::BoundingBox | boundingBoxFromPointCloud (const pcl::PointCloud< PointT > &cloud) |
void | buildAllGroupsSetFromGraphMap (IntegerGraphMap graph_map, std::vector< std::set< int > > &output_sets) |
void | buildGroupFromGraphMap (IntegerGraphMap graph_map, const int from_index, std::vector< int > &to_indices, std::set< int > &output_set) |
std_msgs::ColorRGBA | colorCategory20 (int i) |
cv::Scalar | colorROSToCVBGR (const std_msgs::ColorRGBA &ros_color) |
Convert std_msgs::ColorRGBA to cv::Scalar in BGR order. It expects 0-1 values in std_msgs::ColorRGBA. | |
cv::Scalar | colorROSToCVRGB (const std_msgs::ColorRGBA &ros_color) |
Convert std_msgs::ColorRGBA to cv::Scalar in RGB order. It expects 0-1 values in std_msgs::ColorRGBA. | |
bool | compareHistogramWithRangeBin (const jsk_recognition_msgs::HistogramWithRangeBin &left, const jsk_recognition_msgs::HistogramWithRangeBin &right) |
return true if left.count is larger than right.count. | |
cv::MatND | computeHistogram (const cv::Mat &input_image, int bin_size, float min_value, float max_value, const cv::Mat &mask_image) |
simple wrapper for cv::calcHist. | |
void | convertEigenAffine3 (const Eigen::Affine3d &from, Eigen::Affine3f &to) |
void | convertEigenAffine3 (const Eigen::Affine3f &from, Eigen::Affine3d &to) |
template<class FromT , class ToT > | |
void | convertMatrix4 (const FromT &from, ToT &to) |
std::vector< Plane::Ptr > | convertToPlanes (std::vector< pcl::ModelCoefficients::Ptr >) |
template<class PointT > | |
std::vector< typename pcl::PointCloud< PointT >::Ptr > | convertToPointCloudArray (const typename pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< pcl::PointIndices::Ptr > &indices) |
template<class T > | |
pcl::PointCloud< pcl::PointXYZ > ::Ptr | convertToXYZCloud (const pcl::PointCloud< T > &cloud) |
template<class PointT > | |
ConvexPolygon::Ptr | convexFromCoefficientsAndInliers (const typename pcl::PointCloud< PointT >::Ptr cloud, const pcl::PointIndices::Ptr inliers, const pcl::ModelCoefficients::Ptr coefficients) |
std::vector < jsk_recognition_msgs::HistogramWithRangeBin > | cvMatNDToHistogramWithRangeBinArray (const cv::MatND &cv_hist, float min_value, float max_value) |
convert cv::MatND to jsk_recognition_msgs::HistogramimageWithRangeBin array | |
void | drawHistogramWithRangeBin (cv::Mat &image, const jsk_recognition_msgs::HistogramWithRangeBin &bin, float min_width_value, float max_width_value, float max_height_value, cv::Scalar color) |
draw bin to cv::Mat | |
bool | isValidPoint (const pcl::PointXYZ &p) |
tf::StampedTransform | lookupTransformWithDuration (tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration) |
template<class PointT > | |
void | markerMsgToPointCloud (const visualization_msgs::Marker &input_marker, int sample_nums, pcl::PointCloud< PointT > &output_cloud) |
std::ostream & | operator<< (std::ostream &os, const Segment &seg) |
template<class PointT > | |
Vertices | pointCloudToVertices (const pcl::PointCloud< PointT > &cloud) |
Compute Vertices from PointCloud. | |
template<class FromT , class ToT > | |
void | pointFromVectorToVector (const FromT &from, ToT &to) |
template<class FromT , class ToT > | |
void | pointFromVectorToXYZ (const FromT &p, ToT &msg) |
template<class FromT , class ToT > | |
void | pointFromXYZToVector (const FromT &msg, ToT &p) |
template<class FromT , class ToT > | |
void | pointFromXYZToXYZ (const FromT &from, ToT &to) |
std::vector< cv::Point > | project3DPointstoPixel (const image_geometry::PinholeCameraModel &model, const Vertices &vertices) |
Project array of 3d point represented in Eigen::Vector3f to 2d point using model. | |
cv::Point | project3DPointToPixel (const image_geometry::PinholeCameraModel &model, const Eigen::Vector3f &p) |
Project 3d point represented in Eigen::Vector3f to 2d point using model. | |
void | publishPointIndices (ros::Publisher &pub, const pcl::PointIndices &indices, const std_msgs::Header &header) |
Convert pcl::PointIndices to pcl_msgs::PointIndices and publish it with overriding header. | |
double | randomGaussian (double mean, double var, boost::mt19937 &gen) |
Return a random value according to gaussian distribution. If variance is zero, it just returns mean. | |
double | randomUniform (double min, double max, boost::mt19937 &gen) |
Return a random value according to uniform distribution. | |
void | rangeImageToCvMat (const pcl::RangeImage &range_image, cv::Mat &mat) |
Convert pcl::RangeImage to cv::Mat. Distance is normalized to 0-1 and colorized. | |
Eigen::Quaternionf | rotFrom3Axis (const Eigen::Vector3f &ex, const Eigen::Vector3f &ey, const Eigen::Vector3f &ez) |
void | sortHistogramWithRangeBinArray (std::vector< jsk_recognition_msgs::HistogramWithRangeBin > &bins) |
sort std::vector<jsk_recognition_msgs::HistogramWithRangeBin>. largest value will be at the first element. | |
std::vector< int > | subIndices (const std::vector< int > &a, const std::vector< int > &b) |
pcl::PointIndices::Ptr | subIndices (const pcl::PointIndices &a, const pcl::PointIndices &b) |
std::vector < jsk_recognition_msgs::HistogramWithRangeBin > | topNHistogramWithRangeBins (const std::vector< jsk_recognition_msgs::HistogramWithRangeBin > &bins, double top_n_rate) |
extract top-N histograms. bins should be sorted. top_n_rate should be 0-1. | |
template<class PointT > | |
pcl::PointCloud< PointT >::Ptr | verticesToPointCloud (const Vertices &v) |
Compute PointCloud from Vertices. | |
Variables | |
boost::mutex | global_chull_mutex |
This file defines several utilities for pcl <--> ros bridging.
typedef std::map<int, std::vector<int> > jsk_recognition_utils::IntegerGraphMap |
Definition at line 161 of file pcl_util.h.
typedef Eigen::Vector3f jsk_recognition_utils::Point |
typedef boost::tuple<size_t, size_t> jsk_recognition_utils::PointIndexPair |
typedef boost::tuple<Point, Point> jsk_recognition_utils::PointPair |
typedef Eigen::Vector3f jsk_recognition_utils::Vertex |
typedef std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > jsk_recognition_utils::Vertices |
void jsk_recognition_utils::_buildGroupFromGraphMap | ( | IntegerGraphMap | graph_map, |
const int | from_index, | ||
std::vector< int > & | to_indices, | ||
std::set< int > & | output_set | ||
) |
Definition at line 164 of file pcl_util.cpp.
void jsk_recognition_utils::addDiagnosticBooleanStat | ( | const std::string & | string_prefix, |
const bool | value, | ||
diagnostic_updater::DiagnosticStatusWrapper & | stat | ||
) |
Definition at line 229 of file pcl_util.cpp.
void jsk_recognition_utils::addDiagnosticErrorSummary | ( | const std::string & | string_prefix, |
jsk_topic_tools::VitalChecker::Ptr | vital_checker, | ||
diagnostic_updater::DiagnosticStatusWrapper & | stat | ||
) |
Definition at line 218 of file pcl_util.cpp.
void jsk_recognition_utils::addDiagnosticInformation | ( | const std::string & | string_prefix, |
jsk_topic_tools::TimeAccumulator & | accumulator, | ||
diagnostic_updater::DiagnosticStatusWrapper & | stat | ||
) |
Definition at line 204 of file pcl_util.cpp.
std::vector< int > jsk_recognition_utils::addIndices | ( | const std::vector< int > & | a, |
const std::vector< int > & | b | ||
) |
Definition at line 62 of file pcl_util.cpp.
pcl::PointIndices::Ptr jsk_recognition_utils::addIndices | ( | const pcl::PointIndices & | a, |
const pcl::PointIndices & | b | ||
) |
Definition at line 72 of file pcl_util.cpp.
void jsk_recognition_utils::addSet | ( | std::set< T > & | output, |
const std::set< T > & | new_set | ||
) |
Definition at line 184 of file pcl_util.h.
Eigen::Affine3f jsk_recognition_utils::affineFromYAMLNode | ( | const YAML::Node & | pose | ) |
Definition at line 45 of file pcl_util.cpp.
void jsk_recognition_utils::appendVector | ( | std::vector< T > & | a, |
const std::vector< T > & | b | ||
) |
Definition at line 113 of file pcl_util.h.
jsk_recognition_msgs::BoundingBox jsk_recognition_utils::boundingBoxFromPointCloud | ( | const pcl::PointCloud< PointT > & | cloud | ) |
Definition at line 137 of file geo_util.h.
void jsk_recognition_utils::buildAllGroupsSetFromGraphMap | ( | IntegerGraphMap | graph_map, |
std::vector< std::set< int > > & | output_sets | ||
) |
Definition at line 184 of file pcl_util.cpp.
void jsk_recognition_utils::buildGroupFromGraphMap | ( | IntegerGraphMap | graph_map, |
const int | from_index, | ||
std::vector< int > & | to_indices, | ||
std::set< int > & | output_set | ||
) |
Definition at line 133 of file pcl_util.cpp.
std_msgs::ColorRGBA jsk_recognition_utils::colorCategory20 | ( | int | i | ) |
cv::Scalar jsk_recognition_utils::colorROSToCVBGR | ( | const std_msgs::ColorRGBA & | ros_color | ) | [inline] |
Convert std_msgs::ColorRGBA to cv::Scalar in BGR order. It expects 0-1 values in std_msgs::ColorRGBA.
Definition at line 60 of file color_utils.h.
cv::Scalar jsk_recognition_utils::colorROSToCVRGB | ( | const std_msgs::ColorRGBA & | ros_color | ) | [inline] |
Convert std_msgs::ColorRGBA to cv::Scalar in RGB order. It expects 0-1 values in std_msgs::ColorRGBA.
Definition at line 48 of file color_utils.h.
bool jsk_recognition_utils::compareHistogramWithRangeBin | ( | const jsk_recognition_msgs::HistogramWithRangeBin & | left, |
const jsk_recognition_msgs::HistogramWithRangeBin & | right | ||
) |
return true if left.count is larger than right.count.
Definition at line 72 of file cv_utils.cpp.
cv::MatND jsk_recognition_utils::computeHistogram | ( | const cv::Mat & | input_image, |
int | bin_size, | ||
float | min_value, | ||
float | max_value, | ||
const cv::Mat & | mask_image | ||
) |
simple wrapper for cv::calcHist.
cv::MatND is a class to represent histogram in OpenCV 2.x. computeHistogram create 1-dimension cv::MatND.
Definition at line 40 of file cv_utils.cpp.
void jsk_recognition_utils::convertEigenAffine3 | ( | const Eigen::Affine3d & | from, |
Eigen::Affine3f & | to | ||
) |
Definition at line 71 of file pcl_conversion_util.cpp.
void jsk_recognition_utils::convertEigenAffine3 | ( | const Eigen::Affine3f & | from, |
Eigen::Affine3d & | to | ||
) |
Definition at line 80 of file pcl_conversion_util.cpp.
void jsk_recognition_utils::convertMatrix4 | ( | const FromT & | from, |
ToT & | to | ||
) |
Definition at line 101 of file pcl_conversion_util.h.
std::vector< Plane::Ptr > jsk_recognition_utils::convertToPlanes | ( | std::vector< pcl::ModelCoefficients::Ptr > | coefficients | ) |
Definition at line 76 of file polygon.cpp.
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 | ||
) |
Definition at line 80 of file pcl_util.h.
pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_recognition_utils::convertToXYZCloud | ( | const pcl::PointCloud< T > & | cloud | ) |
Definition at line 98 of file pcl_util.h.
ConvexPolygon::Ptr jsk_recognition_utils::convexFromCoefficientsAndInliers | ( | const typename pcl::PointCloud< PointT >::Ptr | cloud, |
const pcl::PointIndices::Ptr | inliers, | ||
const pcl::ModelCoefficients::Ptr | coefficients | ||
) |
Definition at line 91 of file convex_polygon.h.
std::vector< jsk_recognition_msgs::HistogramWithRangeBin > jsk_recognition_utils::cvMatNDToHistogramWithRangeBinArray | ( | const cv::MatND & | cv_hist, |
float | min_value, | ||
float | max_value | ||
) |
convert cv::MatND to jsk_recognition_msgs::HistogramimageWithRangeBin array
Definition at line 56 of file cv_utils.cpp.
void jsk_recognition_utils::drawHistogramWithRangeBin | ( | cv::Mat & | image, |
const jsk_recognition_msgs::HistogramWithRangeBin & | bin, | ||
float | min_width_value, | ||
float | max_width_value, | ||
float | max_height_value, | ||
cv::Scalar | color | ||
) |
draw bin to cv::Mat
Definition at line 108 of file cv_utils.cpp.
bool jsk_recognition_utils::isValidPoint | ( | const pcl::PointXYZ & | p | ) | [inline] |
Definition at line 195 of file pcl_conversion_util.h.
tf::StampedTransform jsk_recognition_utils::lookupTransformWithDuration | ( | tf::TransformListener * | listener, |
const std::string & | to_frame, | ||
const std::string & | from_frame, | ||
const ros::Time & | stamp, | ||
ros::Duration | duration | ||
) |
Definition at line 60 of file tf_listener_singleton.cpp.
void jsk_recognition_utils::markerMsgToPointCloud | ( | const visualization_msgs::Marker & | input_marker, |
int | sample_nums, | ||
pcl::PointCloud< PointT > & | output_cloud | ||
) |
Definition at line 117 of file pcl_conversion_util.h.
std::ostream& jsk_recognition_utils::operator<< | ( | std::ostream & | os, |
const Segment & | seg | ||
) |
Definition at line 98 of file segment.cpp.
Vertices jsk_recognition_utils::pointCloudToVertices | ( | const pcl::PointCloud< PointT > & | cloud | ) |
Compute Vertices from PointCloud.
Definition at line 121 of file geo_util.h.
void jsk_recognition_utils::pointFromVectorToVector | ( | const FromT & | from, |
ToT & | to | ||
) |
Definition at line 94 of file pcl_conversion_util.h.
void jsk_recognition_utils::pointFromVectorToXYZ | ( | const FromT & | p, |
ToT & | msg | ||
) |
Definition at line 80 of file pcl_conversion_util.h.
void jsk_recognition_utils::pointFromXYZToVector | ( | const FromT & | msg, |
ToT & | p | ||
) |
Definition at line 73 of file pcl_conversion_util.h.
void jsk_recognition_utils::pointFromXYZToXYZ | ( | const FromT & | from, |
ToT & | to | ||
) |
Definition at line 87 of file pcl_conversion_util.h.
std::vector< cv::Point > jsk_recognition_utils::project3DPointstoPixel | ( | const image_geometry::PinholeCameraModel & | model, |
const Vertices & | vertices | ||
) |
Project array of 3d point represented in Eigen::Vector3f to 2d point using model.
Definition at line 41 of file sensor_model_utils.cpp.
cv::Point jsk_recognition_utils::project3DPointToPixel | ( | const image_geometry::PinholeCameraModel & | model, |
const Eigen::Vector3f & | p | ||
) | [inline] |
Project 3d point represented in Eigen::Vector3f to 2d point using model.
Definition at line 51 of file sensor_model_utils.h.
void jsk_recognition_utils::publishPointIndices | ( | ros::Publisher & | pub, |
const pcl::PointIndices & | indices, | ||
const std_msgs::Header & | header | ||
) |
Convert pcl::PointIndices to pcl_msgs::PointIndices and publish it with overriding header.
Definition at line 41 of file pcl_ros_util.cpp.
double jsk_recognition_utils::randomGaussian | ( | double | mean, |
double | var, | ||
boost::mt19937 & | gen | ||
) |
Return a random value according to gaussian distribution. If variance is zero, it just returns mean.
Definition at line 41 of file random_util.cpp.
double jsk_recognition_utils::randomUniform | ( | double | min, |
double | max, | ||
boost::mt19937 & | gen | ||
) |
Return a random value according to uniform distribution.
Definition at line 55 of file random_util.cpp.
void jsk_recognition_utils::rangeImageToCvMat | ( | const pcl::RangeImage & | range_image, |
cv::Mat & | mat | ||
) |
Convert pcl::RangeImage to cv::Mat. Distance is normalized to 0-1 and colorized.
range_image | instance of pcl::RangeImage |
mat | instance of cv::Mat, converted cv::Mat is set into this argument. |
Definition at line 42 of file pcl_conversion_util.cpp.
Eigen::Quaternionf jsk_recognition_utils::rotFrom3Axis | ( | const Eigen::Vector3f & | ex, |
const Eigen::Vector3f & | ey, | ||
const Eigen::Vector3f & | ez | ||
) |
Definition at line 55 of file geo_util.cpp.
void jsk_recognition_utils::sortHistogramWithRangeBinArray | ( | std::vector< jsk_recognition_msgs::HistogramWithRangeBin > & | bins | ) |
sort std::vector<jsk_recognition_msgs::HistogramWithRangeBin>. largest value will be at the first element.
Definition at line 78 of file cv_utils.cpp.
std::vector< int > jsk_recognition_utils::subIndices | ( | const std::vector< int > & | a, |
const std::vector< int > & | b | ||
) |
Definition at line 81 of file pcl_util.cpp.
pcl::PointIndices::Ptr jsk_recognition_utils::subIndices | ( | const pcl::PointIndices & | a, |
const pcl::PointIndices & | b | ||
) |
Definition at line 94 of file pcl_util.cpp.
std::vector< jsk_recognition_msgs::HistogramWithRangeBin > jsk_recognition_utils::topNHistogramWithRangeBins | ( | const std::vector< jsk_recognition_msgs::HistogramWithRangeBin > & | bins, |
double | top_n_rate | ||
) |
extract top-N histograms. bins should be sorted. top_n_rate should be 0-1.
Definition at line 84 of file cv_utils.cpp.
pcl::PointCloud<PointT>::Ptr jsk_recognition_utils::verticesToPointCloud | ( | const Vertices & | v | ) |
Compute PointCloud from Vertices.
Definition at line 100 of file geo_util.h.
boost::mutex jsk_recognition_utils::global_chull_mutex |
Definition at line 43 of file pcl_util.cpp.