Classes | Typedefs | Enumerations | Functions | Variables
srs_env_model_percp Namespace Reference

Classes

class  DynModelExporter
class  ExportedPlane
class  IndexStruct
class  ParameterSpace
class  ParameterSpaceHierarchy
class  ParameterSpaceHierarchyFullIterator
struct  PlaneDetectorSettings
class  PlaneExt
class  PointError
class  Polygonizer
class  SceneModel

Typedefs

typedef boost::array< int16_t, 2 > point2_t

Enumerations

enum  displayModesEnum { RGB, DEPTH }
enum  estimationModeEnum { MODE1 = 1, MODE2, MODE3 }
enum  subVariantsEnum { SV_NONE = 0, SV_1, SV_2 }

Functions

Point3f backProject (Point2i p, float z, float fx, float fy)
cv::Point3f backProject (cv::Point2i p, float z, float fx, float fy)
Scalar bbColor (255, 0, 0)
Scalar bbColorFront (0, 0, 255)
vector< Point3f > bbVertices (8)
string bbWinName ("Bounding Box")
bool calcNearAndFarFaceDepth (cv::Mat &m, float f, float *z1, float *z2)
bool calcNearAndFarFaceDepth (Mat &m, float f, float *z1, float *z2)
bool calcNearAndFarFaceDistance (cv::Mat &m, float fx, float fy, cv::Point2i roiLB, cv::Point2i roiRT, float *d1, float *d2)
bool calcNearAndFarFaceDistance (Mat &m, float fx, float fy, Point2i roiLB, Point2i roiRT, float *d1, float *d2)
bool calcStats (Mat &m, float *mean, float *stdDev)
bool calcStats (cv::Mat &m, float *mean, float *stdDev)
void callback (const sensor_msgs::ImageConstPtr &dep, const sensor_msgs::CameraInfoConstPtr &cam_info)
void callback (const sensor_msgs::ImageConstPtr &dep, const CameraInfoConstPtr &cam_info)
void callbackkinect (const sensor_msgs::ImageConstPtr &dep, const sensor_msgs::CameraInfoConstPtr &cam_info)
void callbackkinect (const sensor_msgs::ImageConstPtr &dep, const CameraInfoConstPtr &cam_info)
void callbackkinect_rgb (const sensor_msgs::ImageConstPtr &dep, const CameraInfoConstPtr &cam_info, const sensor_msgs::ImageConstPtr &rgb)
void callbackpcl (const PointCloud2ConstPtr &cloud)
void callbackpcl (const sensor_msgs::PointCloud2ConstPtr &cloud)
void callbackpcl_rgb (const PointCloud2ConstPtr &cloud, const sensor_msgs::ImageConstPtr &rgb)
bool clear (srs_env_model_percp::ClearPlanes::Request &req, srs_env_model_percp::ClearPlanes::Response &res)
bool estimate2DConvexHull (const ros::Time &stamp, const std::vector< cv::Point3f > points, std::vector< cv::Point2i > &convexHull)
void estimate2DHullMesh ()
bool estimate2DHullMesh_callback (srs_env_model_percp::Estimate2DHullMesh::Request &req, srs_env_model_percp::Estimate2DHullMesh::Response &res)
bool estimate2DHullPointCloud_callback (srs_env_model_percp::Estimate2DHullPointCloud::Request &req, srs_env_model_percp::Estimate2DHullPointCloud::Response &res)
bool estimateBB (const ros::Time &stamp, const point2_t &p1, const point2_t &p2, int mode, cv::Point3f &bbLBF, cv::Point3f &bbRBF, cv::Point3f &bbRTF, cv::Point3f &bbLTF, cv::Point3f &bbLBB, cv::Point3f &bbRBB, cv::Point3f &bbRTB, cv::Point3f &bbLTB)
bool estimateBB (const ros::Time &stamp, const point2_t &p1, const point2_t &p2, int mode, Point3f &bbLBF, Point3f &bbRBF, Point3f &bbRTF, Point3f &bbLTF, Point3f &bbLBB, Point3f &bbRBB, Point3f &bbRTB, Point3f &bbLTB)
bool estimateBB_callback (srs_env_model_percp::EstimateBB::Request &req, srs_env_model_percp::EstimateBB::Response &res)
bool estimateBBAlt_callback (srs_env_model_percp::EstimateBBAlt::Request &req, srs_env_model_percp::EstimateBBAlt::Response &res)
bool estimateBBPose (const cv::Point3f &bbLBF, const cv::Point3f &bbRBF, const cv::Point3f &bbRTF, const cv::Point3f &bbLTF, const cv::Point3f &bbLBB, const cv::Point3f &bbRBB, const cv::Point3f &bbRTB, const cv::Point3f &bbLTB, cv::Point3f &position, tf::Quaternion &orientation, cv::Point3f &scale)
bool estimateBBPose (const Point3f &bbLBF, const Point3f &bbRBF, const Point3f &bbRTF, const Point3f &bbLTF, const Point3f &bbLBB, const Point3f &bbRBB, const Point3f &bbRTB, const Point3f &bbLTB, Point3f &position, tf::Quaternion &orientation, Point3f &scale)
bool estimateRect (const ros::Time &stamp, const cv::Point3f &bbLBF, const cv::Point3f &bbRBF, const cv::Point3f &bbRTF, const cv::Point3f &bbLTF, const cv::Point3f &bbLBB, const cv::Point3f &bbRBB, const cv::Point3f &bbRTB, const cv::Point3f &bbLTB, point2_t &p1, point2_t &p2)
bool estimateRect (const ros::Time &stamp, const Point3f &bbLBF, const Point3f &bbRBF, const Point3f &bbRTF, const Point3f &bbLTF, const Point3f &bbLBB, const Point3f &bbRBB, const Point3f &bbRTB, const Point3f &bbLTB, point2_t &p1, point2_t &p2)
bool estimateRect_callback (srs_env_model_percp::EstimateRect::Request &req, srs_env_model_percp::EstimateRect::Response &res)
bool estimateRectAlt_callback (srs_env_model_percp::EstimateRectAlt::Request &req, srs_env_model_percp::EstimateRectAlt::Response &res)
Point2i fwdProject (Point3f p, float fx, float fy, float cx, float cy)
cv::Point2i fwdProject (cv::Point3f p, float fx, float fy, float cx, float cy)
bool getParams (ros::NodeHandle nh)
void getPlanes (Normals &normal, pcl::PointCloud< pcl::PointXYZ > &pointcloud, const sensor_msgs::ImageConstPtr *rgb=NULL)
string hullWinName ("Convex Hull")
string inputVideoWinName ("Input Video (use your mouse to specify a ROI)")
void kinect_proc (const sensor_msgs::ImageConstPtr &dep, const CameraInfoConstPtr &cam_info, const sensor_msgs::ImageConstPtr *rgb=NULL)
bool onLoad (srs_env_model_percp::LoadSave::Request &req, srs_env_model_percp::LoadSave::Response &res)
void onMouse (int event, int x, int y, int flags, void *param)
bool onReset (srs_env_model_percp::ResetPlanes::Request &req, srs_env_model_percp::ResetPlanes::Response &res)
bool onSave (srs_env_model_percp::LoadSave::Request &req, srs_env_model_percp::LoadSave::Response &res)
void pcl_proc (const PointCloud2ConstPtr &cloud, const sensor_msgs::ImageConstPtr *rgb=NULL)
void pcl_process (const PointCloud2ConstPtr &cloud, const sensor_msgs::ImageConstPtr *rgb=NULL)
Scalar rectColor (0, 255, 255)
vector< Point2i > rectPoints (2)
void redrawWindows ()
void scaleDepth ()
void sendRequest (Point2i p1, Point2i p2)
void setImages ()
void sv1_callback (const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &camInfo)
void sv1_processSubMsgs (const sensor_msgs::ImageConstPtr &rgb, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &camInfo)
void sv2_callback (const sensor_msgs::PointCloud2ConstPtr &pointCloud, const sensor_msgs::CameraInfoConstPtr &camInfo)
void sv2_processSubMsgs (const sensor_msgs::ImageConstPtr &rgb, const sensor_msgs::PointCloud2ConstPtr &pointCloud, const sensor_msgs::CameraInfoConstPtr &camInfo)
void visualize ()
void visualizeInImage ()
void visualizeWithMarkers ()

