Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
jsk_recognition_utils Namespace Reference

Namespaces

 chainermodels
 
 color
 
 conversations
 
 datasets
 
 depth
 
 feature
 
 geometry
 
 mask
 
 put_text
 
 visualize
 

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...
 
struct  PointXYZHLS
 
class  Polygon
 
class  PolyLine
 Class to represent 3-D polyline (not closed). More...
 
class  ScopedWallDurationReporter
 
class  Segment
 Class to represent 3-D straight line which has finite length. More...
 
class  SeriesedBoolean
 
class  SpindleLaserSensor
 
class  TfListenerSingleton
 
class  WallDurationTimer
 

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, PointPointPair
 
typedef jsk_topic_tools::TimeredDiagnosticUpdater TimeredDiagnosticUpdater
 
typedef Eigen::Vector3f Vertex
 
typedef std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
 

Enumerations

enum  Colors {
  ALICEBLUE, ANTIQUEWHITE, AQUA, AQUAMARINE,
  AZURE, BEIGE, BISQUE, BLACK,
  BLANCHEDALMOND, BLUE, BLUEVIOLET, BROWN,
  BURLYWOOD, CADETBLUE, CHARTREUSE, CHOCOLATE,
  CORAL, CORNFLOWERBLUE, CORNSILK, CRIMSON,
  CYAN, DARKBLUE, DARKCYAN, DARKGOLDENROD,
  DARKGRAY, DARKGREEN, DARKGREY, DARKKHAKI,
  DARKMAGENTA, DARKOLIVEGREEN, DARKORANGE, DARKORCHID,
  DARKRED, DARKSALMON, DARKSEAGREEN, DARKSLATEBLUE,
  DARKSLATEGRAY, DARKSLATEGREY, DARKTURQUOISE, DARKVIOLET,
  DEEPPINK, DEEPSKYBLUE, DIMGRAY, DIMGREY,
  DODGERBLUE, FIREBRICK, FLORALWHITE, FORESTGREEN,
  FUCHSIA, GAINSBORO, GHOSTWHITE, GOLD,
  GOLDENROD, GRAY, GREEN, GREENYELLOW,
  GREY, HONEYDEW, HOTPINK, INDIANRED,
  INDIGO, IVORY, KHAKI, LAVENDER,
  LAVENDERBLUSH, LAWNGREEN, LEMONCHIFFON, LIGHTBLUE,
  LIGHTCORAL, LIGHTCYAN, LIGHTGOLDENRODYELLOW, LIGHTGRAY,
  LIGHTGREEN, LIGHTGREY, LIGHTPINK, LIGHTSALMON,
  LIGHTSEAGREEN, LIGHTSKYBLUE, LIGHTSLATEGRAY, LIGHTSLATEGREY,
  LIGHTSTEELBLUE, LIGHTYELLOW, LIME, LIMEGREEN,
  LINEN, MAGENTA, MAROON, MEDIUMAQUAMARINE,
  MEDIUMBLUE, MEDIUMORCHID, MEDIUMPURPLE, MEDIUMSEAGREEN,
  MEDIUMSLATEBLUE, MEDIUMSPRINGGREEN, MEDIUMTURQUOISE, MEDIUMVIOLETRED,
  MIDNIGHTBLUE, MINTCREAM, MISTYROSE, MOCCASIN,
  NAVAJOWHITE, NAVY, OLDLACE, OLIVE,
  OLIVEDRAB, ORANGE, ORANGERED, ORCHID,
  PALEGOLDENROD, PALEGREEN, PALEVIOLETRED, PAPAYAWHIP,
  PEACHPUFF, PERU, PINK, PLUM,
  POWDERBLUE, PURPLE, RED, ROSYBROWN,
  ROYALBLUE, SADDLEBROWN, SALMON, SANDYBROWN,
  SEAGREEN, SEASHELL, SIENNA, SILVER,
  SKYBLUE, SLATEBLUE, SLATEGRAY, SLATEGREY,
  SNOW, SPRINGGREEN, STEELBLUE, TAN,
  TEAL, THISTLE, TOMATO, TURQUOISE,
  VIOLET, WHEAT, WHITE, WHITESMOKE,
  YELLOW, YELLOWGREEN
}
 146 rgb colors More...
 
