#include <parameter_space_hierarchy.h>
Public Types | |
typedef but_plane_detector::Plane < float > | tPlane |
typedef std::vector< tPlane, Eigen::aligned_allocator < tPlane > > | tPlanes |
Public Member Functions | |
void | addVolume (ParameterSpace &second, int angle1, int angle2, int shift) |
void | addVolume (ParameterSpace &second, int angle1, int angle2, int shift, float factor) |
void | clear () |
int | findMaxima (tPlanes &indices, double min_value, int neighborhood, int around) |
void | fromIndex (int bin_index, int inside_index, int &angle1, int &angle2, int &z) |
double | get (int angle1, int angle2, int z) |
double | get (int bin_index, int inside_index) |
double | get (double angle1, double angle2, double z) |
double | getAngle (int index) |
IndexStruct | getIndex (double angle1, double angle2, double z) |
IndexStruct | getIndex (int angle1, int angle2, int z) |
void | getIndex (double angle1, double angle2, double z, int &angle1Index, int &angle2Index, int &shiftIndex) |
double | getShift (int irndex) |
int | getSize () |
ParameterSpaceHierarchy (double anglemin, double anglemax, double zmin, double zmax, double angleRes=DEFAULT_ANGLE_STEP, double shiftRes=DEFAULT_SHIFT_STEP) | |
void | set (int angle1, int angle2, int z, double val) |
void | set (int bin_index, int inside_index, double val) |
void | set (double angle1, double angle2, double z, double val) |
~ParameterSpaceHierarchy () | |
Static Public Member Functions | |
static void | toAngles (float x, float y, float z, float &a1, float &a2) |
static void | toEuklid (float a1, float a2, float &x, float &y, float &z) |
Public Attributes | |
int | m_angleLoSize |
int | m_angleLoSize2 |
double | m_angleLoStep |
double | m_anglemax |
double | m_anglemin |
int | m_angleSize |
int | m_angleSize2 |
double | m_angleStep |
double ** | m_dataLowRes |
int | m_hiSize |
int | m_hiSize2 |
bool | m_init |
int | m_loSize |
cv::Mat | m_paramSpace |
int | m_shiftLoSize |
double | m_shiftLoStep |
double | m_shiftmax |
double | m_shiftmin |
int | m_shiftSize |
double | m_shiftStep |
int | m_size |
Class encapsulating a Hough parameter space - (angle, angle, shift) Structure is 2 level hierarchic
Definition at line 80 of file parameter_space_hierarchy.h.
Definition at line 83 of file parameter_space_hierarchy.h.
typedef std::vector<tPlane, Eigen::aligned_allocator<tPlane> > srs_env_model_percp::ParameterSpaceHierarchy::tPlanes |
Definition at line 84 of file parameter_space_hierarchy.h.
ParameterSpaceHierarchy::ParameterSpaceHierarchy | ( | double | anglemin, |
double | anglemax, | ||
double | zmin, | ||
double | zmax, | ||
double | angleRes = DEFAULT_ANGLE_STEP , |
||
double | shiftRes = DEFAULT_SHIFT_STEP |
||
) |
Constructor - creates and allocates a space (angle X angle X shift)
anglemin | Minimal angle in space |
anglemax | Maximal angle in space |
zmin | Minimal shift in space |
zmax | Maximal shift in space |
angleRes | Angle resolution (step) |
shiftRes | Shift resolution (step) |
Definition at line 52 of file parameter_space_hierarchy.cpp.
Destructor
Definition at line 88 of file parameter_space_hierarchy.cpp.
void ParameterSpaceHierarchy::addVolume | ( | ParameterSpace & | second, |
int | angle1, | ||
int | angle2, | ||
int | shift | ||
) |
Adds a second volume to this with offset
second | Second volume to be added |
angle1 | Angle 1 offset |
angle2 | Angle 2 offset |
shift | Shift offset |
Definition at line 286 of file parameter_space_hierarchy.cpp.
void ParameterSpaceHierarchy::addVolume | ( | ParameterSpace & | second, |
int | angle1, | ||
int | angle2, | ||
int | shift, | ||
float | factor | ||
) |
Adds a second volume to this with offset and multiplied by given factor
second | Second volume to be added |
angle1 | Angle 1 offset |
angle2 | Angle 2 offset |
shift | Shift offset |
factor | number by which each gauss function will be multiplied |
Definition at line 316 of file parameter_space_hierarchy.cpp.
void ParameterSpaceHierarchy::clear | ( | void | ) |
Definition at line 96 of file parameter_space_hierarchy.cpp.
int ParameterSpaceHierarchy::findMaxima | ( | tPlanes & | indices, |
double | min_value, | ||
int | neighborhood, | ||
int | around | ||
) |
Finds maximas in this and saves them as planes to given vector
indices | Found planes |
Definition at line 342 of file parameter_space_hierarchy.cpp.
void ParameterSpaceHierarchy::fromIndex | ( | int | bin_index, |
int | inside_index, | ||
int & | angle1, | ||
int & | angle2, | ||
int & | z | ||
) |
Converts an index into axis coordinates
i | Given index |
angle1 | First angle coordinate |
angle2 | Second angle coordinate |
z | Shift (d param) coordinate |
Definition at line 227 of file parameter_space_hierarchy.cpp.
double ParameterSpaceHierarchy::get | ( | int | angle1, |
int | angle2, | ||
int | z | ||
) |
Returns a value saved at given coordinates (indices)
angle1 | First angle coordinate |
angle2 | Second angle coordinate |
z | Shift (d param) coordinate |
Definition at line 144 of file parameter_space_hierarchy.cpp.
double ParameterSpaceHierarchy::get | ( | int | bin_index, |
int | inside_index | ||
) |
Returns a value saved at given index
index | Given index |
Definition at line 179 of file parameter_space_hierarchy.cpp.
double ParameterSpaceHierarchy::get | ( | double | angle1, |
double | angle2, | ||
double | z | ||
) |
Returns a value saved at given values
angle1 | First angle value |
angle2 | Second angle value |
z | Shift (d param) value |
Definition at line 483 of file parameter_space_hierarchy.cpp.
double ParameterSpaceHierarchy::getAngle | ( | int | index | ) |
Converts index in parameter space into angle value
index | Angle axis index |
Definition at line 452 of file parameter_space_hierarchy.cpp.
IndexStruct ParameterSpaceHierarchy::getIndex | ( | double | angle1, |
double | angle2, | ||
double | z | ||
) |
Returns an index from given values
angle1 | First angle value |
angle2 | Second angle value |
z | Shift (d param) value |
Definition at line 208 of file parameter_space_hierarchy.cpp.
IndexStruct ParameterSpaceHierarchy::getIndex | ( | int | angle1, |
int | angle2, | ||
int | z | ||
) |
Returns an index from given coordinate indices
angle1 | First angle coordinate |
angle2 | Second angle coordinate |
z | Shift (d param) coordinate |
Definition at line 253 of file parameter_space_hierarchy.cpp.
void ParameterSpaceHierarchy::getIndex | ( | double | angle1, |
double | angle2, | ||
double | z, | ||
int & | angle1Index, | ||
int & | angle2Index, | ||
int & | shiftIndex | ||
) |
Converts between values and coordinates
angle1 | First angle value |
angle2 | Second angle value |
z | Shift (d param) value |
angle1Index | First angle coordinate |
angle2Index | Second angle coordinate |
shiftIndex | (d param) coordinate |
Definition at line 272 of file parameter_space_hierarchy.cpp.
double ParameterSpaceHierarchy::getShift | ( | int | irndex | ) |
Converts index in parameter space into shift value
index | Shift axis index |
Definition at line 461 of file parameter_space_hierarchy.cpp.
int ParameterSpaceHierarchy::getSize | ( | ) |
Returns a size of this space structure in Bytes
Definition at line 469 of file parameter_space_hierarchy.cpp.
void ParameterSpaceHierarchy::set | ( | int | angle1, |
int | angle2, | ||
int | z, | ||
double | val | ||
) |
Saves a value at given coordinates (indices)
angle1 | First angle coordinate |
angle2 | Second angle coordinate |
z | Shift (d param) coordinate |
val | Value to be saved |
Definition at line 164 of file parameter_space_hierarchy.cpp.
void ParameterSpaceHierarchy::set | ( | int | bin_index, |
int | inside_index, | ||
double | val | ||
) |
Saves a value at given index
index | Given index |
val | Value to be saved |
Definition at line 192 of file parameter_space_hierarchy.cpp.
void ParameterSpaceHierarchy::set | ( | double | angle1, |
double | angle2, | ||
double | z, | ||
double | val | ||
) |
Saves a value at given values
angle1 | First angle value |
angle2 | Second angle value |
z | Shift (d param) value |
val | Value to be saved |
Definition at line 500 of file parameter_space_hierarchy.cpp.
void ParameterSpaceHierarchy::toAngles | ( | float | x, |
float | y, | ||
float | z, | ||
float & | a1, | ||
float & | a2 | ||
) | [static] |
Conversion from Euclidian representation of normal (x, y, z) to parametrized (a1, a2)
x | X vector coordinate |
y | Y vector coordinate |
z | Z vector coordinate |
a1 | First angle |
a2 | Second angle |
Definition at line 114 of file parameter_space_hierarchy.cpp.
void ParameterSpaceHierarchy::toEuklid | ( | float | a1, |
float | a2, | ||
float & | x, | ||
float & | y, | ||
float & | z | ||
) | [static] |
Conversion from parametrized representation of normal (a1, a2) to Euclidian (x, y, z)
x | X vector coordinate |
y | Y vector coordinate |
z | Z vector coordinate |
a1 | First angle |
a2 | Second angle |
Definition at line 130 of file parameter_space_hierarchy.cpp.
Low resolution angle axis size
Definition at line 324 of file parameter_space_hierarchy.h.
Low resolution angle axis size ^ 2
Definition at line 329 of file parameter_space_hierarchy.h.
Step of one low resolution angle coordinate
Definition at line 269 of file parameter_space_hierarchy.h.
Maximal shift value
Definition at line 294 of file parameter_space_hierarchy.h.
Minimal angle value
Definition at line 289 of file parameter_space_hierarchy.h.
Size of angle axis
Definition at line 309 of file parameter_space_hierarchy.h.
Size of angle axis ^ 2
Definition at line 314 of file parameter_space_hierarchy.h.
Step of one angle coordinage
Definition at line 259 of file parameter_space_hierarchy.h.
Pointer to the low resolution structure
Definition at line 354 of file parameter_space_hierarchy.h.
High resolution space size
Definition at line 339 of file parameter_space_hierarchy.h.
High resolution space size ^ 2
Definition at line 344 of file parameter_space_hierarchy.h.
Initialized flag
Definition at line 254 of file parameter_space_hierarchy.h.
Size of low reslution array
Definition at line 304 of file parameter_space_hierarchy.h.
Param space matrix
Definition at line 349 of file parameter_space_hierarchy.h.
Low resolution shift axis size
Definition at line 334 of file parameter_space_hierarchy.h.
Step of one low resolution shift coordinate
Definition at line 274 of file parameter_space_hierarchy.h.
Maximal shift value
Definition at line 284 of file parameter_space_hierarchy.h.
Minimal shift value
Definition at line 279 of file parameter_space_hierarchy.h.
Shift axis size
Definition at line 319 of file parameter_space_hierarchy.h.
Step of one shift coordinate
Definition at line 264 of file parameter_space_hierarchy.h.
Size of underlying structure
Definition at line 299 of file parameter_space_hierarchy.h.