Variables

static const std::string BB_ESTIMATOR_PREFIX = "/bb_estimator"
ros::ServiceClient bbAddClient
ros::ServiceClient bbChangePoseClient
ros::ServiceClient bbChangeScaleClient
ros::ServiceClient bbEstimateClient
geometry_msgs::Pose bbPose
geometry_msgs::Vector3 bbScale
const int CACHE_SIZE = 10
sensor_msgs::CameraInfo cam_info_legacy
const std::string CAMERA_INFO_TOPIC_IN = "camera_info_in"
std::string camFrameId
message_filters::Cache
< CameraInfo > 
camInfoCache
sensor_msgs::PointCloud2 cloud_msg
int counter = 0
Mat currentCamK
Mat currentDepth
Mat currentImage
Mat currentRgb
const bool DEBUG = false
const std::string DEPTH_IMAGE_TOPIC_IN = "depth_image_in"
message_filters::Cache< Image > depthCache
static const std::string DET_INPUT_CAM_INFO_TOPIC = "camera_info_in"
static const std::string DET_INPUT_IMAGE_TOPIC = "depth_image_in"
static const std::string DET_INPUT_POINT_CLOUD_TOPIC = "points_in"
static const std::string DET_INPUT_RGB_IMAGE_TOPIC = "rgb_in"
static const std::string DET_OUTPUT_IMAGE_TOPIC = PLANE_DETECTOR_PREFIX + std::string("/image")
static const std::string DET_OUTPUT_MARKER_SRS_TOPIC = PLANE_DETECTOR_PREFIX + std::string("/srs_poly_array")
static const std::string DET_OUTPUT_MARKER_TOPIC = PLANE_DETECTOR_PREFIX + std::string("/poly")
static const std::string DET_OUTPUT_PLANES_TOPIC = PLANE_DETECTOR_PREFIX + std::string("/plane_array")
static const std::string DET_OUTPUT_POINT_CLOUD_TOPIC = PLANE_DETECTOR_PREFIX + std::string("/point_cloud")
static const std::string DET_SERVICE_INSERT_PLANE = "/but_env_model/insert_plane"
static const std::string DET_SERVICE_INSERT_PLANES = "/but_env_model/insert_planes"
static const std::string DET_SERVICE_LOAD_PLANES = PLANE_DETECTOR_PREFIX + std::string("/load_planes")
static const std::string DET_SERVICE_RESET_PLANES = PLANE_DETECTOR_PREFIX + std::string("/reset_planes")
static const std::string DET_SERVICE_SAVE_PLANES = PLANE_DETECTOR_PREFIX + std::string("/save_planes")
int displayMode = RGB
const std::string Estimate2DHullMesh_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_2D_hull_mesh")
const std::string Estimate2DHullPointCloud_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_2D_hull_point_cloud")
const std::string EstimateBB_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_bb")
const std::string EstimateBBAlt_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_bb_alt")
const std::string EstimateRect_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_rect")
const std::string EstimateRectAlt_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_rect_alt")
int estimationMode = 1
DynModelExporterexporter = NULL
const std::string GLOBAL_FRAME_DEFAULT = "/map"
const std::string GLOBAL_FRAME_PARAM = "global_frame"
ros::ServiceClient Hull2DMeshEstimateClient
static const std::string INPUT_CAM_INFO_TOPIC = KIN2PCL_INPUT_CAM_INFO_TOPIC
static const std::string INPUT_IMAGE_TOPIC = KIN2PCL_INPUT_IMAGE_TOPIC
bool isBBCalculated = false
bool isBBPrimitiveCreated = false
bool isWaitingForResponse = false
static const std::string KIN2PCL_INPUT_CAM_INFO_TOPIC = "/camera/depth/camera_info"
static const std::string KIN2PCL_INPUT_IMAGE_TOPIC = "/camera/depth/image"
static const std::string KIN2PCL_NODE_NAME = "but_kin2pcl_node"
static const std::string KIN2PCL_OUTPUT_POINT_CLOUD_FRAMEID = "/openni_depth_frame"
static const std::string KIN2PCL_OUTPUT_POINT_CLOUD_TOPIC = PACKAGE_NAME_PREFIX + std::string("/point_cloud")
SceneModelmodel
int modelNo = 0
Point2i mouseDown
ros::NodeHandlen = NULL
static const std::string NODE_NAME = KIN2PCL_NODE_NAME
const int OUTLIERS_PERCENT_DEFAULT = 10
const std::string OUTLIERS_PERCENT_PARAM = "outliers_percent"
int outliersPercent = OUTLIERS_PERCENT_DEFAULT
static const std::string OUTPUT_POINT_CLOUD_FRAMEID = KIN2PCL_OUTPUT_POINT_CLOUD_FRAMEID
static const std::string OUTPUT_POINT_CLOUD_TOPIC = KIN2PCL_OUTPUT_POINT_CLOUD_TOPIC
static const std::string PACKAGE_NAME_PREFIX = "/but_env_model_percp"
const std::string PARAM_HT_ANGLE_RES = "planedet_ht_angle_res"
const double PARAM_HT_ANGLE_RES_DEFAULT = 512
const std::string PARAM_HT_GAUSS_ANGLE_RES = "planedet_ht_gauss_angle_res"
const double PARAM_HT_GAUSS_ANGLE_RES_DEFAULT = 11
const std::string PARAM_HT_GAUSS_ANGLE_SIGMA = "planedet_ht_gauss_angle_sigma"
const double PARAM_HT_GAUSS_ANGLE_SIGMA_DEFAULT = 0.04
const std::string PARAM_HT_GAUSS_SHIFT_RES = "planedet_ht_gauss_shift_res"
const double PARAM_HT_GAUSS_SHIFT_RES_DEFAULT = 11
const std::string PARAM_HT_GAUSS_SHIFT_SIGMA = "planedet_ht_gauss_shift_sigma"
const double PARAM_HT_GAUSS_SHIFT_SIGMA_DEFAULT = 0.15
const std::string PARAM_HT_KEEPTRACK = "planedet_ht_keep_track"
const int PARAM_HT_KEEPTRACK_DEFAULT = 1
const std::string PARAM_HT_LVL1_GAUSS_ANGLE_RES = "planedet_ht_lvl1_gauss_angle_res"
const double PARAM_HT_LVL1_GAUSS_ANGLE_RES_DEFAULT = 21
const std::string PARAM_HT_LVL1_GAUSS_ANGLE_SIGMA = "planedet_ht_lvl1_gauss_angle_sigma"
const double PARAM_HT_LVL1_GAUSS_ANGLE_SIGMA_DEFAULT = 5.0
const std::string PARAM_HT_LVL1_GAUSS_SHIFT_RES = "planedet_ht_lvl1_gauss_shift_res"
const double PARAM_HT_LVL1_GAUSS_SHIFT_RES_DEFAULT = 21
const std::string PARAM_HT_LVL1_GAUSS_SHIFT_SIGMA = "planedet_ht_lvl1_gauss_shift_sigma"
const double PARAM_HT_LVL1_GAUSS_SHIFT_SIGMA_DEFAULT = 5.0
const std::string PARAM_HT_MAXDEPTH = "planedet_ht_maxdepth"
const double PARAM_HT_MAXDEPTH_DEFAULT = 100.0
const std::string PARAM_HT_MAXHEIGHT = "planedet_ht_max_height"
const double PARAM_HT_MAXHEIGHT_DEFAULT = 3.0
const std::string PARAM_HT_MAXSHIFT = "planedet_ht_maxshift"
const double PARAM_HT_MAXSHIFT_DEFAULT = 40.0
const std::string PARAM_HT_MIN_SMOOTH = "planedet_ht_min_smooth"
const int PARAM_HT_MIN_SMOOTH_DEFAULT = 50
const std::string PARAM_HT_MINHEIGHT = "planedet_ht_min_height"
const double PARAM_HT_MINHEIGHT_DEFAULT = 0.1
const std::string PARAM_HT_MINSHIFT = "planedet_ht_minshift"
const double PARAM_HT_MINSHIFT_DEFAULT = -40.0
const std::string PARAM_HT_PLANE_MERGE_ANGLE = "planedet_ht_plane_merge_angle"
const double PARAM_HT_PLANE_MERGE_ANGLE_DEFAULT = 0.3
const std::string PARAM_HT_PLANE_MERGE_SHIFT = "planedet_ht_plane_merge_shift"
const double PARAM_HT_PLANE_MERGE_SHIFT_DEFAULT = 0.1
const std::string PARAM_HT_SHIFT_RES = "planedet_ht_shift_res"
const double PARAM_HT_SHIFT_RES_DEFAULT = 4096
const std::string PARAM_HT_STEP_SUBSTRACTION = "planedet_ht_step_substraction"
const double PARAM_HT_STEP_SUBSTRACTION_DEFAULT = 0.2
const std::string PARAM_NODE_INPUT = "planedet_input"
const std::string PARAM_NODE_INPUT_DEFAULT = PARAM_NODE_INPUT_PCL
const std::string PARAM_NODE_INPUT_KINECT = "kinect"
const std::string PARAM_NODE_INPUT_PCL = "pcl"
const std::string PARAM_NODE_ORIGINAL_FRAME = "original_frame"
const std::string PARAM_NODE_ORIGINAL_FRAME_DEFAULT = "/head_cam3d_link"
const std::string PARAM_NODE_OUTPUT_FRAME = "global_frame"
const std::string PARAM_NODE_OUTPUT_FRAME_DEFAULT = "/map"
const std::string PARAM_NORMAL_ITER = "planedet_normal_iter"
const int PARAM_NORMAL_ITER_DEFAULT = 3
const std::string PARAM_NORMAL_NEIGHBORHOOD = "planedet_normal_neighborhood"
const int PARAM_NORMAL_NEIGHBORHOOD_DEFAULT = 5
const std::string PARAM_NORMAL_OUTLIERTHRESH = "planedet_normal_outlierThreshold"
const double PARAM_NORMAL_OUTLIERTHRESH_DEFAULT = 0.02
const std::string PARAM_NORMAL_THRESHOLD = "planedet_normal_threshold"
const double PARAM_NORMAL_THRESHOLD_DEFAULT = 0.2
const std::string PARAM_NORMAL_TYPE = "planedet_normal_type"
const int PARAM_NORMAL_TYPE_DEFAULT = but_plane_detector::NormalType::PCL
const std::string PARAM_SEARCH_MAXIMA_SEARCH_BLUR = "planedet_search_maxima_search_blur"
const int PARAM_SEARCH_MAXIMA_SEARCH_BLUR_DEFAULT = 0
const std::string PARAM_SEARCH_MAXIMA_SEARCH_NEIGHBORHOOD = "planedet_search_maxima_search_neighborhood"
const int PARAM_SEARCH_MAXIMA_SEARCH_NEIGHBORHOOD_DEFAULT = 1
const std::string PARAM_SEARCH_MINIMUM_CURRENT_SPACE = "planedet_search_minimum_current_space"
const double PARAM_SEARCH_MINIMUM_CURRENT_SPACE_DEFAULT = 1500.0
const std::string PARAM_SEARCH_MINIMUM_GLOBAL_SPACE = "planedet_search_minimum_global_space"
const double PARAM_SEARCH_MINIMUM_GLOBAL_SPACE_DEFAULT = 1.5
const std::string PARAM_VISUALISATION_COLOR = "planedet_visualisation_color"
const std::string PARAM_VISUALISATION_COLOR_DEFAULT = "plane_eq"
const std::string PARAM_VISUALISATION_DISTANCE = "planedet_visualisation_distance"
const double PARAM_VISUALISATION_DISTANCE_DEFAULT = 0.05
const std::string PARAM_VISUALISATION_MAX_POLY_SIZE = "planedet_max_poly_size"
const int PARAM_VISUALISATION_MAX_POLY_SIZE_DEFAULT = 2000
const std::string PARAM_VISUALISATION_MIN_COUNT = "planedet_visualisation_min_count"
const int PARAM_VISUALISATION_MIN_COUNT_DEFAULT = 2000
const std::string PARAM_VISUALISATION_PLANE_NORMAL_DEV = "planedet_visualisation_plane_normal_dev"
const double PARAM_VISUALISATION_PLANE_NORMAL_DEV_DEFAULT = 0.15
const std::string PARAM_VISUALISATION_PLANE_SHIFT_DEV = "planedet_visualisation_plane_shift_dev"
const double PARAM_VISUALISATION_PLANE_SHIFT_DEV_DEFAULT = 0.45
const std::string PARAM_VISUALISATION_TTL = "planedet_visualisation_ttl"
const int PARAM_VISUALISATION_TTL_DEFAULT = 10
static const std::string PCDEXP_INPUT_CAM_INFO_TOPIC = "/cam3d/depth/camera_info"
static const std::string PCDEXP_INPUT_IMAGE_TOPIC = "/cam3d/depth/image_raw"
static const std::string PCDEXP_NODE_NAME = "but_pcd_exporter_node"
static const std::string PCDEXP_OUTPUT_POINT_CLOUD_FRAMEID = "/openni_depth_frame"
static const std::string PCDEXP_OUTPUT_POINT_CLOUD_TOPIC = PACKAGE_NAME_PREFIX + std::string("/point_cloud")
static const float PI = 3.1415926535
static const std::string PLANE_DETECTOR_PREFIX = "/but_plane_detector"
const std::string POINT_CLOUD_TOPIC_IN = "points_in"
message_filters::Cache
< PointCloud2 > 
pointCloudCache
ros::Publisher pub
ros::Publisher pub1
ros::Publisher pub2
ros::Publisher pub3
const int QUEUE_SIZE = 10
ros::ServiceClient rectEstimateClient
Mat requestCamK
Mat requestDepth
Mat requestImage
Mat requestRgb
const std::string RGB_IMAGE_TOPIC_IN = "rgb_image_in"
Point2i roiP1
Point2i roiP2
const int SAMPLING_PERCENT_DEFAULT = 30
const std::string SAMPLING_PERCENT_PARAM = "sampling_percent"
int samplingPercent = SAMPLING_PERCENT_DEFAULT
std::string sceneFrameId
static const std::string SEG_INPUT_CAM_INFO_TOPIC = "/cam3d/depth/camera_info"
static const std::string SEG_INPUT_IMAGE_TOPIC = "/cam3d/depth/image_raw"
static const std::string SEG_NODE_NAME = "but_segmenter_node"
static const std::string SEG_OUTPUT_DEVIATION_IMAGE_TOPIC = PACKAGE_NAME_PREFIX + std::string("/but_env_model/seg_deviation_image")
static const std::string SEG_OUTPUT_REGION_INFO_TOPIC = PACKAGE_NAME_PREFIX + std::string("/but_env_model/seg_region_image")
PlaneDetectorSettings settings
const double SIDES_RATIO_DEFAULT = 5.0
const std::string SIDES_RATIO_PARAM = "sides_ratio"
double sidesRatio = SIDES_RATIO_DEFAULT
int subVariant = SV_NONE
tf::TransformListenertfListener
tf::TransformListenertfListenerCam
tf::TransformListenertfListenerRGB
tf::MessageFilter
< sensor_msgs::PointCloud2 > * 
transform_filter
tf::MessageFilter< CameraInfo > * transform_filterCam
tf::MessageFilter< Image > * transform_filterDepth
tf::MessageFilter< Image > * transform_filterRGB
tf::StampedTransform worldToSensorTf