enum  ComparePolicy {
  CORRELATION = 0, BHATTACHARYYA, INTERSECTION, CHISQUARE,
  KL_DIVERGENCE
}
 
enum  HistogramPolicy { HUE = 0, HUE_AND_SATURATION }
 

Functions

void _buildGroupFromGraphMap (IntegerGraphMap graph_map, const int from_index, std::vector< int > &to_indices, std::set< int > &output_set)
 
pcl::PointIndices::Ptr addIndices (const pcl::PointIndices &a, const pcl::PointIndices &b)
 
std::vector< int > addIndices (const std::vector< int > &a, const std::vector< int > &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)
 
cv::Rect boundingRectFromContours (const std::vector< cv::Point > &contours)
 Return Bounding Box from contours. More...
 
cv::Rect boundingRectOfMaskImage (const cv::Mat &image)
 compute bounding rectangle of mask image. More...
 
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. More...
 
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. More...
 
bool compareHistogram (const std::vector< float > &input, const std::vector< float > &reference, const ComparePolicy policy, double &distance)
 
bool compareHistogramWithRangeBin (const jsk_recognition_msgs::HistogramWithRangeBin &left, const jsk_recognition_msgs::HistogramWithRangeBin &right)
 return true if left.count is larger than right.count. More...
 
void computeColorHistogram1d (const pcl::PointCloud< pcl::PointXYZHSV > &cloud, std::vector< float > &histogram, const int bin_size, const double white_threshold=0.1, const double black_threshold=0.1)
 
void computeColorHistogram2d (const pcl::PointCloud< pcl::PointXYZHSV > &cloud, std::vector< float > &histogram, const int bin_size_per_channel, const double white_threshold=0.1, const double black_threshold=0.1)
 
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. More...
 
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::PtrconvertToPlanes (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)
 
template<typename PointT >
void cropPointCloud (const typename pcl::PointCloud< PointT >::Ptr &cloud, const jsk_recognition_msgs::BoundingBox &bbox_msg, std::vector< int > *indices, bool extract_removed_indices=false)
 Crop point cloud with jsk_recognition_msgs/BoundingBox. More...
 
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 More...
 
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 More...
 
int getHistogramBin (const double &val, const int &step, const double &min, const double &max)
 
cv::Vec3d getRGBColor (const int color)
 get rgb color with enum. More...
 
bool hasField (const std::string &field_name, const sensor_msgs::PointCloud2 &msg)
 check if sensor_msgs/PointCloud2 message has the specified field. More...
 
cv::MatND HistogramWithRangeBinArrayTocvMatND (const std::vector< jsk_recognition_msgs::HistogramWithRangeBin > &histogram)
 convert jsk_recognition_msgs::HistogramimageWithRangeBin array to cv::MatND More...
 
void HSV2HLS (const pcl::PointXYZHSV &hsv, PointXYZHLS &hls)
 
bool isBGR (const std::string &encoding)
 Check encodings. More...
 
bool isBGRA (const std::string &encoding)
 
bool isRGB (const std::string &encoding)
 
bool isRGBA (const std::string &encoding)
 
bool isSameFrameId (const std::string &a, const std::string &b)
 Return true if a and b are the same frame_id. More...
 
bool isSameFrameId (const std_msgs::Header &a, const std_msgs::Header &b)
 Return true if a and b have the same frame_id. More...
 
template<class T1 , class T2 >
bool isSameFrameId (const T1 &a, const T2 &b)
 Return true if a and b have the same frame_id. More...
 
bool isValidPoint (const pcl::PointXYZ &p)
 
