Public Member Functions | Public Attributes | Protected Member Functions | Private Attributes | List of all members
cliff_detector::CliffDetector Class Reference

The CliffDetector class detect cliff based on depth image. More...

#include <cliff_detector.h>

Public Member Functions

 CliffDetector ()
 
void detectCliff (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
 detectCliff detects descending stairs based on the information in a depth image More...
 
bool getPublishDepthEnable () const
 getPublishDepthEnable More...
 
float getSensorMountHeight ()
 getSensorMountHeight gets sensor mount height More...
 
float getSensorTiltAngle ()
 getSensorTiltAngle gets sensor tilt angle in degrees More...
 
void setBlockPointsThresh (const int thresh)
 setBlockPointsThresh sets threshold value of pixels in block to set block as stairs More...
 
void setBlockSize (const int size)
 setBlockSize sets size of square block (subimage) used in cliff detector More...
 
void setCamModelUpdate (const bool u)
 Sets the number of image rows to use in data processing. More...
 
void setDepthImgStepCol (const int step)
 setDepthImgStepCol More...
 
void setDepthImgStepRow (const int step)
 setDepthImgStepRow More...
 
void setGroundMargin (const float margin)
 setGroundMargin sets the floor margin (in meters) More...
 
void setParametersConfigurated (const bool u)
 setParametersConfigurated More...
 
void setPublishDepthEnable (const bool enable)
 setPublishDepthEnable More...
 
void setRangeLimits (const float rmin, const float rmax)
 setRangeLimits sets the minimum and maximum range of depth value from RGBD sensor. More...
 
void setSensorMountHeight (const float height)
 setSensorMountHeight sets the height of sensor mount (in meters) from ground More...
 
void setSensorTiltAngle (const float angle)
 setSensorTiltAngle sets the sensor tilt angle (in degrees) More...
 
void setUsedDepthHeight (const unsigned int height)
 setUsedDepthHeight More...
 

Public Attributes

sensor_msgs::ImageConstPtr depth_msg_to_pub_
 Store points which contain stairs. More...
 
sensor_msgs::Image new_depth_msg_
 
depth_nav_msgs::Point32List stairs_points_msg_
 

Protected Member Functions

double angleBetweenRays (const cv::Point3d &ray1, const cv::Point3d &ray2) const
 
void calcDeltaAngleForImgRows (double vertical_fov)
 calcDeltaAngleForImgRows More...
 
void calcGroundDistancesForImgRows (double vertical_fov)
 Calculates distances to ground for every row of depth image. More...
 
void calcTiltCompensationFactorsForImgRows ()
 calcTiltCompensationFactorsForImgRows calculate factors used in tilt compensation More...
 
void fieldOfView (double &min, double &max, double x1, double y1, double xc, double yc, double x2, double y2)
 
template<typename T >
void findCliffInDepthImage (const sensor_msgs::ImageConstPtr &depth_msg)
 
double lengthOfVector (const cv::Point3d &vec) const
 lengthOfVector calculates length of 3D vector. More...
 

Private Attributes

unsigned int block_points_thresh_
 Threshold value of points in block to admit stairs. More...
 
unsigned int block_size_
 Square block (subimage) size (px). More...
 
bool cam_model_update_
 Determines if continuously cam model update required. More...
 
image_geometry::PinholeCameraModel camera_model_
 Class for managing sensor_msgs/CameraInfo messages. More...
 
std::vector< double > delta_row_
 
unsigned int depth_image_step_col_
 Columns step in depth processing (px). More...
 
unsigned int depth_image_step_row_
 Rows step in depth processing (px). More...
 
bool depth_sensor_params_update
 
std::vector< unsigned int > dist_to_ground_
 Calculated distances to ground for every row of depth image in mm. More...
 
float ground_margin_
 Margin for ground points feature detector (m) More...
 
std::string outputFrameId_
 Output frame_id for laserscan. More...
 
bool publish_depth_enable_
 Determines if depth should be republished. More...
 
float range_max_
 Stores the current maximum range to use. More...
 
float range_min_
 Stores the current minimum range to use. More...
 
float sensor_mount_height_
 Height of sensor mount from ground. More...
 
float sensor_tilt_angle_
 Sensor tilt angle (degrees) More...
 
std::vector< double > tilt_compensation_factor_
 Calculated sensor tilt compensation factors. More...
 
unsigned int used_depth_height_
 Used depth height from img bottom (px) More...
 

Detailed Description

The CliffDetector class detect cliff based on depth image.

Definition at line 25 of file cliff_detector.h.

Constructor & Destructor Documentation

cliff_detector::CliffDetector::CliffDetector ( )

Definition at line 5 of file cliff_detector.cpp.

Member Function Documentation

double cliff_detector::CliffDetector::angleBetweenRays ( const cv::Point3d &  ray1,
const cv::Point3d &  ray2 
) const
protected

Computes the angle between two cv::Point3d

Computes the angle of two cv::Point3d assumed to be vectors starting at the origin (0,0,0). Uses the following equation: angle = arccos(a*b/(|a||b|)) where a = ray1 and b = ray2.

Parameters
ray1The first ray
ray2The second ray
Returns
The angle between the two rays (in radians)

Definition at line 158 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::calcDeltaAngleForImgRows ( double  vertical_fov)
protected

calcDeltaAngleForImgRows

Parameters
vertical_fov

Definition at line 183 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::calcGroundDistancesForImgRows ( double  vertical_fov)
protected

Calculates distances to ground for every row of depth image.

Calculates distances to ground for rows of depth image based on known height of sensor mount and tilt angle. It assume that sensor height and tilt angle in relative to ground is constant.

Calculated values are placed in vector dist_to_ground_.

Definition at line 194 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::calcTiltCompensationFactorsForImgRows ( )
protected

calcTiltCompensationFactorsForImgRows calculate factors used in tilt compensation

Definition at line 216 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::detectCliff ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
)

