Public Member Functions | Protected Member Functions | Private Attributes | List of all members
depth_sensor_pose::DepthSensorPose Class Reference

#include <depth_sensor_pose.h>

Inheritance diagram for depth_sensor_pose::DepthSensorPose:
Inheritance graph
[legend]

Public Member Functions

 DepthSensorPose ()=default
 
 DepthSensorPose (const DepthSensorPose &)=delete
 
void estimateParams (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
 
sensor_msgs::ImageConstPtr getDbgImage () const
 
bool getPublishDepthEnable () const
 getPublishDepthEnable More...
 
float getSensorMountHeight () const
 
float getSensorTiltAngle () const
 
DepthSensorPoseoperator= (const DepthSensorPose &)=delete
 
void setCamModelUpdate (const bool u)
 setCamModelUpdate More...
 
void setDepthImgStepCol (const int step)
 setDepthImgStepCol More...
 
void setDepthImgStepRow (const int step)
 setDepthImgStepRow More...
 
void setGroundMaxPoints (const unsigned u)
 
void setPublishDepthEnable (const bool enable)
 setPublishDepthEnable More...
 
void setRangeLimits (const float rmin, const float rmax)
 
void setRansacDistanceThresh (const float u)
 
void setRansacMaxIter (const unsigned u)
 
void setReconfParamsUpdated (bool updated)
 setReconfParamsUpdated More...
 
void setSensorMountHeightMax (const float height)
 setSensorMountHeight sets the height of sensor mount (in meters) from ground More...
 
void setSensorMountHeightMin (const float height)
 setSensorMountHeight sets the height of sensor mount (in meters) from ground More...
 
void setSensorTiltAngleMax (const float angle)
 setSensorTiltAngle sets the sensor tilt angle (in degrees) More...
 
void setSensorTiltAngleMin (const float angle)
 setSensorTiltAngle sets the sensor tilt angle (in degrees) More...
 
void setUsedDepthHeight (const unsigned height)
 setUsedDepthHeight More...
 
 ~DepthSensorPose ()=default
 

Protected Member Functions

double angleBetweenRays (const cv::Point3d &ray1, const cv::Point3d &ray2) const
 
void calcDeltaAngleForImgRows (double vertical_fov)
 
void calcGroundDistancesForImgRows (double mount_height, double tilt_angle, std::vector< double > &distances)
 Calculates distances to ground for every row of depth image. More...
 
void fieldOfView (double &min, double &max, double x1, double y1, double xc, double yc, double x2, double y2)
 
template<typename T >
void getGroundPoints (const sensor_msgs::ImageConstPtr &depth_msg, pcl::PointCloud< pcl::PointXYZ >::Ptr &points, std::list< std::pair< unsigned, unsigned >> &points_indices)
 
double lengthOfVector (const cv::Point3d &vec) const
 
sensor_msgs::ImagePtr prepareDbgImage (const sensor_msgs::ImageConstPtr &depth_msg, const std::list< std::pair< unsigned, unsigned >> &ground_points_indices)
 
void sensorPoseCalibration (const sensor_msgs::ImageConstPtr &depth_msg, double &tilt_angle, double &height)
 

Private Attributes

bool cam_model_update_ {false}
 Determines if continuously cam model update is required. More...
 
image_geometry::PinholeCameraModel camera_model_
 
sensor_msgs::ImagePtr dbg_image_
 
std::vector< double > delta_row_
 
unsigned depth_image_step_col_ {0}
 Columns step in depth processing (px). More...
 
unsigned depth_image_step_row_ {0}
 Rows step in depth processing (px). More...
 
std::vector< double > dist_to_ground_max_
 
std::vector< double > dist_to_ground_min_
 
float groundDistTolerance_ {0}
 Class for managing sensor_msgs/CameraInfo messages. More...
 
unsigned max_ground_points_ {0}
 
double mount_height_est_ {0}
 
float mount_height_max_ {0}
 Max height of sensor mount from ground. More...
 
float mount_height_min_ {0}
 Min height of sensor mount from ground. More...
 
bool publish_depth_enable_ {false}
 Determines if debug image should be published. More...
 
float range_max_ {0}
 Stores the current maximum range to use. More...
 
float range_min_ {0}
 Stores the current minimum range to use. More...
 
float ransacDistanceThresh_ {0}
 
unsigned ransacMaxIter_ {0}
 
bool reconf_serv_params_updated_ {true}
 
double tilt_angle_est_ {0}
 
float tilt_angle_max_ {0}
 Max angle of sensor tilt in degrees. More...
 
float tilt_angle_min_ {0}
 Min angle of sensor tilt in degrees. More...
 
unsigned used_depth_height_ {0}
 Used depth height from img bottom (px) More...
 

Detailed Description

Definition at line 31 of file depth_sensor_pose.h.

Constructor & Destructor Documentation

depth_sensor_pose::DepthSensorPose::DepthSensorPose ( )
default
depth_sensor_pose::DepthSensorPose::~DepthSensorPose ( )
default
depth_sensor_pose::DepthSensorPose::DepthSensorPose ( const DepthSensorPose )
delete

Member Function Documentation

double depth_sensor_pose::DepthSensorPose::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 129 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::calcDeltaAngleForImgRows ( double  vertical_fov)
protected

Definition at line 156 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::calcGroundDistancesForImgRows ( double  mount_height,
double  tilt_angle,
std::vector< double > &  distances 
)
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 166 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::estimateParams ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
)