template<class PointT >
bool isValidPoint (const PointT &p)
 
void labelToRGB (const cv::Mat src, cv::Mat &dst)
 convert label image to rgb one. More...
 
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)
 
void normalizeHistogram (std::vector< float > &histogram)
 
std::ostream & operator<< (std::ostream &os, const PolyLine &pl)
 
std::ostream & operator<< (std::ostream &os, const Segment &seg)
 
template<class PointT >
Vertices pointCloudToVertices (const pcl::PointCloud< PointT > &cloud)
 Compute Vertices from PointCloud. More...
 
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::Pointproject3DPointstoPixel (const image_geometry::PinholeCameraModel &model, const Vertices &vertices)
 Project array of 3d point represented in Eigen::Vector3f to 2d point using model. More...
 
cv::Point project3DPointToPixel (const image_geometry::PinholeCameraModel &model, const Eigen::Vector3f &p)
 Project 3d point represented in Eigen::Vector3f to 2d point using model. More...
 
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. More...
 
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. More...
 
double randomUniform (double min, double max, boost::mt19937 &gen)
 Return a random value according to uniform distribution. More...
 
void rangeImageToCvMat (const pcl::RangeImage &range_image, cv::Mat &mat)
 Convert pcl::RangeImage to cv::Mat. Distance is normalized to 0-1 and colorized. More...
 
void rotateHistogram1d (const std::vector< float > &input, std::vector< float > &output, const double degree)
 
void rotateHistogram2d (const std::vector< float > &input, std::vector< float > &output, const double degree)
 
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. More...
 
pcl::PointIndices::Ptr subIndices (const pcl::PointIndices &a, const pcl::PointIndices &b)
 