detectCliff detects descending stairs based on the information in a depth image

This function detects descending stairs based on the information in the depth encoded image (UInt16 encoding). To do this, it requires the synchornized Image/CameraInfo pair associated with the image.

Parameters
depth_msgUInt16 encoded depth image.
info_msgCameraInfo associated with depth_msg

Definition at line 7 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::fieldOfView ( double &  min,
double &  max,
double  x1,
double  y1,
double  xc,
double  yc,
double  x2,
double  y2 
)
protected

Calculate vertical angle_min and angle_max by measuring angles between the top ray, bottom ray, and optical center ray

Parameters
camModelThe image_geometry camera model for this image.
min_angleThe minimum vertical angle
max_angleThe maximum vertical angle

Definition at line 163 of file cliff_detector.cpp.

template<typename T >
template void cliff_detector::CliffDetector::findCliffInDepthImage< float > ( const sensor_msgs::ImageConstPtr &  depth_msg)
protected

Find 2D points relative to robots where stairs are detected

This uses a method

Parameters
depth_msgThe UInt16 encoded depth message.

Definition at line 233 of file cliff_detector.cpp.

bool cliff_detector::CliffDetector::getPublishDepthEnable ( ) const
inline

getPublishDepthEnable

Returns

Definition at line 79 of file cliff_detector.h.

float cliff_detector::CliffDetector::getSensorMountHeight ( )
inline

getSensorMountHeight gets sensor mount height

Returns
Return sensor mount height in meters

Definition at line 58 of file cliff_detector.h.

float cliff_detector::CliffDetector::getSensorTiltAngle ( )
inline

getSensorTiltAngle gets sensor tilt angle in degrees

Returns
Return sensor tilt angle in degrees

Definition at line 69 of file cliff_detector.h.

double cliff_detector::CliffDetector::lengthOfVector ( const cv::Point3d &  vec) const
protected

lengthOfVector calculates length of 3D vector.

Method calculates the length of 3D vector assumed to be a vector with start at the (0,0,0).

Parameters
vecVector 3D which lenght will be calculated.
Returns
Returns the length of 3D vector.

Definition at line 154 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::setBlockPointsThresh ( const int  thresh)

setBlockPointsThresh sets threshold value of pixels in block to set block as stairs

Parameters
threshValue of threshold in pixels.

Definition at line 114 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::setBlockSize ( const int  size)

setBlockSize sets size of square block (subimage) used in cliff detector

Parameters
sizeSize of square block in pixels

Definition at line 104 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::setCamModelUpdate ( const bool  u)
inline

Sets the number of image rows to use in data processing.

scan_height is the number of rows (pixels) to use in the output.

Parameters
scan_heightNumber of pixels centered around the center of the image to data processing setCamModelUpdate

Definition at line 92 of file cliff_detector.h.

void cliff_detector::CliffDetector::setDepthImgStepCol ( const int  step)

setDepthImgStepCol

Parameters
step

Definition at line 134 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::setDepthImgStepRow ( const int  step)

setDepthImgStepRow

Parameters
step

Definition at line 124 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::setGroundMargin ( const float  margin)

setGroundMargin sets the floor margin (in meters)

Parameters
margin

Definition at line 144 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::setParametersConfigurated ( const bool  u)
inline

setParametersConfigurated

Parameters
u

