Public Member Functions | Protected Member Functions | Private Attributes | List of all members
laserscan_kinect::LaserScanKinect Class Reference

#include <laserscan_kinect.h>

Public Member Functions

sensor_msgs::ImageConstPtr getDbgImage () const
 
sensor_msgs::LaserScanPtr getLaserScanMsg (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
 prepareLaserScanMsg converts depthimage and prepare new LaserScan message More...
 
bool getPublishDbgImgEnable () const
 
 LaserScanKinect ()
 
void setCamModelUpdate (const bool enable)
 setCamModelUpdate sets the camera parameters More...
 
void setDepthImgRowStep (const int row_step)
 setDepthImgRowStep More...
 
void setGroundMargin (const float margin)
 setGroundMargin sets the floor margin (in meters) More...
 
void setGroundRemove (const bool enable)
 setGroundRemove enables or disables the feature which remove ground from scan More...
 
void setOutputFrame (const std::string &frame)
 setOutputFrame sets the frame to output laser scan More...
 
void setPublishDbgImgEnable (const bool enable)
 setPublishDbgImgEnable More...
 
void setRangeLimits (const float rmin, const float rmax)
 setRangeLimits sets depth sensor min and max ranges More...
 
void setScanConfigurated (const bool configured)
 setScanConfigurated sets the configuration status More...
 
void setScanHeight (const int scan_height)
 setScanHeight sets height of depth image which will be used in conversion process More...
 
void setSensorMountHeight (const float height)
 setSensorMountHeight sets the height of sensor mount (in meters) More...
 
void setSensorTiltAngle (const float angle)
 setSensorTiltAngle sets the sensor tilt angle (in degrees) More...
 
void setThreadsNum (unsigned threads_num)
 
void setTiltCompensation (const bool enable)
 setTiltCompensation enables or disables the feature which compensates sensor tilt More...
 
 ~LaserScanKinect ()=default
 

Protected Member Functions

void calcGroundDistancesForImgRows (double vertical_fov)
 calcGroundDistancesForImgRows calculate coefficients used in ground removing from scan More...
 
void calcScanMsgIndexForImgCols (const sensor_msgs::ImageConstPtr &depth_msg)
 calcScanMsgIndexForImgCols More...
 
void calcTiltCompensationFactorsForImgRows (double vertical_fov)
 calcTiltCompensationFactorsForImgRows calculate factors used in tilt compensation More...
 
template<typename T >
void convertDepthToPolarCoords (const sensor_msgs::ImageConstPtr &depth_msg)
 convertDepthToPolarCoords converts depth map to 2D More...
 
template<typename T >
float getSmallestValueInColumn (const sensor_msgs::ImageConstPtr &depth_msg, int col)
 getSmallestValueInColumn finds smallest values in depth image columns More...
 
sensor_msgs::ImagePtr prepareDbgImage (const sensor_msgs::ImageConstPtr &depth_msg, const std::list< std::pair< int, int >> &min_dist_points_indices)
 

Private Attributes

image_geometry::PinholeCameraModel cam_model_
 Class for managing CameraInfo messages. More...
 
bool cam_model_update_ {false}
 If continously calibration update required. More...
 
sensor_msgs::ImagePtr dbg_image_
 
unsigned depth_img_row_step_ {0}
 Row step in depth map processing. More...
 
std::vector< float > dist_to_ground_corrected
 Calculated maximal distances for measurements not included as floor. More...
 
float ground_margin_ {0}
 Margin for floor remove feature (in meters) More...
 
bool ground_remove_enable_ {false}
 Determines if remove ground from output scan. More...
 
int image_vertical_offset_ {0}
 The vertical offset of image based on calibration data. More...
 
bool is_scan_msg_configured_ {false}
 Determines if laser scan message is configurated. More...
 
std::list< std::pair< int, int > > min_dist_points_indices_
 
std::string output_frame_id_
 Output frame_id for laserscan message. More...
 
std::mutex points_indices_mutex_
 
bool publish_dbg_image_ {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...
 
unsigned scan_height_ {0}
 Number of pixel rows used to scan computing. More...
 
sensor_msgs::LaserScanPtr scan_msg_
 Published scan message. More...
 
std::vector< unsigned > scan_msg_index_
 Calculated laser scan msg indexes for each depth image column. More...
 
std::mutex scan_msg_mutex_
 
float sensor_mount_height_ {0}
 Height of sensor mount from ground. More...
 
float sensor_tilt_angle_ {0}
 Angle of sensor tilt. More...
 
unsigned threads_num_ {1}
 Determines threads number used in image processing. More...
 
bool tilt_compensation_enable_ {false}
 Determines if tilt compensation feature is on. More...
 
std::vector< float > tilt_compensation_factor_
 Calculated sensor tilt compensation factors. More...
 

Detailed Description

Definition at line 17 of file laserscan_kinect.h.

Constructor & Destructor Documentation

laserscan_kinect::LaserScanKinect::LaserScanKinect ( )
inline

Definition at line 19 of file laserscan_kinect.h.

laserscan_kinect::LaserScanKinect::~LaserScanKinect ( )
default

Member Function Documentation

void laserscan_kinect::LaserScanKinect::calcGroundDistancesForImgRows ( double  vertical_fov)
protected

calcGroundDistancesForImgRows calculate coefficients used in ground removing from scan

Parameters
vertical_fov

Definition at line 183 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::calcScanMsgIndexForImgCols ( const sensor_msgs::ImageConstPtr &  depth_msg)
protected

calcScanMsgIndexForImgCols

Parameters
depth_msg

Definition at line 232 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::calcTiltCompensationFactorsForImgRows ( double  vertical_fov)
protected

calcTiltCompensationFactorsForImgRows calculate factors used in tilt compensation

Parameters
vertical_fov

Definition at line 216 of file laserscan_kinect.cpp.

template<typename T >
void laserscan_kinect::LaserScanKinect::convertDepthToPolarCoords ( const sensor_msgs::ImageConstPtr &  depth_msg)
protected

convertDepthToPolarCoords converts depth map to 2D

Definition at line 303 of file laserscan_kinect.cpp.

sensor_msgs::ImageConstPtr laserscan_kinect::LaserScanKinect::getDbgImage ( ) const

Definition at line 179 of file laserscan_kinect.cpp.

sensor_msgs::LaserScanPtr laserscan_kinect::LaserScanKinect::getLaserScanMsg ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
)

prepareLaserScanMsg converts depthimage and prepare new LaserScan message

Parameters
depth_msgMessage that contains depth image which will be converted to LaserScan.
info_msgMessage which contains depth sensor parameters.
Returns
Return pointer to LaserScan message.

Definition at line 14 of file laserscan_kinect.cpp.

bool laserscan_kinect::LaserScanKinect::getPublishDbgImgEnable ( ) const
inline

Definition at line 104 of file laserscan_kinect.h.

template<typename T >
template float laserscan_kinect::LaserScanKinect::getSmallestValueInColumn< float > ( const sensor_msgs::ImageConstPtr &  depth_msg,
int  col 
)
protected

getSmallestValueInColumn finds smallest values in depth image columns

Definition at line 243 of file laserscan_kinect.cpp.

sensor_msgs::ImagePtr laserscan_kinect::LaserScanKinect::prepareDbgImage ( const sensor_msgs::ImageConstPtr &  depth_msg,
const std::list< std::pair< int, int >> &  min_dist_points_indices 
)
protected

Definition at line 357 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::setCamModelUpdate ( const bool  enable)
inline

setCamModelUpdate sets the camera parameters

Parameters
enable

Definition at line 61 of file laserscan_kinect.h.

void laserscan_kinect::LaserScanKinect::setDepthImgRowStep ( const int  row_step)

setDepthImgRowStep

Parameters
row_step

Definition at line 129 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::setGroundMargin ( const float  margin)

setGroundMargin sets the floor margin (in meters)

Parameters
margin

Definition at line 159 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::setGroundRemove ( const bool  enable)
inline

setGroundRemove enables or disables the feature which remove ground from scan

Parameters
enable

Definition at line 77 of file laserscan_kinect.h.

void laserscan_kinect::LaserScanKinect::setOutputFrame ( const std::string &  frame)
inline

setOutputFrame sets the frame to output laser scan

Parameters
frame

Definition at line 36 of file laserscan_kinect.h.

void laserscan_kinect::LaserScanKinect::setPublishDbgImgEnable ( const bool  enable)
inline

setPublishDbgImgEnable

Parameters
enable

Definition at line 100 of file laserscan_kinect.h.

void laserscan_kinect::LaserScanKinect::setRangeLimits ( const float  rmin,
const float  rmax 
)

setRangeLimits sets depth sensor min and max ranges

Parameters
rminMinimum sensor range (below it is death zone) in meters.
rmaxMaximum sensor range in meters.

Definition at line 102 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::setScanConfigurated ( const bool  configured)
inline

setScanConfigurated sets the configuration status

Parameters
enable

Definition at line 95 of file laserscan_kinect.h.

void laserscan_kinect::LaserScanKinect::setScanHeight ( const int  scan_height)

setScanHeight sets height of depth image which will be used in conversion process

Parameters
scan_heightHeight of used part of depth image in pixels.

Definition at line 119 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::setSensorMountHeight ( const float  height)

setSensorMountHeight sets the height of sensor mount (in meters)

Definition at line 139 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::setSensorTiltAngle ( const float  angle)

setSensorTiltAngle sets the sensor tilt angle (in degrees)

Parameters
angle

Definition at line 149 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::setThreadsNum ( unsigned  threads_num)

Definition at line 169 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::setTiltCompensation ( const bool  enable)
inline

setTiltCompensation enables or disables the feature which compensates sensor tilt

Parameters
enable

Definition at line 89 of file laserscan_kinect.h.

Member Data Documentation

image_geometry::PinholeCameraModel laserscan_kinect::LaserScanKinect::cam_model_
private

Class for managing CameraInfo messages.

Definition at line 162 of file laserscan_kinect.h.

bool laserscan_kinect::LaserScanKinect::cam_model_update_ {false}
private

If continously calibration update required.

Definition at line 149 of file laserscan_kinect.h.

sensor_msgs::ImagePtr laserscan_kinect::LaserScanKinect::dbg_image_
private

Definition at line 179 of file laserscan_kinect.h.

unsigned laserscan_kinect::LaserScanKinect::depth_img_row_step_ {0}
private

Row step in depth map processing.

Definition at line 148 of file laserscan_kinect.h.

std::vector<float> laserscan_kinect::LaserScanKinect::dist_to_ground_corrected
private

Calculated maximal distances for measurements not included as floor.

Definition at line 171 of file laserscan_kinect.h.

float laserscan_kinect::LaserScanKinect::ground_margin_ {0}
private

Margin for floor remove feature (in meters)

Definition at line 153 of file laserscan_kinect.h.

bool laserscan_kinect::LaserScanKinect::ground_remove_enable_ {false}
private

Determines if remove ground from output scan.

Definition at line 152 of file laserscan_kinect.h.

int laserscan_kinect::LaserScanKinect::image_vertical_offset_ {0}
private

The vertical offset of image based on calibration data.

Definition at line 177 of file laserscan_kinect.h.

bool laserscan_kinect::LaserScanKinect::is_scan_msg_configured_ {false}
private

Determines if laser scan message is configurated.

Definition at line 165 of file laserscan_kinect.h.

std::list<std::pair<int, int> > laserscan_kinect::LaserScanKinect::min_dist_points_indices_
private

Definition at line 180 of file laserscan_kinect.h.

std::string laserscan_kinect::LaserScanKinect::output_frame_id_
private

Output frame_id for laserscan message.

Definition at line 144 of file laserscan_kinect.h.

std::mutex laserscan_kinect::LaserScanKinect::points_indices_mutex_
private

Definition at line 182 of file laserscan_kinect.h.

bool laserscan_kinect::LaserScanKinect::publish_dbg_image_ {false}
private

Determines if debug image should be published.

Definition at line 155 of file laserscan_kinect.h.

float laserscan_kinect::LaserScanKinect::range_max_ {0}
private

Stores the current maximum range to use.

Definition at line 146 of file laserscan_kinect.h.

float laserscan_kinect::LaserScanKinect::range_min_ {0}
private

Stores the current minimum range to use.

Definition at line 145 of file laserscan_kinect.h.

unsigned laserscan_kinect::LaserScanKinect::scan_height_ {0}
private

Number of pixel rows used to scan computing.

Definition at line 147 of file laserscan_kinect.h.

sensor_msgs::LaserScanPtr laserscan_kinect::LaserScanKinect::scan_msg_
private

Published scan message.

Definition at line 159 of file laserscan_kinect.h.

std::vector<unsigned> laserscan_kinect::LaserScanKinect::scan_msg_index_
private

Calculated laser scan msg indexes for each depth image column.

Definition at line 168 of file laserscan_kinect.h.

std::mutex laserscan_kinect::LaserScanKinect::scan_msg_mutex_
private

Definition at line 183 of file laserscan_kinect.h.

float laserscan_kinect::LaserScanKinect::sensor_mount_height_ {0}
private

Height of sensor mount from ground.

Definition at line 150 of file laserscan_kinect.h.

float laserscan_kinect::LaserScanKinect::sensor_tilt_angle_ {0}
private

Angle of sensor tilt.

Definition at line 151 of file laserscan_kinect.h.

unsigned laserscan_kinect::LaserScanKinect::threads_num_ {1}
private

Determines threads number used in image processing.

Definition at line 156 of file laserscan_kinect.h.

bool laserscan_kinect::LaserScanKinect::tilt_compensation_enable_ {false}
private

Determines if tilt compensation feature is on.

Definition at line 154 of file laserscan_kinect.h.

std::vector<float> laserscan_kinect::LaserScanKinect::tilt_compensation_factor_
private

Calculated sensor tilt compensation factors.

Definition at line 174 of file laserscan_kinect.h.


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


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