std::vector< int > subIndices (const std::vector< int > &a, const std::vector< int > &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. More...
 
template<class PointT >
pcl::PointCloud< PointT >::Ptr verticesToPointCloud (const Vertices &v)
 Compute PointCloud from Vertices. More...
 

Variables

bool _chainer_available = True
 
bool _chainercv_available = True
 
list _depends = []
 
bool _fcn_available = True
 
 BagOfFeatures = feature.BagOfFeatures
 
 bounding_box_msg_to_aabb = conversations.bounding_box_msg_to_aabb
 
 bounding_rect_of_mask = mask.bounding_rect_of_mask
 
 centerize = visualize.centerize
 
 colorize_cluster_indices = visualize.colorize_cluster_indices
 
 decompose_descriptors_with_label = feature.decompose_descriptors_with_label
 
 descent_closing = mask.descent_closing
 
 file
 
 get_overlap_of_aabb = geometry.get_overlap_of_aabb
 
 get_tile_image = visualize.get_tile_image
 
boost::mutex global_chull_mutex
 
 rects_msg_to_ndarray = conversations.rects_msg_to_ndarray
 

Detailed Description

This file defines several utilities for pcl <--> ros bridging.

Typedef Documentation

◆ IntegerGraphMap

Definition at line 193 of file pcl_util.h.

◆ Point

typedef Eigen::Vector3f jsk_recognition_utils::Point

Definition at line 77 of file types.h.

◆ PointIndexPair

typedef boost::tuple<size_t, size_t> jsk_recognition_utils::PointIndexPair

Definition at line 82 of file types.h.

◆ PointPair

Definition at line 81 of file types.h.

◆ TimeredDiagnosticUpdater

typedef jsk_topic_tools::TimeredDiagnosticUpdater jsk_recognition_utils::TimeredDiagnosticUpdater

Definition at line 253 of file pcl_util.h.

◆ Vertex

typedef Eigen::Vector3f jsk_recognition_utils::Vertex

Definition at line 78 of file types.h.

◆ Vertices

typedef std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > jsk_recognition_utils::Vertices

Definition at line 80 of file types.h.

Enumeration Type Documentation

◆ Colors

146 rgb colors

Enumerator
ALICEBLUE 
ANTIQUEWHITE 
AQUA 
AQUAMARINE 
AZURE 
BEIGE 
BISQUE 
BLACK 
BLANCHEDALMOND 
BLUE 
BLUEVIOLET 
BROWN 
BURLYWOOD 
CADETBLUE 
CHARTREUSE 
CHOCOLATE 
CORAL 
CORNFLOWERBLUE 
CORNSILK 
CRIMSON 
CYAN 
DARKBLUE 
DARKCYAN 
DARKGOLDENROD 
DARKGRAY 
DARKGREEN 
DARKGREY 
DARKKHAKI 
DARKMAGENTA 
DARKOLIVEGREEN 
DARKORANGE 
DARKORCHID 
DARKRED 
DARKSALMON 
DARKSEAGREEN 
DARKSLATEBLUE 
DARKSLATEGRAY 
DARKSLATEGREY 
DARKTURQUOISE 
DARKVIOLET 
DEEPPINK 
DEEPSKYBLUE 
DIMGRAY 
DIMGREY 
DODGERBLUE 
FIREBRICK 
FLORALWHITE 
FORESTGREEN 
FUCHSIA 
GAINSBORO 
GHOSTWHITE 
GOLD 
GOLDENROD 
GRAY 
GREEN 
GREENYELLOW 
GREY 
HONEYDEW 
HOTPINK 
INDIANRED 
INDIGO 
IVORY 
KHAKI 
LAVENDER 
LAVENDERBLUSH 
LAWNGREEN 
LEMONCHIFFON 
LIGHTBLUE 
LIGHTCORAL 
LIGHTCYAN 
LIGHTGOLDENRODYELLOW 
LIGHTGRAY 
LIGHTGREEN 
LIGHTGREY 
LIGHTPINK 
LIGHTSALMON 
LIGHTSEAGREEN 
LIGHTSKYBLUE 
LIGHTSLATEGRAY 
LIGHTSLATEGREY 
LIGHTSTEELBLUE 
LIGHTYELLOW 
LIME 
LIMEGREEN 
LINEN 
MAGENTA 
MAROON 
MEDIUMAQUAMARINE 
MEDIUMBLUE 
MEDIUMORCHID 
MEDIUMPURPLE 
MEDIUMSEAGREEN 
MEDIUMSLATEBLUE 
MEDIUMSPRINGGREEN 
MEDIUMTURQUOISE 
MEDIUMVIOLETRED 
MIDNIGHTBLUE 
MINTCREAM 
MISTYROSE 
MOCCASIN 
NAVAJOWHITE 
NAVY 
OLDLACE 
OLIVE 
OLIVEDRAB 
ORANGE 
ORANGERED 
ORCHID 
PALEGOLDENROD 
PALEGREEN 
PALEVIOLETRED 
PAPAYAWHIP 
PEACHPUFF 
PERU 
PINK 
PLUM 
POWDERBLUE 
PURPLE 
RED 
ROSYBROWN 
ROYALBLUE 
SADDLEBROWN 
SALMON 
SANDYBROWN 
SEAGREEN 
SEASHELL 
SIENNA 
SILVER 
SKYBLUE 
SLATEBLUE 
SLATEGRAY 
SLATEGREY 
SNOW 
SPRINGGREEN 
STEELBLUE 
TAN 
TEAL 
THISTLE 
TOMATO 
TURQUOISE 
VIOLET 
WHEAT 
WHITE 
WHITESMOKE 
YELLOW 
YELLOWGREEN 

Definition at line 82 of file rgb_colors.h.

◆ ComparePolicy

Enumerator
CORRELATION 
BHATTACHARYYA 
INTERSECTION 
CHISQUARE 
KL_DIVERGENCE 

Definition at line 87 of file color_histogram.h.

◆ HistogramPolicy

Enumerator
HUE 
HUE_AND_SATURATION 

Definition at line 82 of file color_histogram.h.

Function Documentation

◆ _buildGroupFromGraphMap()

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 196 of file pcl_util.cpp.

◆ addIndices() [1/2]

pcl::PointIndices::Ptr jsk_recognition_utils::addIndices ( const pcl::PointIndices &  a,
const pcl::PointIndices &  b 
)

Definition at line 104 of file pcl_util.cpp.

◆ addIndices() [2/2]

std::vector< int > jsk_recognition_utils::addIndices ( const std::vector< int > &  a,
const std::vector< int > &  b 
)

Definition at line 94 of file pcl_util.cpp.

◆ addSet()

template<class T >
void jsk_recognition_utils::addSet ( std::set< T > &  output,
const std::set< T > &  new_set 
)

Definition at line 216 of file pcl_util.h.

◆ affineFromYAMLNode()

Eigen::Affine3f jsk_recognition_utils::affineFromYAMLNode ( const YAML::Node &  pose)

Definition at line 77 of file pcl_util.cpp.

◆ appendVector()

template<class T >
void jsk_recognition_utils::appendVector ( std::vector< T > &  a,
const std::vector< T > &  b 
)

Definition at line 145 of file pcl_util.h.

◆ boundingBoxFromPointCloud()

template<class PointT >
jsk_recognition_msgs::BoundingBox jsk_recognition_utils::boundingBoxFromPointCloud ( const pcl::PointCloud< PointT > &  cloud)

Definition at line 139 of file geo_util.h.

◆ boundingRectFromContours()

cv::Rect jsk_recognition_utils::boundingRectFromContours ( const std::vector< cv::Point > &  contours)

Return Bounding Box from contours.

Definition at line 196 of file cv_utils.cpp.

◆ boundingRectOfMaskImage()

cv::Rect jsk_recognition_utils::boundingRectOfMaskImage ( const cv::Mat &  image)

compute bounding rectangle of mask image.

Definition at line 218 of file cv_utils.cpp.

◆ buildAllGroupsSetFromGraphMap()

void jsk_recognition_utils::buildAllGroupsSetFromGraphMap ( IntegerGraphMap  graph_map,
std::vector< std::set< int > > &  output_sets 
)

Definition at line 216 of file pcl_util.cpp.

◆ buildGroupFromGraphMap()

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 165 of file pcl_util.cpp.

◆ colorCategory20()

std_msgs::ColorRGBA jsk_recognition_utils::colorCategory20 ( int  i)

◆ colorROSToCVBGR()

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 92 of file color_utils.h.

◆ colorROSToCVRGB()

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 80 of file color_utils.h.

◆ compareHistogram()

bool jsk_recognition_utils::compareHistogram ( const std::vector< float > &  input,
const std::vector< float > &  reference,
const ComparePolicy  policy,
double &  distance 
)
inline

Definition at line 229 of file color_histogram.h.

◆ compareHistogramWithRangeBin()

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 120 of file cv_utils.cpp.

◆ computeColorHistogram1d()

void jsk_recognition_utils::computeColorHistogram1d ( const pcl::PointCloud< pcl::PointXYZHSV > &  cloud,
std::vector< float > &  histogram,
const int  bin_size,
const double  white_threshold = 0.1,
const double  black_threshold = 0.1 
)
inline

Definition at line 133 of file color_histogram.h.

◆ computeColorHistogram2d()

void jsk_recognition_utils::computeColorHistogram2d ( const pcl::PointCloud< pcl::PointXYZHSV > &  cloud,
std::vector< float > &  histogram,
const int  bin_size_per_channel,
const double  white_threshold = 0.1,
const double  black_threshold = 0.1 
)
inline

Definition at line 160 of file color_histogram.h.

◆ computeHistogram()

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 76 of file cv_utils.cpp.

◆ convertEigenAffine3() [1/2]

void jsk_recognition_utils::convertEigenAffine3 ( const Eigen::Affine3d &  from,
Eigen::Affine3f &  to 
)

Definition at line 103 of file pcl_conversion_util.cpp.

◆ convertEigenAffine3() [2/2]

void jsk_recognition_utils::convertEigenAffine3 ( const Eigen::Affine3f &  from,
Eigen::Affine3d &  to 
)

Definition at line 112 of file pcl_conversion_util.cpp.

◆ convertMatrix4()

template<class FromT , class ToT >
void jsk_recognition_utils::convertMatrix4 ( const FromT &  from,
ToT &  to 
)

Definition at line 101 of file pcl_conversion_util.h.

◆ convertToPlanes()

std::vector< Plane::Ptr > jsk_recognition_utils::convertToPlanes ( std::vector< pcl::ModelCoefficients::Ptr >  coefficients)

Definition at line 76 of file polygon.cpp.

◆ convertToPointCloudArray()

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 
)

