Classes | Typedefs | Functions | Variables
swri_image_util Namespace Reference

Classes

class  BlendImagesNodelet
class  ContrastStretchNodelet
class  CrosshairsNodelet
class  DrawTextNodelet
class  NormalizeResponseNodelet
class  PitchAndRollEstimator
 A class for estimating image warping based on perspective distortion. Primarily intended for use with downward-facing camera methods. More...
class  PitchAndRollEstimatorQueue
 A class for estimating image warping based on perspective distortion. Primarily intended for use with downward-facing camera methods. More...
class  ReplaceColorsNodelet
class  RollingNormalization
class  RotateImageNodelet
class  ScaleImageNodelet
class  WarpImageNodelet

Typedefs

typedef cv::Rect_< double > BoundingBox

Functions

void blendImages (const cv::Mat &base_image, const cv::Mat &top_image, const double alpha, cv::Mat &dest_image)
void blendImages (const cv::Mat &base_image, const cv::Mat &top_image, const double alpha, const cv::Scalar mask_color, cv::Mat &dest_image)
void ContrastStretch (int32_t grid_size, const cv::Mat &source_image, cv::Mat &dest_image, const cv::Mat &mask=cv::Mat(), double max_min=0.0, double min_max=0.0)
void ConvertMatches (const std::vector< cv::KeyPoint > &kp1, const std::vector< cv::KeyPoint > &kp2, const std::vector< cv::DMatch > &matches, cv::Mat &kp1_out, cv::Mat &kp2_out)
 Converts keypoints and matches into two cv::Mats in which the the matching keypoints from kp1 and kp2 are ordered in the same manner.
void DrawMatches (cv::Mat &image_out, const cv::Mat image1, const cv::Mat image2, const cv::Mat points1, const cv::Mat points2, const cv::Scalar &color=cv::Scalar::all(-1), bool draw_image_borders=false)
void DrawMatches (const std::string &title, const cv::Mat image1, const cv::Mat image2, const cv::Mat points1, const cv::Mat points2, const cv::Scalar &color=cv::Scalar::all(-1), bool draw_image_borders=false)
void DrawMatches (const std::string &title, const cv::Mat image, const cv::Mat points1, const cv::Mat points2, const cv::Scalar &color1, const cv::Scalar &color2, bool draw_image_borders=false)
void DrawOverlap (const std::string &title, const cv::Mat &image1, const cv::Mat &image2, const cv::Mat &transform)
cv::Mat generate_normalization_image (const std::vector< cv::Mat > &image_list)
 Computes a best estimate of a normalization image from a vector of images.
std::vector< tf::Vector3GetEllipsePoints (const cv::Mat &ellipse, const tf::Vector3 &center, double scale, int32_t num_points)
void GetFundamentalInliers (const cv::Mat points1, const cv::Mat points2, cv::Mat &fundamental_matrix, cv::Mat &inliers1, cv::Mat &inliers2, double max_distance=1.0, double confidence=0.99)
 Computes the fundamental matrix for a set of matching points in two different images. The method also returns the inlier keypoints for both frames.
void GetFundamentalInliers (const cv::Mat points1, const cv::Mat points2, cv::Mat &fundamental_matrix, cv::Mat &inliers1, cv::Mat &inliers2, std::vector< uint32_t > &indices, double max_distance=1.0, double confidence=0.99)
 Computes the fundamental matrix for a set of matching points in two different images. The method also returns the inlier keypoints for both frames.
double GetOverlappingArea (const cv::Rect &rect, const cv::Mat &rigid_transform)
cv::Mat GetR (double pitch, double roll, double yaw=0.0)
 Gets the rotation matrix associated with the specified pitch and roll values.
bool Intersects (const BoundingBox &box1, const BoundingBox &box2)
void JetColorMap (unsigned char &r, unsigned char &g, unsigned char &b, float value, float min, float max)
 Map a scalar value to a color gradient.
void MaskedBoxFilter (cv::Mat &mat, cv::Mat &mask, int32_t kernel_size)
void normalize_illumination (cv::Mat NormImage, cv::Mat SourceImage, cv::Mat &DestImage)
void NormalizeResponse (const cv::Mat &src, cv::Mat &dst, int winsize, int ftzero, uchar *buf)
cv::Mat ProjectEllipsoid (const cv::Mat &ellipsiod)
void RandomColor (int32_t seed, double &r, double &g, double &b)
void replaceColors (const cv::Mat &original_image, const cv::Mat &lut, cv::Mat &modified_image)
cv::Mat scale_2_8bit (const cv::Mat &image)
 Convert the input Mat to 8 bit.