Detailed Description

Description: Encapsulates a class of plane exporter (export to but_gui module/interactive markers)

Description: Class encapsulating Parameter space (i.e. 3D Hough grid)

Contains methods for construction / maxima search / adding of volumes etc.

Description: Class encapsulating region transformation into poly representation

Description: Class encapsulating A scene model (i.e. found planes)

Description: Module exports depth map images point cloud messages

Description: Module exports depth map images into files Output files are marked as model_NUM.pcd


Typedef Documentation

Point in 2D

Definition at line 92 of file funcs.h.


Enumeration Type Documentation

Enumerator:
RGB 
DEPTH 

Definition at line 175 of file sample_client.cpp.

Modes of bounding box estimation They differ in interpretation of the specified 2D region of interest (ROI).

MODE1 = The ROI corresponds to projection of BB front face and the BB is rotated to fit the viewing frustum (representing the back-projection of the ROI) in such way, that the BB front face is perpendicular to the frustum's center axis. (BB can be non-parallel with all axis.)

MODE2 = In the ROI is contained the whole projection of BB. (BB is parallel with all axis.)

MODE3 = The ROI corresponds to projection of BB front face. (BB is parallel with all axis.)

Enumerator:
MODE1 
MODE2 
MODE3 

Definition at line 87 of file funcs.h.