Definition at line 112 of file pcl_util.h.

◆ convertToXYZCloud()

template<class T >
pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_recognition_utils::convertToXYZCloud ( const pcl::PointCloud< T > &  cloud)

Definition at line 130 of file pcl_util.h.

◆ convexFromCoefficientsAndInliers()

template<class PointT >
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 123 of file convex_polygon.h.

◆ cropPointCloud()

template<typename PointT >
void jsk_recognition_utils::cropPointCloud ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
const jsk_recognition_msgs::BoundingBox &  bbox_msg,
std::vector< int > *  indices,
bool  extract_removed_indices = false 
)

Crop point cloud with jsk_recognition_msgs/BoundingBox.

Definition at line 133 of file pcl_ros_util.h.

◆ cvMatNDToHistogramWithRangeBinArray()

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 92 of file cv_utils.cpp.

◆ drawHistogramWithRangeBin()

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 156 of file cv_utils.cpp.

◆ getHistogramBin()

int jsk_recognition_utils::getHistogramBin ( const double &  val,
const int &  step,
const double &  min,
const double &  max 
)
inline

Definition at line 111 of file color_histogram.h.

◆ getRGBColor()

cv::Vec3d jsk_recognition_utils::getRGBColor ( const int  color)

get rgb color with enum.

Definition at line 75 of file rgb_colors.cpp.

