#include <scene_model.h>
Public Types | |
typedef but_plane_detector::Plane < float > | tPlane |
typedef std::vector< tPlane, Eigen::aligned_allocator < tPlane > > | tPlanes |
Public Member Functions | |
void | AddNext (cv::Mat &depth, const sensor_msgs::CameraInfoConstPtr &cam_info, but_plane_detector::Normals &normals, double min_current) |
void | AddNext (but_plane_detector::Normals &normals, double min_current) |
void | clearNoise (double minValue) |
void | recomputePlanes (double min_current, double min_global, int blur, int search_neighborhood, double substraction) |
SceneModel (double max_depth=3.0, double min_shift=-40.0, double max_shift=40.0, int angle_resolution=512, int shift_resolution=4096, int gauss_angle_res=11, int gauss_shift_res=11, double gauss_angle_sigma=0.04, double gauss_shift_sigma=0.15, int lvl1_gauss_angle_res=21, int lvl1_gauss_shift_res=21, double lvl1_gauss_angle_sigma=5.0, double lvl1_gauss_shift_sigma=5.0, double plane_merge_angle=0.3, double plane_merge_shift=0.1) | |
Public Attributes | |
ParameterSpaceHierarchy | current_space |
ParameterSpace | gauss |
ParameterSpace | gaussPlane |
double | indexFactor |
double | m_angle_max |
double | m_angle_min |
int | m_angle_res |
double | m_depth |
double | m_plane_merge_angle |
double | m_plane_merge_shift |
double | m_shift_max |
double | m_shift_min |
int | m_shift_res |
int | max_plane |
tPlanes | planes |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | scene_cloud |
ParameterSpaceHierarchy | space |
Definition at line 65 of file scene_model.h.
typedef but_plane_detector::Plane<float> srs_env_model_percp::SceneModel::tPlane |
Definition at line 68 of file scene_model.h.
typedef std::vector<tPlane, Eigen::aligned_allocator<tPlane> > srs_env_model_percp::SceneModel::tPlanes |
Definition at line 69 of file scene_model.h.
srs_env_model_percp::SceneModel::SceneModel | ( | double | max_depth = 3.0 , |
double | min_shift = -40.0 , |
||
double | max_shift = 40.0 , |
||
int | angle_resolution = 512 , |
||
int | shift_resolution = 4096 , |
||
int | gauss_angle_res = 11 , |
||
int | gauss_shift_res = 11 , |
||
double | gauss_angle_sigma = 0.04 , |
||
double | gauss_shift_sigma = 0.15 , |
||
int | lvl1_gauss_angle_res = 21 , |
||
int | lvl1_gauss_shift_res = 21 , |
||
double | lvl1_gauss_angle_sigma = 5.0 , |
||
double | lvl1_gauss_shift_sigma = 5.0 , |
||
double | plane_merge_angle = 0.3 , |
||
double | plane_merge_shift = 0.1 |
||
) |
Constructor - initializes a scene and allocates necessary space - a space of (angle, angle, d) where angles are angles of plane normal and d is d parameter of plane equation.
max_depth | Maximum computed depth by each frame in meters (default 3.0) |
min_shift | Minimal d parameter value (ax + by + cz + d = 0) in Hough space (default -40.0) |
max_shift | Maximal d parameter value (ax + by + cz + d = 0) in Hough space (default 40.0) |
angle_resolution | Angle coordinates resolution (Hough space size in angle directions) (default 512) |
shift_resolution | d parameter coordinates resolution (Hough space size in angle directions) (default 4096) |
gauss_angle_res | Angle resolution of added Gauss function (default 11) |
gauss_shift_res | d parameter resolution of added Gauss function (default 11) |
gauss_angle_sigma | Sigma of added Gauss function in angle coordinates (default 11) |
gauss_shift_sigma | Sigma of added Gauss function in d parameter coordinates (default 11) |
Definition at line 58 of file scene_model.cpp.
void srs_env_model_percp::SceneModel::AddNext | ( | cv::Mat & | depth, |
const sensor_msgs::CameraInfoConstPtr & | cam_info, | ||
but_plane_detector::Normals & | normals, | ||
double | min_current | ||
) |
Function adds a depth map with computed normals into existing Hough space
depth | Depth image |
cam_info | Camera info object |
normals | Computed normals of depth image |
void srs_env_model_percp::SceneModel::AddNext | ( | but_plane_detector::Normals & | normals, |
double | min_current | ||
) |
Function adds a depth map with computed normals into existing Hough space
normals | Normals object (point cloud with precomputed normals) |
Definition at line 400 of file scene_model.cpp.
void srs_env_model_percp::SceneModel::clearNoise | ( | double | minValue | ) |
Clears all nodes with value lesser than parameter
minValue | All nodes with value lesser than this parameter will be removed |
Definition at line 379 of file scene_model.cpp.
void srs_env_model_percp::SceneModel::recomputePlanes | ( | double | min_current, |
double | min_global, | ||
int | blur, | ||
int | search_neighborhood, | ||
double | substraction | ||
) |
Function recomputes a list of planes saved in this class (scene model)
min_current | Minimal value for detected plane in current frame Hough space |
min_global | Minimal value for detected plane in global frame Hough space |
Definition at line 111 of file scene_model.cpp.
Definition at line 142 of file scene_model.h.
Cached Hough space aux Discretized Gauss function
Definition at line 152 of file scene_model.h.
Definition at line 153 of file scene_model.h.
Definition at line 163 of file scene_model.h.
Definition at line 171 of file scene_model.h.
Definition at line 170 of file scene_model.h.
Definition at line 174 of file scene_model.h.
Definition at line 168 of file scene_model.h.
Definition at line 178 of file scene_model.h.
Definition at line 177 of file scene_model.h.
Definition at line 173 of file scene_model.h.
Definition at line 172 of file scene_model.h.
Definition at line 175 of file scene_model.h.
Maximum plane index
Definition at line 158 of file scene_model.h.
Detected planes vector
Definition at line 135 of file scene_model.h.
pcl::PointCloud<pcl::PointXYZRGB>::Ptr srs_env_model_percp::SceneModel::scene_cloud |
Point cloud representation of Hough space for visualisation purposes
Definition at line 130 of file scene_model.h.
Hough space representation
Definition at line 141 of file scene_model.h.