Definition at line 129 of file cliff_detector.h.

void cliff_detector::CliffDetector::setPublishDepthEnable ( const bool  enable)
inline

setPublishDepthEnable

Parameters
enable

Definition at line 74 of file cliff_detector.h.

void cliff_detector::CliffDetector::setRangeLimits ( const float  rmin,
const float  rmax 
)

setRangeLimits sets the minimum and maximum range of depth value from RGBD sensor.

Parameters
rminMinimum of depth value which will be used in data processing.
rminMaximum of depth value which will be used in data processing.

Definition at line 57 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::setSensorMountHeight ( const float  height)

setSensorMountHeight sets the height of sensor mount (in meters) from ground

Parameters
heightValue of sensor mount height (in meters).

Definition at line 74 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::setSensorTiltAngle ( const float  angle)

setSensorTiltAngle sets the sensor tilt angle (in degrees)

Parameters
angle

Definition at line 84 of file cliff_detector.cpp.

void cliff_detector::CliffDetector::setUsedDepthHeight ( const unsigned int  height)

setUsedDepthHeight

Parameters
height

Definition at line 94 of file cliff_detector.cpp.

Member Data Documentation

unsigned int cliff_detector::CliffDetector::block_points_thresh_
private

Threshold value of points in block to admit stairs.

Definition at line 203 of file cliff_detector.h.

unsigned int cliff_detector::CliffDetector::block_size_
private

Square block (subimage) size (px).

Definition at line 202 of file cliff_detector.h.

bool cliff_detector::CliffDetector::cam_model_update_
private

Determines if continuously cam model update required.

Definition at line 200 of file cliff_detector.h.

image_geometry::PinholeCameraModel cliff_detector::CliffDetector::camera_model_
private

Class for managing sensor_msgs/CameraInfo messages.

Definition at line 210 of file cliff_detector.h.

std::vector<double> cliff_detector::CliffDetector::delta_row_
private

Definition at line 216 of file cliff_detector.h.

unsigned int cliff_detector::CliffDetector::depth_image_step_col_
private

Columns step in depth processing (px).

Definition at line 205 of file cliff_detector.h.

unsigned int cliff_detector::CliffDetector::depth_image_step_row_
private

Rows step in depth processing (px).

Definition at line 204 of file cliff_detector.h.

sensor_msgs::ImageConstPtr cliff_detector::CliffDetector::depth_msg_to_pub_

Store points which contain stairs.

Definition at line 220 of file cliff_detector.h.

bool cliff_detector::CliffDetector::depth_sensor_params_update
private

Definition at line 208 of file cliff_detector.h.

std::vector<unsigned int> cliff_detector::CliffDetector::dist_to_ground_
private

Calculated distances to ground for every row of depth image in mm.

Definition at line 212 of file cliff_detector.h.

float cliff_detector::CliffDetector::ground_margin_
private

Margin for ground points feature detector (m)

Definition at line 206 of file cliff_detector.h.

sensor_msgs::Image cliff_detector::CliffDetector::new_depth_msg_

Definition at line 219 of file cliff_detector.h.

std::string cliff_detector::CliffDetector::outputFrameId_
private

Output frame_id for laserscan.

Definition at line 194 of file cliff_detector.h.

bool cliff_detector::CliffDetector::publish_depth_enable_
private

Determines if depth should be republished.

Definition at line 199 of file cliff_detector.h.

float cliff_detector::CliffDetector::range_max_
private

Stores the current maximum range to use.

Definition at line 196 of file cliff_detector.h.

float cliff_detector::CliffDetector::range_min_
private

Stores the current minimum range to use.

Definition at line 195 of file cliff_detector.h.

float cliff_detector::CliffDetector::sensor_mount_height_
private

Height of sensor mount from ground.

Definition at line 197 of file cliff_detector.h.

float cliff_detector::CliffDetector::sensor_tilt_angle_
private

Sensor tilt angle (degrees)

Definition at line 198 of file cliff_detector.h.

depth_nav_msgs::Point32List cliff_detector::CliffDetector::stairs_points_msg_

Definition at line 223 of file cliff_detector.h.

std::vector<double> cliff_detector::CliffDetector::tilt_compensation_factor_
private

Calculated sensor tilt compensation factors.

Definition at line 214 of file cliff_detector.h.

unsigned int cliff_detector::CliffDetector::used_depth_height_
private

Used depth height from img bottom (px)

Definition at line 201 of file cliff_detector.h.


The documentation for this class was generated from the following files:


cliff_detector
Author(s): Michal Drwiega (http://www.mdrwiega.com)
autogenerated on Wed May 5 2021 02:56:04