◆ hasField()

bool jsk_recognition_utils::hasField ( const std::string field_name,
const sensor_msgs::PointCloud2 &  msg 
)

check if sensor_msgs/PointCloud2 message has the specified field.

Definition at line 108 of file pcl_ros_util.cpp.

◆ HistogramWithRangeBinArrayTocvMatND()

cv::MatND jsk_recognition_utils::HistogramWithRangeBinArrayTocvMatND ( const std::vector< jsk_recognition_msgs::HistogramWithRangeBin > &  histogram)

convert jsk_recognition_msgs::HistogramimageWithRangeBin array to cv::MatND

Definition at line 109 of file cv_utils.cpp.

◆ HSV2HLS()

void jsk_recognition_utils::HSV2HLS ( const pcl::PointXYZHSV &  hsv,
PointXYZHLS hls 
)
inline

Definition at line 101 of file color_histogram.h.

◆ isBGR()

bool jsk_recognition_utils::isBGR ( const std::string encoding)

Check encodings.

Definition at line 238 of file cv_utils.cpp.

◆ isBGRA()

bool jsk_recognition_utils::isBGRA ( const std::string encoding)

Definition at line 248 of file cv_utils.cpp.

◆ isRGB()

bool jsk_recognition_utils::isRGB ( const std::string encoding)

Definition at line 243 of file cv_utils.cpp.

◆ isRGBA()

bool jsk_recognition_utils::isRGBA ( const std::string encoding)

Definition at line 253 of file cv_utils.cpp.

◆ isSameFrameId() [1/3]

bool jsk_recognition_utils::isSameFrameId ( const std::string a,
const std::string b 
)

Return true if a and b are the same frame_id.