Converts the information in a depth image (sensor_msgs::Image) to a sensor_msgs::LaserScan.

This function converts the information in the depth encoded image (UInt16) into a sensor_msgs::LaserScan as accurately as possible. To do this, it requires the synchornized Image/CameraInfo pair associated with the image.

Parameters
depth_msgUInt16 or Float32 encoded depth image.
info_msgCameraInfo associated with depth_msg
Returns
sensor_msgs::LaserScanPtr for the center row(s) of the depth image.

Definition at line 7 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::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 136 of file depth_sensor_pose.cpp.

sensor_msgs::ImageConstPtr depth_sensor_pose::DepthSensorPose::getDbgImage ( ) const

Definition at line 121 of file depth_sensor_pose.cpp.

template<typename T >
void depth_sensor_pose::DepthSensorPose::getGroundPoints ( const sensor_msgs::ImageConstPtr &  depth_msg,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
std::list< std::pair< unsigned, unsigned >> &  points_indices 
)
protected

Definition at line 189 of file depth_sensor_pose.cpp.

bool depth_sensor_pose::DepthSensorPose::getPublishDepthEnable ( ) const
inline

getPublishDepthEnable

Returns

Definition at line 96 of file depth_sensor_pose.h.

float depth_sensor_pose::DepthSensorPose::getSensorMountHeight ( ) const
inline

Definition at line 131 of file depth_sensor_pose.h.

float depth_sensor_pose::DepthSensorPose::getSensorTiltAngle ( ) const
inline

Definition at line 129 of file depth_sensor_pose.h.

double depth_sensor_pose::DepthSensorPose::lengthOfVector ( const cv::Point3d &  vec) const
protected

Computes euclidean length of a cv::Point3d (as a ray from origin)

This function computes the length of a cv::Point3d assumed to be a vector starting at the origin (0,0,0).

Parameters
rayThe ray for which the magnitude is desired.
Returns
Returns the magnitude of the ray.

Definition at line 125 of file depth_sensor_pose.cpp.

DepthSensorPose& depth_sensor_pose::DepthSensorPose::operator= ( const DepthSensorPose )
delete
sensor_msgs::ImagePtr depth_sensor_pose::DepthSensorPose::prepareDbgImage ( const sensor_msgs::ImageConstPtr &  depth_msg,
const std::list< std::pair< unsigned, unsigned >> &  ground_points_indices 
)
protected

Definition at line 320 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::sensorPoseCalibration ( const sensor_msgs::ImageConstPtr &  depth_msg,
double &  tilt_angle,
double &  height 
)
protected

Definition at line 247 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::setCamModelUpdate ( const bool  u)
inline

setCamModelUpdate

Parameters
u

Definition at line 101 of file depth_sensor_pose.h.

void depth_sensor_pose::DepthSensorPose::setDepthImgStepCol ( const int  step)

setDepthImgStepCol

Parameters
step

Definition at line 111 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::setDepthImgStepRow ( const int  step)

setDepthImgStepRow

Parameters
step

Definition at line 101 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::setGroundMaxPoints ( const unsigned  u)
inline

Definition at line 127 of file depth_sensor_pose.h.

void depth_sensor_pose::DepthSensorPose::setPublishDepthEnable ( const bool  enable)
inline

setPublishDepthEnable

Parameters
enable

Definition at line 91 of file depth_sensor_pose.h.

void depth_sensor_pose::DepthSensorPose::setRangeLimits ( const float  rmin,
const float  rmax 
)

Sets the minimum and maximum range for the sensor_msgs::LaserScan.

rangeMin is used to determine how close of a value to allow through when multiple radii correspond to the same angular increment. rangeMax is used to set the output message.

Parameters
rangeMinMinimum range to assign points to the laserscan, also minimum range to use points in the output scan.
rangeMaxMaximum range to use points in the output scan.

Definition at line 34 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::setRansacDistanceThresh ( const float  u)
inline

Definition at line 125 of file depth_sensor_pose.h.

void depth_sensor_pose::DepthSensorPose::setRansacMaxIter ( const unsigned  u)
inline

Definition at line 123 of file depth_sensor_pose.h.

void depth_sensor_pose::DepthSensorPose::setReconfParamsUpdated ( bool  updated)
inline