cv::Mat scale_2_8bit_color (const cv::Mat &image)
 Convert the input Mat to 8 bit color.
cv::Mat WarpImage (const cv::Mat &image, double roll, double pitch)
void WarpPoints (double pitch, double roll, const cv::Size &image_size, const cv::Mat &pts_in, cv::Mat &pts_out)
void WarpPoints (double pitch, double roll, const cv::Size &image_size, const std::vector< cv::KeyPoint > &pts_in, std::vector< cv::KeyPoint > &pts_out)

Variables

const double DEFAULT_ALPHA_LEVEL = 0.5
const int32_t MAX_RGB_VALUE = 255
const cv::Scalar NO_MASK = cv::Scalar(-1, -1, -1)
const int32_t NUM_GRAY_VALUES = 256

Typedef Documentation

typedef cv::Rect_<double> swri_image_util::BoundingBox

Definition at line 31 of file geometry_util.h.


Function Documentation

void swri_image_util::blendImages ( const cv::Mat &  base_image,
const cv::Mat &  top_image,
const double  alpha,
cv::Mat &  dest_image 
)

Blends two images together. top_image will be drawn on top of base_image with a blending level of alpha. The blended image will be placed in dest_image

Definition at line 35 of file blend_images_util.cpp.

void swri_image_util::blendImages ( const cv::Mat &  base_image,
const cv::Mat &  top_image,
const double  alpha,
const cv::Scalar  mask_color,
cv::Mat &  dest_image 
)

Blends two images together. top_image will be drawn on top of base_image with a blending level of alpha. The color mask_color will be made transparent in the top_image. The blended image will be placed in dest_image

Definition at line 71 of file blend_images_util.cpp.

void swri_image_util::ContrastStretch ( int32_t  grid_size,
const cv::Mat &  source_image,
cv::Mat &  dest_image,
const cv::Mat &  mask = cv::Mat(),
double  max_min = 0.0,
double  min_max = 0.0 
)

Normalizes the illumination in an image using contrast stretching.

Parameters:
[in]grid_sizeThe grid size to normalize on
[in]source_imageThe image to normalize
[out]dest_imageThe resulting normalized image

Definition at line 135 of file image_normalization.cpp.

void swri_image_util::ConvertMatches ( const std::vector< cv::KeyPoint > &  kp1,
const std::vector< cv::KeyPoint > &  kp2,
const std::vector< cv::DMatch > &  matches,
cv::Mat &  kp1_out,
cv::Mat &  kp2_out 
)

Converts keypoints and matches into two cv::Mats in which the the matching keypoints from kp1 and kp2 are ordered in the same manner.

Parameters:
[in]kp1The first set of keypoints
[in]kp2The second set of keypoints
[in]matchesThe vector of matches
[out]kp1_outThe first set of matching keypoints output as a Mat
[out]kp2_outThe second set of matching keypoints output as a Mat

Definition at line 109 of file image_matching.cpp.

void swri_image_util::DrawMatches ( cv::Mat &  image_out,
const cv::Mat  image1,
const cv::Mat  image2,
const cv::Mat  points1,
const cv::Mat  points2,
const cv::Scalar &  color = cv::Scalar::all(-1),
bool  draw_image_borders = false 
)

Definition at line 127 of file draw_util.cpp.

void swri_image_util::DrawMatches ( const std::string &  title,
const cv::Mat  image1,
const cv::Mat  image2,
const cv::Mat  points1,
const cv::Mat  points2,
const cv::Scalar &  color = cv::Scalar::all(-1),
bool  draw_image_borders = false 
)

Definition at line 195 of file draw_util.cpp.

void swri_image_util::DrawMatches ( const std::string &  title,
const cv::Mat  image,
const cv::Mat  points1,
const cv::Mat  points2,
const cv::Scalar &  color1,
const cv::Scalar &  color2,
bool  draw_image_borders = false 
)

Definition at line 216 of file draw_util.cpp.

void swri_image_util::DrawOverlap ( const std::string &  title,
const cv::Mat &  image1,
const cv::Mat &  image2,
const cv::Mat &  transform 
)

