Classes | |
class | BlendImagesNodelet |
class | ContrastStretchNodelet |
class | CrosshairsNodelet |
class | DrawPolygonNodelet |
class | DrawTextNodelet |
class | ImagePubNodelet |
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 | 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. More... | |
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. More... | |
std::vector< tf::Vector3 > | GetEllipsePoints (const cv::Mat &ellipse, const tf::Vector3 ¢er, 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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
cv::Mat | scale_2_8bit_color (const cv::Mat &image) |
Convert the input Mat to 8 bit color. More... | |
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 cv::Rect_<double> swri_image_util::BoundingBox |
Definition at line 31 of file geometry_util.h.
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.
[in] | grid_size | The grid size to normalize on |
[in] | source_image | The image to normalize |
[out] | dest_image | The 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.
[in] | kp1 | The first set of keypoints |
[in] | kp2 | The second set of keypoints |
[in] | matches | The vector of matches |
[out] | kp1_out | The first set of matching keypoints output as a Mat |
[out] | kp2_out | The 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 196 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 217 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.
[in] | image_list | A vector of images – it is best to have a diversity of images in this list. |
Returns | the 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.
[in] | ellipse | The ellipse represented as a 2x2 float matrix. |
[in] | center | The center of the ellipse. |
[in] | scale | A scale factor. |
[in] | num_points | The number of points to use. |
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.
[in] | points1 | The keypoints for the first image |
[in] | points2 | The matching keypoints for a second image |
[out] | fundamental_matrix | The computed fundamental matrix |
[out] | inliers1 | The inlier keypoints from the first set |
[out] | inliers2 | The inlier keypoints from the second set |
[in] | max_distance | The maximum allowable distance (in pixels) from the computed epipolar line |
[in] | confidence | The 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.
[in] | points1 | The keypoints for the first image |
[in] | points2 | The matching keypoints for a second image |
[out] | fundamental_matrix | The computed fundamental matrix |
[out] | inliers1 | The inlier keypoints from the first set |
[out] | inliers2 | The inlier keypoints from the second set |
[out] | indices | The indices of the inlier keypoints |
[in] | max_distance | The maximum allowable distance (in pixels) from the computed epipolar line |
[in] | confidence | The 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.
[in] | rect | The rectangle. |
[in] | rigid_transform | The rigid transform. |
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.
[in] | pitch | The pitch value |
[in] | roll | The roll value |
[in] | yaw | The yaw value (default = 0.0); |
Returns | the 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.
[in] | box1 | The first rectangle. |
[in] | box2 | The second rectangle. |
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.
[out] | r | Red channel of the output gradient color. |
[out] | g | Green channel of the output gradient color. |
[out] | b | Blue channel of the output gradient color. |
[in] | value | The input value to be mapped to a color. |
[in] | min | The minimum value on the gradient scale. |
[in] | max | The 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
[in] | NormImage | A normalization image |
[in] | SourceImage | The image to normalize |
[out] | DestImage | The 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 289 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.
[in] | ellipsoid | The ellipsoid represented as a 3x3 float matrix. |
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.
[in] | image | The input image |
Definition at line 373 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.
[in] | image | The input image |
Definition at line 389 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)
[in] | pitch | The pitch used to warp the point |
[in] | roll | The roll used to warp the point |
[in] | image_size | The size of the (unwarped) image |
[in] | pts_in | The points to warp |
[out] | pts_out | The 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)
[in] | pitch | The pitch used to warp the point |
[in] | roll | The roll used to warp the point |
[in] | image_size | The size of the (unwarped) image |
[in] | pts_in | The points to warp |
[out] | pts_out | The warped points |
Definition at line 88 of file image_warp_util.cpp.
const double swri_image_util::DEFAULT_ALPHA_LEVEL = 0.5 |
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.