Definition at line 83 of file pcl_ros_util.cpp.

◆ isSameFrameId() [2/3]

bool jsk_recognition_utils::isSameFrameId ( const std_msgs::Header a,
const std_msgs::Header b 
)

Return true if a and b have the same frame_id.

Definition at line 103 of file pcl_ros_util.cpp.

◆ isSameFrameId() [3/3]

template<class T1 , class T2 >
bool jsk_recognition_utils::isSameFrameId ( const T1 &  a,
const T2 &  b 
)

Return true if a and b have the same frame_id.

Definition at line 116 of file pcl_ros_util.h.

◆ isValidPoint() [1/2]

bool jsk_recognition_utils::isValidPoint ( const pcl::PointXYZ &  p)
inline

Definition at line 195 of file pcl_conversion_util.h.

◆ isValidPoint() [2/2]

template<class PointT >
bool jsk_recognition_utils::isValidPoint ( const PointT &  p)
inline

Definition at line 201 of file pcl_conversion_util.h.

◆ labelToRGB()

void jsk_recognition_utils::labelToRGB ( const cv::Mat  src,
cv::Mat &  dst 
)

convert label image to rgb one.

Definition at line 179 of file cv_utils.cpp.

◆ lookupTransformWithDuration()

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 92 of file tf_listener_singleton.cpp.

◆ markerMsgToPointCloud()

template<class PointT >
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.

◆ normalizeHistogram()

void jsk_recognition_utils::normalizeHistogram ( std::vector< float > &  histogram)
inline

Definition at line 121 of file color_histogram.h.

◆ operator<<() [1/2]

std::ostream& jsk_recognition_utils::operator<< ( std::ostream &  os,
const PolyLine pl 
)

Definition at line 166 of file polyline.cpp.

◆ operator<<() [2/2]

std::ostream& jsk_recognition_utils::operator<< ( std::ostream &  os,
const Segment seg 
)

Definition at line 102 of file segment.cpp.

◆ pointCloudToVertices()

template<class PointT >
Vertices jsk_recognition_utils::pointCloudToVertices ( const pcl::PointCloud< PointT > &  cloud)

Compute Vertices from PointCloud.

Definition at line 123 of file geo_util.h.

◆ pointFromVectorToVector()

template<class FromT , class ToT >
void jsk_recognition_utils::pointFromVectorToVector ( const FromT &  from,
ToT &  to 
)

Definition at line 94 of file pcl_conversion_util.h.

◆ pointFromVectorToXYZ()

template<class FromT , class ToT >
void jsk_recognition_utils::pointFromVectorToXYZ ( const FromT &  p,
ToT &  msg 
)

Definition at line 80 of file pcl_conversion_util.h.

◆ pointFromXYZToVector()

template<class FromT , class ToT >
void jsk_recognition_utils::pointFromXYZToVector ( const FromT &  msg,
ToT &  p 
)

Definition at line 73 of file pcl_conversion_util.h.

◆ pointFromXYZToXYZ()

template<class FromT , class ToT >
void jsk_recognition_utils::pointFromXYZToXYZ ( const FromT &  from,
ToT &  to 
)

Definition at line 87 of file pcl_conversion_util.h.

◆ project3DPointstoPixel()

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.

◆ project3DPointToPixel()

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 83 of file sensor_model_utils.h.

◆ publishPointIndices()

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 73 of file pcl_ros_util.cpp.

◆ randomGaussian()

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 73 of file random_util.cpp.

◆ randomUniform()

double jsk_recognition_utils::randomUniform ( double  min,
double  max,
boost::mt19937 &  gen 
)

Return a random value according to uniform distribution.

Definition at line 87 of file random_util.cpp.

◆ rangeImageToCvMat()

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.

Parameters
range_imageinstance of pcl::RangeImage
matinstance of cv::Mat, converted cv::Mat is set into this argument.

Definition at line 74 of file pcl_conversion_util.cpp.