Definition at line 106 of file draw_util.cpp.

cv::Mat swri_image_util::generate_normalization_image ( const std::vector< cv::Mat > &  image_list)

Computes a best estimate of a normalization image from a vector of images.

Parameters:
[in]image_listA vector of images -- it is best to have a diversity of images in this list.
Return values:
Returnsthe normalization image

Definition at line 54 of file image_normalization.cpp.

std::vector< tf::Vector3 > swri_image_util::GetEllipsePoints ( const cv::Mat &  ellipse,
const tf::Vector3 center,
double  scale,
int32_t  num_points 
)

Gets a list of points on the perimeter of an ellipse.

Parameters:
[in]ellipseThe ellipse represented as a 2x2 float matrix.
[in]centerThe center of the ellipse.
[in]scaleA scale factor.
[in]num_pointsThe number of points to use.
Returns:
A list of points on the perimeter of the ellipse if successful. An empty list otherwise.

Definition at line 195 of file geometry_util.cpp.

void swri_image_util::GetFundamentalInliers ( const cv::Mat  points1,
const cv::Mat  points2,
cv::Mat &  fundamental_matrix,
cv::Mat &  inliers1,
cv::Mat &  inliers2,
double  max_distance = 1.0,
double  confidence = 0.99 
)

Computes the fundamental matrix for a set of matching points in two different images. The method also returns the inlier keypoints for both frames.

Parameters:
[in]points1The keypoints for the first image
[in]points2The matching keypoints for a second image
[out]fundamental_matrixThe computed fundamental matrix
[out]inliers1The inlier keypoints from the first set
[out]inliers2The inlier keypoints from the second set
[in]max_distanceThe maximum allowable distance (in pixels) from the computed epipolar line
[in]confidenceThe confidence level (which affects the number of iterations)

Definition at line 43 of file image_matching.cpp.

void swri_image_util::GetFundamentalInliers ( const cv::Mat  points1,
const cv::Mat  points2,
cv::Mat &  fundamental_matrix,
cv::Mat &  inliers1,
cv::Mat &  inliers2,
std::vector< uint32_t > &  indices,
double  max_distance = 1.0,
double  confidence = 0.99 
)

Computes the fundamental matrix for a set of matching points in two different images. The method also returns the inlier keypoints for both frames.

Parameters:
[in]points1The keypoints for the first image
[in]points2The matching keypoints for a second image
[out]fundamental_matrixThe computed fundamental matrix
[out]inliers1The inlier keypoints from the first set
[out]inliers2The inlier keypoints from the second set
[out]indicesThe indices of the inlier keypoints
[in]max_distanceThe maximum allowable distance (in pixels) from the computed epipolar line
[in]confidenceThe confidence level (which affects the number of iterations)

Definition at line 61 of file image_matching.cpp.

double swri_image_util::GetOverlappingArea ( const cv::Rect &  rect,
const cv::Mat &  rigid_transform 
)

Calculate the overlapping area of a rectangle an a rigidly transformed version of itself.

Parameters:
[in]rectThe rectangle.
[in]rigid_transformThe rigid transform.
Returns:
The area of intersection of the two rectangles.

Definition at line 51 of file geometry_util.cpp.

cv::Mat swri_image_util::GetR ( double  pitch,
double  roll,
double  yaw = 0.0 
)

Gets the rotation matrix associated with the specified pitch and roll values.

Parameters:
[in]pitchThe pitch value
[in]rollThe roll value
[in]yawThe yaw value (default = 0.0);
Return values:
Returnsthe appropriately formatted rotation matrix

Definition at line 116 of file image_warp_util.cpp.

bool swri_image_util::Intersects ( const BoundingBox &  box1,
const BoundingBox &  box2 
)

Determine if two aligned rectangles intersect one another.

Parameters:
[in]box1The first rectangle.
[in]box2The second rectangle.
Returns:
True if box1 intersects with box2. False otherwise.

Definition at line 46 of file geometry_util.cpp.

void swri_image_util::JetColorMap ( unsigned char &  r,
unsigned char &  g,
unsigned char &  b,
float  value,
float  min,
float  max 
)

Map a scalar value to a color gradient.

Return a color gradient RGB value by mapping an input value to a specified scale.

Parameters:
[out]rRed channel of the output gradient color.
[out]gGreen channel of the output gradient color.
[out]bBlue channel of the output gradient color.
[in]valueThe input value to be mapped to a color.
[in]minThe minimum value on the gradient scale.
[in]maxThe maximum value on the gradient scale.