setReconfParamsUpdated

Parameters
updated

Definition at line 121 of file depth_sensor_pose.h.

void depth_sensor_pose::DepthSensorPose::setSensorMountHeightMax ( 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 61 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::setSensorMountHeightMin ( 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 51 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::setSensorTiltAngleMax ( const float  angle)

setSensorTiltAngle sets the sensor tilt angle (in degrees)

Parameters
angle

Definition at line 81 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::setSensorTiltAngleMin ( const float  angle)

setSensorTiltAngle sets the sensor tilt angle (in degrees)

Parameters
angle

Definition at line 71 of file depth_sensor_pose.cpp.

void depth_sensor_pose::DepthSensorPose::setUsedDepthHeight ( const unsigned  height)

setUsedDepthHeight

Parameters
height

Definition at line 91 of file depth_sensor_pose.cpp.

Member Data Documentation

bool depth_sensor_pose::DepthSensorPose::cam_model_update_ {false}
private

Determines if continuously cam model update is required.

Definition at line 203 of file depth_sensor_pose.h.

image_geometry::PinholeCameraModel depth_sensor_pose::DepthSensorPose::camera_model_
private

Definition at line 214 of file depth_sensor_pose.h.

sensor_msgs::ImagePtr depth_sensor_pose::DepthSensorPose::dbg_image_
private

Definition at line 216 of file depth_sensor_pose.h.

std::vector<double> depth_sensor_pose::DepthSensorPose::delta_row_
private

Definition at line 222 of file depth_sensor_pose.h.

unsigned depth_sensor_pose::DepthSensorPose::depth_image_step_col_ {0}
private

Columns step in depth processing (px).

Definition at line 206 of file depth_sensor_pose.h.

unsigned depth_sensor_pose::DepthSensorPose::depth_image_step_row_ {0}
private

Rows step in depth processing (px).

Definition at line 205 of file depth_sensor_pose.h.

std::vector<double> depth_sensor_pose::DepthSensorPose::dist_to_ground_max_
private

Definition at line 223 of file depth_sensor_pose.h.

std::vector<double> depth_sensor_pose::DepthSensorPose::dist_to_ground_min_
private

Definition at line 224 of file depth_sensor_pose.h.

float depth_sensor_pose::DepthSensorPose::groundDistTolerance_ {0}
private

Class for managing sensor_msgs/CameraInfo messages.

Definition at line 211 of file depth_sensor_pose.h.

unsigned depth_sensor_pose::DepthSensorPose::max_ground_points_ {0}
private

Definition at line 208 of file depth_sensor_pose.h.

double depth_sensor_pose::DepthSensorPose::mount_height_est_ {0}
private

Definition at line 218 of file depth_sensor_pose.h.

float depth_sensor_pose::DepthSensorPose::mount_height_max_ {0}
private

Max height of sensor mount from ground.

Definition at line 198 of file depth_sensor_pose.h.

float depth_sensor_pose::DepthSensorPose::mount_height_min_ {0}
private

Min height of sensor mount from ground.

Definition at line 197 of file depth_sensor_pose.h.

bool depth_sensor_pose::DepthSensorPose::publish_depth_enable_ {false}
private

Determines if debug image should be published.

Definition at line 202 of file depth_sensor_pose.h.

float depth_sensor_pose::DepthSensorPose::range_max_ {0}
private

Stores the current maximum range to use.

Definition at line 196 of file depth_sensor_pose.h.

float depth_sensor_pose::DepthSensorPose::range_min_ {0}
private

Stores the current minimum range to use.

Definition at line 195 of file depth_sensor_pose.h.

float depth_sensor_pose::DepthSensorPose::ransacDistanceThresh_ {0}
private

Definition at line 210 of file depth_sensor_pose.h.

unsigned depth_sensor_pose::DepthSensorPose::ransacMaxIter_ {0}
private

Definition at line 209 of file depth_sensor_pose.h.

bool depth_sensor_pose::DepthSensorPose::reconf_serv_params_updated_ {true}
private

Definition at line 220 of file depth_sensor_pose.h.

double depth_sensor_pose::DepthSensorPose::tilt_angle_est_ {0}
private

Definition at line 219 of file depth_sensor_pose.h.

float depth_sensor_pose::DepthSensorPose::tilt_angle_max_ {0}
private

Max angle of sensor tilt in degrees.

Definition at line 200 of file depth_sensor_pose.h.

float depth_sensor_pose::DepthSensorPose::tilt_angle_min_ {0}
private

Min angle of sensor tilt in degrees.

Definition at line 199 of file depth_sensor_pose.h.

unsigned depth_sensor_pose::DepthSensorPose::used_depth_height_ {0}
private

Used depth height from img bottom (px)

Definition at line 204 of file depth_sensor_pose.h.


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


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