◆ rotateHistogram1d()

void jsk_recognition_utils::rotateHistogram1d ( const std::vector< float > &  input,
std::vector< float > &  output,
const double  degree 
)
inline

Definition at line 189 of file color_histogram.h.

◆ rotateHistogram2d()

void jsk_recognition_utils::rotateHistogram2d ( const std::vector< float > &  input,
std::vector< float > &  output,
const double  degree 
)
inline

Definition at line 208 of file color_histogram.h.

◆ rotFrom3Axis()

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.

◆ sortHistogramWithRangeBinArray()

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 126 of file cv_utils.cpp.

◆ subIndices() [1/2]

pcl::PointIndices::Ptr jsk_recognition_utils::subIndices ( const pcl::PointIndices &  a,
const pcl::PointIndices &  b 
)

Definition at line 126 of file pcl_util.cpp.

◆ subIndices() [2/2]

std::vector< int > jsk_recognition_utils::subIndices ( const std::vector< int > &  a,
const std::vector< int > &  b 
)

Definition at line 113 of file pcl_util.cpp.

◆ topNHistogramWithRangeBins()

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 132 of file cv_utils.cpp.

◆ verticesToPointCloud()

template<class PointT >
pcl::PointCloud<PointT>::Ptr jsk_recognition_utils::verticesToPointCloud ( const Vertices v)

Compute PointCloud from Vertices.

Definition at line 102 of file geo_util.h.

Variable Documentation

◆ _chainer_available

bool jsk_recognition_utils._chainer_available = True
private

Definition at line 16 of file __init__.py.

◆ _chainercv_available

bool jsk_recognition_utils._chainercv_available = True
private

Definition at line 22 of file __init__.py.

◆ _depends

list jsk_recognition_utils._depends = []
private

Definition at line 35 of file __init__.py.

◆ _fcn_available

bool jsk_recognition_utils._fcn_available = True
private

Definition at line 28 of file __init__.py.

◆ BagOfFeatures

jsk_recognition_utils.BagOfFeatures = feature.BagOfFeatures

Definition at line 68 of file __init__.py.

◆ bounding_box_msg_to_aabb

jsk_recognition_utils.bounding_box_msg_to_aabb = conversations.bounding_box_msg_to_aabb

Definition at line 65 of file __init__.py.

◆ bounding_rect_of_mask

jsk_recognition_utils.bounding_rect_of_mask = mask.bounding_rect_of_mask

Definition at line 71 of file __init__.py.

◆ centerize

jsk_recognition_utils.centerize = visualize.centerize

Definition at line 74 of file __init__.py.

◆ colorize_cluster_indices

jsk_recognition_utils.colorize_cluster_indices = visualize.colorize_cluster_indices

Definition at line 75 of file __init__.py.

◆ decompose_descriptors_with_label

jsk_recognition_utils.decompose_descriptors_with_label = feature.decompose_descriptors_with_label

Definition at line 69 of file __init__.py.

◆ descent_closing

jsk_recognition_utils.descent_closing = mask.descent_closing

Definition at line 72 of file __init__.py.

◆ file

jsk_recognition_utils.file

Definition at line 47 of file __init__.py.

◆ get_overlap_of_aabb

jsk_recognition_utils.get_overlap_of_aabb = geometry.get_overlap_of_aabb

Definition at line 78 of file __init__.py.

◆ get_tile_image

jsk_recognition_utils.get_tile_image = visualize.get_tile_image

Definition at line 76 of file __init__.py.

◆ global_chull_mutex

boost::mutex jsk_recognition_utils::global_chull_mutex

Definition at line 75 of file pcl_util.cpp.

◆ rects_msg_to_ndarray

jsk_recognition_utils.rects_msg_to_ndarray = conversations.rects_msg_to_ndarray

Definition at line 66 of file __init__.py.



jsk_recognition_utils
Author(s):
autogenerated on Tue Jan 7 2025 04:04:52