Definition at line 53 of file draw_util.cpp.

void swri_image_util::MaskedBoxFilter ( cv::Mat &  mat,
cv::Mat &  mask,
int32_t  kernel_size 
)

Definition at line 111 of file image_normalization.cpp.

void swri_image_util::normalize_illumination ( cv::Mat  NormImage,
cv::Mat  SourceImage,
cv::Mat &  DestImage 
)

Normalizes the illumination in an image using a normalization image as a template

Parameters:
[in]NormImageA normalization image
[in]SourceImageThe image to normalize
[out]DestImageThe resulting normalized image

Definition at line 40 of file image_normalization.cpp.

void swri_image_util::NormalizeResponse ( const cv::Mat &  src,
cv::Mat &  dst,
int  winsize,
int  ftzero,
uchar *  buf 
)

Normalizes the illumination in an image using approach from OpenCV's stereo block matching.

Definition at line 236 of file image_normalization.cpp.

cv::Mat swri_image_util::ProjectEllipsoid ( const cv::Mat &  ellipsiod)

Projects a 3D ellipsoid to an ellipse on the XY-plane.

Parameters:
[in]ellipsoidThe ellipsoid represented as a 3x3 float matrix.
Returns:
The ellipse as a 2x2 float matrix if successful. An empty matrix otherwise.

Definition at line 73 of file geometry_util.cpp.

void swri_image_util::RandomColor ( int32_t  seed,
double &  r,
double &  g,
double &  b 
)

Definition at line 44 of file draw_util.cpp.

void swri_image_util::replaceColors ( const cv::Mat &  original_image,
const cv::Mat &  lut,
cv::Mat &  modified_image 
)

Replaces the colors in original_image with the values from the look up table in lut. The modified image is stored in modified_image

Definition at line 37 of file replace_colors.cpp.

cv::Mat swri_image_util::scale_2_8bit ( const cv::Mat &  image)

Convert the input Mat to 8 bit.

Parameters:
[in]imageThe input image
Returns:
The 8-bit Mat.

Definition at line 320 of file image_normalization.cpp.

cv::Mat swri_image_util::scale_2_8bit_color ( const cv::Mat &  image)

Convert the input Mat to 8 bit color.

Parameters:
[in]imageThe input image
Returns:
The 8-bit color Mat.

Definition at line 336 of file image_normalization.cpp.

cv::Mat swri_image_util::WarpImage ( const cv::Mat &  image,
double  roll,
double  pitch 
)

Definition at line 37 of file image_warp_util.cpp.

void swri_image_util::WarpPoints ( double  pitch,
double  roll,
const cv::Size &  image_size,
const cv::Mat &  pts_in,
cv::Mat &  pts_out 
)

Warps a matrix of points (in the same form as the inliers)

Parameters:
[in]pitchThe pitch used to warp the point
[in]rollThe roll used to warp the point
[in]image_sizeThe size of the (unwarped) image
[in]pts_inThe points to warp
[out]pts_outThe warped points

Definition at line 60 of file image_warp_util.cpp.

void swri_image_util::WarpPoints ( double  pitch,
double  roll,
const cv::Size &  image_size,
const std::vector< cv::KeyPoint > &  pts_in,
std::vector< cv::KeyPoint > &  pts_out 
)

Warps a matrix of points (in the same form as the inliers)

Parameters:
[in]pitchThe pitch used to warp the point
[in]rollThe roll used to warp the point
[in]image_sizeThe size of the (unwarped) image
[in]pts_inThe points to warp
[out]pts_outThe warped points

Definition at line 88 of file image_warp_util.cpp.


Variable Documentation

Definition at line 44 of file blend_images_nodelet.cpp.

const int32_t swri_image_util::MAX_RGB_VALUE = 255

Definition at line 50 of file replace_colors_nodelet.cpp.

const cv::Scalar swri_image_util::NO_MASK = cv::Scalar(-1, -1, -1)

Definition at line 45 of file blend_images_nodelet.cpp.

const int32_t swri_image_util::NUM_GRAY_VALUES = 256

Definition at line 47 of file replace_colors_nodelet.cpp.



swri_image_util
Author(s): Kris Kozak
autogenerated on Tue Oct 3 2017 03:19:34