Subscription variants

Enumerator:
SV_NONE 
SV_1 
SV_2 

Definition at line 69 of file funcs.h.


Function Documentation

Point3f srs_env_model_percp::backProject ( Point2i  p,
float  z,
float  fx,
float  fy 
)

Definition at line 84 of file funcs.cpp.

cv::Point3f srs_env_model_percp::backProject ( cv::Point2i  p,
float  z,
float  fx,
float  fy 
)

Back perspective projection of a 2D point with a known depth: 2D point in image coords + known depth => 3D point in world (camera) coords (Result of back projection of an image point is typically a line. However, in our case we know also its depth (from the depth map) and thus we can determine its location on that line and so get a single 3D point.)

The world coordinate system is in our case identical with the camera coordinate system => Tx = Ty = 0 and R is identity => P[1:3,1:3] = K, where P is the camera matrix and K is the intrinsic camera matrix. (http://www.ros.org/wiki/image_pipeline/CameraInfo)

This function implements these formulas: X = x * Z / f_x Y = y * Z / f_y where [x,y] is an image point (with (0,0) in the middle of the image) and [X,Y,Z] its perspective back projection in the given depth.

Parameters:
p2D image point.
zDepth of the back projected 3D point.
fxFocal length w.r.t. axis X.
fyFocal length w.r.t. axis Y.
Returns:
The perspective back projection in the given depth.
Scalar srs_env_model_percp::bbColor ( 255  ,
,
 
)
Scalar srs_env_model_percp::bbColorFront ( ,
,
255   
)
string srs_env_model_percp::bbWinName ( "Bounding Box"  )
bool srs_env_model_percp::calcNearAndFarFaceDepth ( cv::Mat &  m,
float  f,
float *  z1,
float *  z2 
)

Calculation of depth of near and far face of BB (perpendicular with all axis). (It is used in MODE2 and MODE3.)

Parameters:
mThe matrix with depth information.
fFocal length.
z1Caclulated depth of the near BB face.
z2Caclulated depth of the far BB face.
Returns:
True if the depth values were calculated. False if not (due to missing depth information in function calcStats).
bool srs_env_model_percp::calcNearAndFarFaceDepth ( Mat &  m,
float  f,
float *  z1,
float *  z2 
)

Definition at line 288 of file funcs.cpp.

bool srs_env_model_percp::calcNearAndFarFaceDistance ( cv::Mat &  m,
float  fx,
float  fy,
cv::Point2i  roiLB,
cv::Point2i  roiRT,
float *  d1,
float *  d2 
)

Calculation of distances from origin to the BB front and back face vertices. (It is used in MODE1.)

Parameters:
mThe matrix with distance information (distance from origin).
fxFocal length w.r.t. X axis.
fyFocal length w.r.t. Y axis.
roiLBLeft-bottom corner of ROI.
roiRTRight-top corner of ROI.
d1Caclulated distance from origin to the BB front face.
d2Caclulated distance from origin to the BB back face.
Returns:
True if the distance values were calculated. False if not (due to missing depth information in function calcStats).
bool srs_env_model_percp::calcNearAndFarFaceDistance ( Mat &  m,
float  fx,
float  fy,
Point2i  roiLB,
Point2i  roiRT,
float *  d1,
float *  d2 
)

Definition at line 235 of file funcs.cpp.

bool srs_env_model_percp::calcStats ( Mat &  m,
float *  mean,
float *  stdDev 
)

Definition at line 104 of file funcs.cpp.

bool srs_env_model_percp::calcStats ( cv::Mat &  m,
float *  mean,
float *  stdDev 
)

Calculation of statistics (mean, standard deviation, min and max).

Parameters:
mThe matrix with depth information from which the statistics will be calculated (it is assumed that the unknown values are represented by zero).
meanThe calculated mean of m.
stdDevThe calculated standard deviation of m.
Returns:
True if the statistics was calculated. False if the statistics could not be calculated, because there is no depth information available in the specified ROI.
void srs_env_model_percp::callback ( const sensor_msgs::ImageConstPtr &  dep,
const sensor_msgs::CameraInfoConstPtr &  cam_info 
)
void srs_env_model_percp::callback ( const sensor_msgs::ImageConstPtr &  dep,
const CameraInfoConstPtr &  cam_info 
)

Definition at line 60 of file kin2pcl_node.cpp.

void srs_env_model_percp::callbackkinect ( const sensor_msgs::ImageConstPtr &  dep,
const sensor_msgs::CameraInfoConstPtr &  cam_info 
)
void srs_env_model_percp::callbackkinect ( const sensor_msgs::ImageConstPtr &  dep,
const CameraInfoConstPtr &  cam_info 
)

Definition at line 351 of file plane_detector_node.cpp.

void srs_env_model_percp::callbackkinect_rgb ( const sensor_msgs::ImageConstPtr &  dep,
const CameraInfoConstPtr &  cam_info,
const sensor_msgs::ImageConstPtr &  rgb 
)

Definition at line 356 of file plane_detector_node.cpp.

void srs_env_model_percp::callbackpcl ( const PointCloud2ConstPtr &  cloud)

Callback function manages sync of messages

Definition at line 129 of file plane_detector_demo_node.cpp.

void srs_env_model_percp::callbackpcl ( const sensor_msgs::PointCloud2ConstPtr &  cloud)

Callback functions manage sync of messages

Callback function manages sync of messages

void srs_env_model_percp::callbackpcl_rgb ( const PointCloud2ConstPtr &  cloud,
const sensor_msgs::ImageConstPtr &  rgb 
)

Callback function manages sync of messages

Definition at line 259 of file plane_detector_node.cpp.

bool srs_env_model_percp::clear ( srs_env_model_percp::ClearPlanes::Request &  req,
srs_env_model_percp::ClearPlanes::Response &  res 
)
bool srs_env_model_percp::estimate2DConvexHull ( const ros::Time stamp,
const std::vector< cv::Point3f >  points,
std::vector< cv::Point2i > &  convexHull 
)

2D convex hull estimation.

Parameters:
stamptime stamp obtained from message header.
pointsinput 3D points (in world coordinates).
convexHullresulting 2D convex hull (in image plane coordinates) of the input points.

Definition at line 1135 of file funcs.cpp.

Definition at line 539 of file sample_client.cpp.

bool srs_env_model_percp::estimate2DHullMesh_callback ( srs_env_model_percp::Estimate2DHullMesh::Request &  req,
srs_env_model_percp::Estimate2DHullMesh::Response &  res 
)

Definition at line 501 of file service_server.cpp.

bool srs_env_model_percp::estimate2DHullPointCloud_callback ( srs_env_model_percp::Estimate2DHullPointCloud::Request &  req,
srs_env_model_percp::Estimate2DHullPointCloud::Response &  res 
)

Definition at line 547 of file service_server.cpp.

bool srs_env_model_percp::estimateBB ( const ros::Time stamp,
const point2_t &  p1,
const point2_t &  p2,
int  mode,
cv::Point3f &  bbLBF,
cv::Point3f &  bbRBF,
cv::Point3f &  bbRTF,
cv::Point3f &  bbLTF,
cv::Point3f &  bbLBB,
cv::Point3f &  bbRBB,
cv::Point3f &  bbRTB,
cv::Point3f &  bbLTB 
)

Bounding box estimation.

Parameters:
stamptime stamp obtained from message header.
p1,p2input 2D rectangle.
modeestimation mode.
bbXYZresulting bounding box corners.
bool srs_env_model_percp::estimateBB ( const ros::Time stamp,
const point2_t &  p1,
const point2_t &  p2,
int  mode,
Point3f &  bbLBF,
Point3f &  bbRBF,
Point3f &  bbRTF,
Point3f &  bbLTF,
Point3f &  bbLBB,
Point3f &  bbRBB,
Point3f &  bbRTB,
Point3f &  bbLTB 
)

Definition at line 318 of file funcs.cpp.

bool srs_env_model_percp::estimateBB_callback ( srs_env_model_percp::EstimateBB::Request &  req,
srs_env_model_percp::EstimateBB::Response &  res 
)

Definition at line 133 of file service_server.cpp.

bool srs_env_model_percp::estimateBBAlt_callback ( srs_env_model_percp::EstimateBBAlt::Request &  req,
srs_env_model_percp::EstimateBBAlt::Response &  res 
)

Definition at line 228 of file service_server.cpp.

bool srs_env_model_percp::estimateBBPose ( const cv::Point3f &  bbLBF,
const cv::Point3f &  bbRBF,
const cv::Point3f &  bbRTF,
const cv::Point3f &  bbLTF,
const cv::Point3f &  bbLBB,
const cv::Point3f &  bbRBB,
const cv::Point3f &  bbRTB,
const cv::Point3f &  bbLTB,
cv::Point3f &  position,
tf::Quaternion orientation,
cv::Point3f &  scale 
)

Bounding box pose estimation.

Parameters:
bbXYZinput bounding box corners.
positioncalculated BB position (i.e. position of its center).
orientationcalculated BB orientation (i.e. quaternion).
scaleBB dimensions.
bool srs_env_model_percp::estimateBBPose ( const Point3f &  bbLBF,
const Point3f &  bbRBF,
const Point3f &  bbRTF,
const Point3f &  bbLTF,
const Point3f &  bbLBB,
const Point3f &  bbRBB,
const Point3f &  bbRTB,
const Point3f &  bbLTB,
Point3f &  position,
tf::Quaternion orientation,
Point3f &  scale 
)

Definition at line 826 of file funcs.cpp.

bool srs_env_model_percp::estimateRect ( const ros::Time stamp,
const cv::Point3f &  bbLBF,
const cv::Point3f &  bbRBF,
const cv::Point3f &  bbRTF,
const cv::Point3f &  bbLTF,
const cv::Point3f &  bbLBB,
const cv::Point3f &  bbRBB,
const cv::Point3f &  bbRTB,
const cv::Point3f &  bbLTB,
point2_t &  p1,
point2_t &  p2 
)

Image rectangle estimation.

Parameters:
stamptime stamp obtained from message header.
bbXYZinput bounding box corners.
p1,p2resulting 2D image rectangle.
bool srs_env_model_percp::estimateRect ( const ros::Time stamp,
const Point3f &  bbLBF,
const Point3f &  bbRBF,
const Point3f &  bbRTF,
const Point3f &  bbLTF,
const Point3f &  bbLBB,
const Point3f &  bbRBB,
const Point3f &  bbRTB,
const Point3f &  bbLTB,
point2_t &  p1,
point2_t &  p2 
)

Definition at line 1016 of file funcs.cpp.

bool srs_env_model_percp::estimateRect_callback ( srs_env_model_percp::EstimateRect::Request &  req,
srs_env_model_percp::EstimateRect::Response &  res 
)

Definition at line 302 of file service_server.cpp.

bool srs_env_model_percp::estimateRectAlt_callback ( srs_env_model_percp::EstimateRectAlt::Request &  req,
srs_env_model_percp::EstimateRectAlt::Response &  res 
)

Definition at line 401 of file service_server.cpp.

Point2i srs_env_model_percp::fwdProject ( Point3f  p,
float  fx,
float  fy,
float  cx,
float  cy 
)

Definition at line 94 of file funcs.cpp.

cv::Point2i srs_env_model_percp::fwdProject ( cv::Point3f  p,
float  fx,
float  fy,
float  cx,
float  cy 
)

Perspective projection of a 3D point to the image plane. Intrinsic camera matrix for the raw (distorted) images is used: [fx 0 cx] K = [ 0 fy cy] [ 0 0 1] [u v w] = K * [X Y Z] x = u / w = fx * X / Z + cx y = v / w = fy * Y / Z + cy Projects 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths (fx, fy) and principal point (cx, cy).

Definition at line 309 of file plane_detector_demo_node.cpp.

void srs_env_model_percp::getPlanes ( Normals normal,
pcl::PointCloud< pcl::PointXYZ > &  pointcloud,
const sensor_msgs::ImageConstPtr *  rgb = NULL 
)

Definition at line 142 of file plane_detector_node.cpp.

string srs_env_model_percp::hullWinName ( "Convex Hull"  )
string srs_env_model_percp::inputVideoWinName ( "Input Video (use your mouse to specify a ROI)"  )
void srs_env_model_percp::kinect_proc ( const sensor_msgs::ImageConstPtr &  dep,
const CameraInfoConstPtr &  cam_info,
const sensor_msgs::ImageConstPtr *  rgb = NULL 
)

Definition at line 265 of file plane_detector_node.cpp.

bool srs_env_model_percp::onLoad ( srs_env_model_percp::LoadSave::Request &  req,
srs_env_model_percp::LoadSave::Response &  res 
)

Definition at line 479 of file plane_detector_node.cpp.

void srs_env_model_percp::onMouse ( int  event,
int  x,
int  y,
int  flags,
void *  param 
)

Definition at line 859 of file sample_client.cpp.

bool srs_env_model_percp::onReset ( srs_env_model_percp::ResetPlanes::Request &  req,
srs_env_model_percp::ResetPlanes::Response &  res 
)

Definition at line 415 of file plane_detector_node.cpp.

bool srs_env_model_percp::onSave ( srs_env_model_percp::LoadSave::Request &  req,
srs_env_model_percp::LoadSave::Response &  res 
)

Definition at line 464 of file plane_detector_node.cpp.

void srs_env_model_percp::pcl_proc ( const PointCloud2ConstPtr &  cloud,
const sensor_msgs::ImageConstPtr *  rgb = NULL 
)

Definition at line 175 of file plane_detector_node.cpp.

void srs_env_model_percp::pcl_process ( const PointCloud2ConstPtr &  cloud,
const sensor_msgs::ImageConstPtr *  rgb = NULL 
)

Definition at line 139 of file plane_detector_ransac_node.cpp.

Scalar srs_env_model_percp::rectColor ( ,
255  ,
255   
)

Definition at line 388 of file sample_client.cpp.

Definition at line 695 of file sample_client.cpp.

void srs_env_model_percp::sendRequest ( Point2i  p1,
Point2i  p2 
)

Definition at line 409 of file sample_client.cpp.

Definition at line 369 of file sample_client.cpp.

void srs_env_model_percp::sv1_callback ( const sensor_msgs::ImageConstPtr &  depth,
const sensor_msgs::CameraInfoConstPtr &  camInfo 
)

Definition at line 592 of file service_server.cpp.

void srs_env_model_percp::sv1_processSubMsgs ( const sensor_msgs::ImageConstPtr &  rgb,
const sensor_msgs::ImageConstPtr &  depth,
const sensor_msgs::CameraInfoConstPtr &  camInfo 
)

Definition at line 724 of file sample_client.cpp.

void srs_env_model_percp::sv2_callback ( const sensor_msgs::PointCloud2ConstPtr &  pointCloud,
const sensor_msgs::CameraInfoConstPtr &  camInfo 
)

Definition at line 624 of file service_server.cpp.

void srs_env_model_percp::sv2_processSubMsgs ( const sensor_msgs::ImageConstPtr &  rgb,
const sensor_msgs::PointCloud2ConstPtr &  pointCloud,
const sensor_msgs::CameraInfoConstPtr &  camInfo 
)

Definition at line 783 of file sample_client.cpp.

Definition at line 359 of file sample_client.cpp.

Definition at line 197 of file sample_client.cpp.

Definition at line 302 of file sample_client.cpp.


Variable Documentation

const std::string srs_env_model_percp::BB_ESTIMATOR_PREFIX = "/bb_estimator" [static]

Definition at line 62 of file services_list.h.

Definition at line 182 of file sample_client.cpp.

Definition at line 182 of file sample_client.cpp.

Definition at line 182 of file sample_client.cpp.

Definition at line 179 of file sample_client.cpp.

Definition at line 157 of file sample_client.cpp.

geometry_msgs::Vector3 srs_env_model_percp::bbScale

Definition at line 158 of file sample_client.cpp.

Cache size

Definition at line 59 of file funcs.h.

sensor_msgs::CameraInfoConstPtr cam_info_aux & srs_env_model_percp::cam_info_legacy

Definition at line 120 of file plane_detector_demo_node.cpp.

const std::string srs_env_model_percp::CAMERA_INFO_TOPIC_IN = "camera_info_in"

Definition at line 94 of file topics_list.h.

Definition at line 130 of file sample_client.cpp.

Definition at line 127 of file sample_client.cpp.

sensor_msgs::PointCloud2 srs_env_model_percp::cloud_msg

Definition at line 54 of file kin2pcl_node.h.

Definition at line 111 of file plane_detector_demo_node.cpp.

Definition at line 191 of file sample_client.cpp.

Definition at line 190 of file sample_client.cpp.

Definition at line 189 of file sample_client.cpp.

Definition at line 190 of file sample_client.cpp.

Definition at line 53 of file funcs.h.

const std::string srs_env_model_percp::DEPTH_IMAGE_TOPIC_IN = "depth_image_in"

Definition at line 92 of file topics_list.h.

Definition at line 125 of file sample_client.cpp.

const std::string srs_env_model_percp::DET_INPUT_CAM_INFO_TOPIC = "camera_info_in" [static]

Definition at line 51 of file topics_list.h.

const std::string srs_env_model_percp::DET_INPUT_IMAGE_TOPIC = "depth_image_in" [static]

Definition at line 50 of file topics_list.h.

const std::string srs_env_model_percp::DET_INPUT_POINT_CLOUD_TOPIC = "points_in" [static]

but_plane_detector - input topics

Definition at line 49 of file topics_list.h.

const std::string srs_env_model_percp::DET_INPUT_RGB_IMAGE_TOPIC = "rgb_in" [static]

Definition at line 52 of file topics_list.h.

const std::string srs_env_model_percp::DET_OUTPUT_IMAGE_TOPIC = PLANE_DETECTOR_PREFIX + std::string("/image") [static]

Definition at line 44 of file topics_list.h.

const std::string srs_env_model_percp::DET_OUTPUT_MARKER_SRS_TOPIC = PLANE_DETECTOR_PREFIX + std::string("/srs_poly_array") [static]

Definition at line 43 of file topics_list.h.

const std::string srs_env_model_percp::DET_OUTPUT_MARKER_TOPIC = PLANE_DETECTOR_PREFIX + std::string("/poly") [static]

Definition at line 42 of file topics_list.h.

const std::string srs_env_model_percp::DET_OUTPUT_PLANES_TOPIC = PLANE_DETECTOR_PREFIX + std::string("/plane_array") [static]

Definition at line 41 of file topics_list.h.

const std::string srs_env_model_percp::DET_OUTPUT_POINT_CLOUD_TOPIC = PLANE_DETECTOR_PREFIX + std::string("/point_cloud") [static]

Definition at line 40 of file topics_list.h.

const std::string srs_env_model_percp::DET_SERVICE_INSERT_PLANE = "/but_env_model/insert_plane" [static]

Definition at line 58 of file topics_list.h.

const std::string srs_env_model_percp::DET_SERVICE_INSERT_PLANES = "/but_env_model/insert_planes" [static]

but_plane_detector - required env. model services

Definition at line 57 of file topics_list.h.

const std::string srs_env_model_percp::DET_SERVICE_LOAD_PLANES = PLANE_DETECTOR_PREFIX + std::string("/load_planes") [static]

but_plane_detector - services

Definition at line 51 of file services_list.h.

const std::string srs_env_model_percp::DET_SERVICE_RESET_PLANES = PLANE_DETECTOR_PREFIX + std::string("/reset_planes") [static]

but_plane_detector - services

Definition at line 46 of file services_list.h.

const std::string srs_env_model_percp::DET_SERVICE_SAVE_PLANES = PLANE_DETECTOR_PREFIX + std::string("/save_planes") [static]

but_plane_detector - services

Definition at line 56 of file services_list.h.

Definition at line 176 of file sample_client.cpp.

const std::string srs_env_model_percp::Estimate2DHullMesh_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_2D_hull_mesh")

bb_estimator - services performing 2D convex hull estimation of a mesh / point cloud

Definition at line 79 of file services_list.h.

const std::string srs_env_model_percp::Estimate2DHullPointCloud_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_2D_hull_point_cloud")

Definition at line 80 of file services_list.h.

const std::string srs_env_model_percp::EstimateBB_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_bb")

bb_estimator - services performing 3D bounding box estimation

Definition at line 67 of file services_list.h.

const std::string srs_env_model_percp::EstimateBBAlt_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_bb_alt")

Definition at line 68 of file services_list.h.

const std::string srs_env_model_percp::EstimateRect_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_rect")

bb_estimator - services performing 2D ractangle estimation

Definition at line 73 of file services_list.h.

const std::string srs_env_model_percp::EstimateRectAlt_SRV = BB_ESTIMATOR_PREFIX + std::string("/estimate_rect_alt")

Definition at line 74 of file services_list.h.

Definition at line 148 of file sample_client.cpp.

Definition at line 118 of file plane_detector_demo_node.cpp.

const std::string srs_env_model_percp::GLOBAL_FRAME_DEFAULT = "/map"

bb_estimator - default scene (world) frame id

Definition at line 75 of file parameters_list.h.

const std::string srs_env_model_percp::GLOBAL_FRAME_PARAM = "global_frame"

bb_estimator - scene (world) frame id

Definition at line 52 of file parameters_list.h.

Definition at line 179 of file sample_client.cpp.

Definition at line 50 of file kin2pcl_node.h.

Definition at line 49 of file kin2pcl_node.h.

Definition at line 151 of file sample_client.cpp.

Definition at line 152 of file sample_client.cpp.

Definition at line 150 of file sample_client.cpp.

const std::string srs_env_model_percp::KIN2PCL_INPUT_CAM_INFO_TOPIC = "/camera/depth/camera_info" [static]

Definition at line 66 of file topics_list.h.

const std::string srs_env_model_percp::KIN2PCL_INPUT_IMAGE_TOPIC = "/camera/depth/image" [static]

Definition at line 65 of file topics_list.h.

const std::string srs_env_model_percp::KIN2PCL_NODE_NAME = "but_kin2pcl_node" [static]

Definition at line 64 of file topics_list.h.

const std::string srs_env_model_percp::KIN2PCL_OUTPUT_POINT_CLOUD_FRAMEID = "/openni_depth_frame" [static]

Definition at line 68 of file topics_list.h.

const std::string srs_env_model_percp::KIN2PCL_OUTPUT_POINT_CLOUD_TOPIC = PACKAGE_NAME_PREFIX + std::string("/point_cloud") [static]

Definition at line 67 of file topics_list.h.

Definition at line 122 of file plane_detector_demo_node.cpp.

Definition at line 56 of file pcd_exporter_node.h.

Definition at line 154 of file sample_client.cpp.

Definition at line 132 of file plane_detector_node.cpp.

static const std::string srs_env_model_percp::NODE_NAME = KIN2PCL_NODE_NAME [static]

Definition at line 48 of file kin2pcl_node.h.

Definition at line 64 of file parameters_list.h.

const std::string srs_env_model_percp::OUTLIERS_PERCENT_PARAM = "outliers_percent"

Definition at line 40 of file parameters_list.h.

Definition at line 141 of file sample_client.cpp.

Definition at line 52 of file kin2pcl_node.h.

Definition at line 51 of file kin2pcl_node.h.

const std::string srs_env_model_percp::PACKAGE_NAME_PREFIX = "/but_env_model_percp" [static]

Definition at line 36 of file services_list.h.

const std::string srs_env_model_percp::PARAM_HT_ANGLE_RES = "planedet_ht_angle_res"

Definition at line 77 of file plane_detector_params.h.

Definition at line 78 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_GAUSS_ANGLE_RES = "planedet_ht_gauss_angle_res"

Definition at line 83 of file plane_detector_params.h.

Definition at line 84 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_GAUSS_ANGLE_SIGMA = "planedet_ht_gauss_angle_sigma"

Definition at line 89 of file plane_detector_params.h.

Definition at line 90 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_GAUSS_SHIFT_RES = "planedet_ht_gauss_shift_res"

Definition at line 86 of file plane_detector_params.h.

Definition at line 87 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_GAUSS_SHIFT_SIGMA = "planedet_ht_gauss_shift_sigma"

Definition at line 92 of file plane_detector_params.h.

Definition at line 93 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_KEEPTRACK = "planedet_ht_keep_track"

Definition at line 107 of file plane_detector_params.h.

Definition at line 108 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_LVL1_GAUSS_ANGLE_RES = "planedet_ht_lvl1_gauss_angle_res"

Definition at line 95 of file plane_detector_params.h.

Definition at line 96 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_LVL1_GAUSS_ANGLE_SIGMA = "planedet_ht_lvl1_gauss_angle_sigma"

Definition at line 101 of file plane_detector_params.h.

Definition at line 102 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_LVL1_GAUSS_SHIFT_RES = "planedet_ht_lvl1_gauss_shift_res"

Definition at line 98 of file plane_detector_params.h.

Definition at line 99 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_LVL1_GAUSS_SHIFT_SIGMA = "planedet_ht_lvl1_gauss_shift_sigma"

Definition at line 104 of file plane_detector_params.h.

Definition at line 105 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_MAXDEPTH = "planedet_ht_maxdepth"

Hough space settings

Definition at line 62 of file plane_detector_params.h.

Definition at line 63 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_MAXHEIGHT = "planedet_ht_max_height"

Definition at line 65 of file plane_detector_params.h.

Definition at line 66 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_MAXSHIFT = "planedet_ht_maxshift"

Definition at line 74 of file plane_detector_params.h.

Definition at line 75 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_MIN_SMOOTH = "planedet_ht_min_smooth"

Definition at line 116 of file plane_detector_params.h.

Definition at line 117 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_MINHEIGHT = "planedet_ht_min_height"

Definition at line 68 of file plane_detector_params.h.

Definition at line 69 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_MINSHIFT = "planedet_ht_minshift"

Definition at line 71 of file plane_detector_params.h.

Definition at line 72 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_PLANE_MERGE_ANGLE = "planedet_ht_plane_merge_angle"

Definition at line 113 of file plane_detector_params.h.

Definition at line 114 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_PLANE_MERGE_SHIFT = "planedet_ht_plane_merge_shift"

Definition at line 110 of file plane_detector_params.h.

Definition at line 111 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_SHIFT_RES = "planedet_ht_shift_res"

Definition at line 80 of file plane_detector_params.h.

Definition at line 81 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_HT_STEP_SUBSTRACTION = "planedet_ht_step_substraction"

Definition at line 119 of file plane_detector_params.h.

Definition at line 120 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NODE_INPUT = "planedet_input"

Global node settings

Definition at line 40 of file plane_detector_params.h.

Definition at line 43 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NODE_INPUT_KINECT = "kinect"

Definition at line 42 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NODE_INPUT_PCL = "pcl"

Definition at line 41 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NODE_ORIGINAL_FRAME = "original_frame"

Input frame TODO: make this automatic

Definition at line 49 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NODE_ORIGINAL_FRAME_DEFAULT = "/head_cam3d_link"

Definition at line 50 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NODE_OUTPUT_FRAME = "global_frame"

Target frame

Definition at line 55 of file plane_detector_params.h.

Definition at line 56 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NORMAL_ITER = "planedet_normal_iter"

Definition at line 179 of file plane_detector_params.h.

Definition at line 180 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NORMAL_NEIGHBORHOOD = "planedet_normal_neighborhood"

Definition at line 170 of file plane_detector_params.h.

Definition at line 171 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NORMAL_OUTLIERTHRESH = "planedet_normal_outlierThreshold"

Definition at line 176 of file plane_detector_params.h.

Definition at line 177 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NORMAL_THRESHOLD = "planedet_normal_threshold"

Definition at line 173 of file plane_detector_params.h.

Definition at line 174 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_NORMAL_TYPE = "planedet_normal_type"

Normal estimation

Definition at line 167 of file plane_detector_params.h.

Definition at line 168 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_SEARCH_MAXIMA_SEARCH_BLUR = "planedet_search_maxima_search_blur"

Definition at line 135 of file plane_detector_params.h.

Definition at line 136 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_SEARCH_MAXIMA_SEARCH_NEIGHBORHOOD = "planedet_search_maxima_search_neighborhood"

Definition at line 132 of file plane_detector_params.h.

Definition at line 133 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_SEARCH_MINIMUM_CURRENT_SPACE = "planedet_search_minimum_current_space"

Plane search

Definition at line 126 of file plane_detector_params.h.

Definition at line 127 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_SEARCH_MINIMUM_GLOBAL_SPACE = "planedet_search_minimum_global_space"

Definition at line 129 of file plane_detector_params.h.

Definition at line 130 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_VISUALISATION_COLOR = "planedet_visualisation_color"

Definition at line 154 of file plane_detector_params.h.

Definition at line 155 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_VISUALISATION_DISTANCE = "planedet_visualisation_distance"

Visualisation

Definition at line 142 of file plane_detector_params.h.

Definition at line 143 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_VISUALISATION_MAX_POLY_SIZE = "planedet_max_poly_size"

Definition at line 160 of file plane_detector_params.h.

Definition at line 161 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_VISUALISATION_MIN_COUNT = "planedet_visualisation_min_count"

Definition at line 145 of file plane_detector_params.h.

Definition at line 146 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_VISUALISATION_PLANE_NORMAL_DEV = "planedet_visualisation_plane_normal_dev"

Definition at line 148 of file plane_detector_params.h.

Definition at line 149 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_VISUALISATION_PLANE_SHIFT_DEV = "planedet_visualisation_plane_shift_dev"

Definition at line 151 of file plane_detector_params.h.

Definition at line 152 of file plane_detector_params.h.

const std::string srs_env_model_percp::PARAM_VISUALISATION_TTL = "planedet_visualisation_ttl"

Definition at line 157 of file plane_detector_params.h.

Definition at line 158 of file plane_detector_params.h.

const std::string srs_env_model_percp::PCDEXP_INPUT_CAM_INFO_TOPIC = "/cam3d/depth/camera_info" [static]

Definition at line 75 of file topics_list.h.

const std::string srs_env_model_percp::PCDEXP_INPUT_IMAGE_TOPIC = "/cam3d/depth/image_raw" [static]

Definition at line 74 of file topics_list.h.

const std::string srs_env_model_percp::PCDEXP_NODE_NAME = "but_pcd_exporter_node" [static]

but_seg_utils - PCD exporter topics

Definition at line 73 of file topics_list.h.

const std::string srs_env_model_percp::PCDEXP_OUTPUT_POINT_CLOUD_FRAMEID = "/openni_depth_frame" [static]

Definition at line 77 of file topics_list.h.

const std::string srs_env_model_percp::PCDEXP_OUTPUT_POINT_CLOUD_TOPIC = PACKAGE_NAME_PREFIX + std::string("/point_cloud") [static]

Definition at line 76 of file topics_list.h.

const float srs_env_model_percp::PI = 3.1415926535 [static]

Definition at line 52 of file funcs.h.

const std::string srs_env_model_percp::PLANE_DETECTOR_PREFIX = "/but_plane_detector" [static]

Definition at line 41 of file services_list.h.

const std::string srs_env_model_percp::POINT_CLOUD_TOPIC_IN = "points_in"

Definition at line 93 of file topics_list.h.

Definition at line 126 of file sample_client.cpp.

Definition at line 55 of file kin2pcl_node.h.

Definition at line 115 of file plane_detector_demo_node.cpp.

Definition at line 116 of file plane_detector_demo_node.cpp.

Definition at line 117 of file plane_detector_demo_node.cpp.

Size of waiting queue for messages to arrive and complete their "set"

Definition at line 64 of file funcs.h.

Definition at line 179 of file sample_client.cpp.

Definition at line 191 of file sample_client.cpp.

Definition at line 190 of file sample_client.cpp.

Definition at line 189 of file sample_client.cpp.

Definition at line 190 of file sample_client.cpp.

const std::string srs_env_model_percp::RGB_IMAGE_TOPIC_IN = "rgb_image_in"

Definition at line 95 of file topics_list.h.

Definition at line 155 of file sample_client.cpp.

Definition at line 155 of file sample_client.cpp.

bb_estimator - Default percentage of rows and columns considered for sampling (for calculation of statistics)

Definition at line 70 of file parameters_list.h.

const std::string srs_env_model_percp::SAMPLING_PERCENT_PARAM = "sampling_percent"

bb_estimator - Percentage of rows and columns considered for sampling (for calculation of statistics)

Definition at line 47 of file parameters_list.h.

Definition at line 117 of file service_server.cpp.

Definition at line 131 of file sample_client.cpp.

const std::string srs_env_model_percp::SEG_INPUT_CAM_INFO_TOPIC = "/cam3d/depth/camera_info" [static]

Definition at line 84 of file topics_list.h.

const std::string srs_env_model_percp::SEG_INPUT_IMAGE_TOPIC = "/cam3d/depth/image_raw" [static]

Definition at line 83 of file topics_list.h.

const std::string srs_env_model_percp::SEG_NODE_NAME = "but_segmenter_node" [static]

but_seg_utils - depth map segmenter topics

Definition at line 82 of file topics_list.h.

const std::string srs_env_model_percp::SEG_OUTPUT_DEVIATION_IMAGE_TOPIC = PACKAGE_NAME_PREFIX + std::string("/but_env_model/seg_deviation_image") [static]

Definition at line 86 of file topics_list.h.

const std::string srs_env_model_percp::SEG_OUTPUT_REGION_INFO_TOPIC = PACKAGE_NAME_PREFIX + std::string("/but_env_model/seg_region_image") [static]

Definition at line 85 of file topics_list.h.

Definition at line 124 of file plane_detector_demo_node.cpp.

bb_estimator - The required maximum ratio of sides length (the longer side is at maximum sidesRatio times longer than the shorter one)

Definition at line 81 of file parameters_list.h.

const std::string srs_env_model_percp::SIDES_RATIO_PARAM = "sides_ratio"

bb_estimator - The required maximum ratio of sides length (the longer side is at maximum sidesRatio times longer than the shorter one)

Definition at line 58 of file parameters_list.h.

Definition at line 145 of file sample_client.cpp.

Definition at line 134 of file sample_client.cpp.

Definition at line 137 of file sample_client.cpp.

Definition at line 119 of file plane_detector_node.cpp.

Definition at line 120 of file plane_detector_node.cpp.

Definition at line 113 of file plane_detector_demo_node.cpp.

Definition at line 116 of file plane_detector_node.cpp.

Definition at line 115 of file plane_detector_node.cpp.

Definition at line 117 of file plane_detector_node.cpp.

Definition at line 172 of file sample_client.cpp.



srs_env_model_percp
Author(s): Rostislav Hulik (ihulik@fit.vutbr.cz), Tomas Hodan, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Sun Jan 5 2014 11:51:57