The CliffDetector class detect cliff based on depth image.
More...
#include <cliff_detector.h>
The CliffDetector class detect cliff based on depth image.
Definition at line 25 of file cliff_detector.h.
cliff_detector::CliffDetector::CliffDetector |
( |
| ) |
|
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
-
ray1 | The first ray |
ray2 | The 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 |
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_msg | UInt16 encoded depth image. |
info_msg | CameraInfo 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
-
camModel | The image_geometry camera model for this image. |
min_angle | The minimum vertical angle |
max_angle | The 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_msg | The UInt16 encoded depth message. |
Definition at line 233 of file cliff_detector.cpp.
bool cliff_detector::CliffDetector::getPublishDepthEnable |
( |
| ) |
const |
|
inline |
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
-
vec | Vector 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
-
thresh | Value 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
-
size | Size 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_height | Number 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 | ) |
|
void cliff_detector::CliffDetector::setDepthImgStepRow |
( |
const int |
step | ) |
|
void cliff_detector::CliffDetector::setGroundMargin |
( |
const float |
margin | ) |
|
setGroundMargin sets the floor margin (in meters)
- Parameters
-
Definition at line 144 of file cliff_detector.cpp.
void cliff_detector::CliffDetector::setParametersConfigurated |
( |
const bool |
u | ) |
|
|
inline |
void cliff_detector::CliffDetector::setPublishDepthEnable |
( |
const bool |
enable | ) |
|
|
inline |
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
-
rmin | Minimum of depth value which will be used in data processing. |
rmin | Maximum 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
-
height | Value 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
-
Definition at line 84 of file cliff_detector.cpp.
void cliff_detector::CliffDetector::setUsedDepthHeight |
( |
const unsigned int |
height | ) |
|
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 |
bool cliff_detector::CliffDetector::cam_model_update_ |
|
private |
Determines if continuously cam model update required.
Definition at line 200 of file cliff_detector.h.
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 |
unsigned int cliff_detector::CliffDetector::depth_image_step_col_ |
|
private |
unsigned int cliff_detector::CliffDetector::depth_image_step_row_ |
|
private |
sensor_msgs::ImageConstPtr cliff_detector::CliffDetector::depth_msg_to_pub_ |
bool cliff_detector::CliffDetector::depth_sensor_params_update |
|
private |
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 |
sensor_msgs::Image cliff_detector::CliffDetector::new_depth_msg_ |
std::string cliff_detector::CliffDetector::outputFrameId_ |
|
private |
bool cliff_detector::CliffDetector::publish_depth_enable_ |
|
private |
float cliff_detector::CliffDetector::range_max_ |
|
private |
float cliff_detector::CliffDetector::range_min_ |
|
private |
float cliff_detector::CliffDetector::sensor_mount_height_ |
|
private |
float cliff_detector::CliffDetector::sensor_tilt_angle_ |
|
private |
depth_nav_msgs::Point32List cliff_detector::CliffDetector::stairs_points_msg_ |
std::vector<double> cliff_detector::CliffDetector::tilt_compensation_factor_ |
|
private |
unsigned int cliff_detector::CliffDetector::used_depth_height_ |
|
private |
The documentation for this class was generated from the following files: