Public Member Functions | Private Member Functions | Private Attributes
laserscan_kinect::LaserScanKinect Class Reference

#include <laserscan_kinect.h>

List of all members.

Public Member Functions

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

Private Member Functions

double angleBetweenRays (const cv::Point3d &ray1, const cv::Point3d &ray2) const
 angleBetweenRays calculate angle between two rays in degrees
void calcGroundDistancesForImgRows (double vertical_fov)
 calcGroundDistancesForImgRows calculate coefficients used in ground removing from scan
void calcScanMsgIndexForImgCols (const sensor_msgs::ImageConstPtr &depth_msg)
 calcScanMsgIndexForImgCols
void calcTiltCompensationFactorsForImgRows (double vertical_fov)
 calcTiltCompensationFactorsForImgRows calculate factors used in tilt compensation
void convertDepthToPolarCoords (const sensor_msgs::ImageConstPtr &depth_msg)
 convertDepthToPolarCoords finds smallest values in depth image columns
void fieldOfView (double &min, double &max, double x1, double y1, double xc, double yc, double x2, double y2)
 fieldOfView calculate field of view (angle)
double lengthOfVector (const cv::Point3d &ray) const
 lengthOfVector calculate length of 3D vector

Private Attributes

bool cam_model_update_
 If continously calibration update required.
image_geometry::PinholeCameraModel camera_model_
 Class for managing CameraInfo messages.
unsigned int depth_img_row_step_
 Row step in depth map processing.
std::vector< unsigned int > dist_to_ground_
 Calculated maximal distances for measurements not included as floor.
float ground_margin_
 Margin for floor remove feature (in meters)
bool ground_remove_enable_
 Determines if remove ground from output scan.
bool is_scan_msg_configurated_
 Determines if laser scan message is configurated.
std::string output_frame_id_
 Output frame_id for laserscan message.
float range_max_
 Stores the current maximum range to use.
float range_min_
 Stores the current minimum range to use.
unsigned int scan_height_
 Number of pixel rows used to scan computing.
sensor_msgs::LaserScanPtr scan_msg_
 Published scan message.
std::vector< unsigned int > scan_msg_index_
 Calculated laser scan msg indexes for each depth image column.
float sensor_mount_height_
 Height of sensor mount from ground.
float sensor_tilt_angle_
 Angle of sensor tilt.
bool tilt_compensation_enable_
 Determines if tilt compensation feature is on.
std::vector< double > tilt_compensation_factor_
 Calculated sensor tilt compensation factors.

Detailed Description

Definition at line 58 of file laserscan_kinect.h.


Constructor & Destructor Documentation

Definition at line 50 of file laserscan_kinect.cpp.

Definition at line 62 of file laserscan_kinect.h.


Member Function Documentation

double LaserScanKinect::angleBetweenRays ( const cv::Point3d &  ray1,
const cv::Point3d &  ray2 
) const [private]

angleBetweenRays calculate angle between two rays in degrees

Parameters:
ray1
ray2
Returns:

Definition at line 231 of file laserscan_kinect.cpp.

void LaserScanKinect::calcGroundDistancesForImgRows ( double  vertical_fov) [private]

calcGroundDistancesForImgRows calculate coefficients used in ground removing from scan

Parameters:
vertical_fov

Definition at line 261 of file laserscan_kinect.cpp.

void LaserScanKinect::calcScanMsgIndexForImgCols ( const sensor_msgs::ImageConstPtr &  depth_msg) [private]

calcScanMsgIndexForImgCols

Parameters:
depth_msg

Definition at line 306 of file laserscan_kinect.cpp.

void LaserScanKinect::calcTiltCompensationFactorsForImgRows ( double  vertical_fov) [private]

calcTiltCompensationFactorsForImgRows calculate factors used in tilt compensation

Parameters:
vertical_fov

Definition at line 287 of file laserscan_kinect.cpp.

void LaserScanKinect::convertDepthToPolarCoords ( const sensor_msgs::ImageConstPtr &  depth_msg) [private]

convertDepthToPolarCoords finds smallest values in depth image columns

Parameters:
depth_msg

Definition at line 318 of file laserscan_kinect.cpp.

void LaserScanKinect::fieldOfView ( double &  min,
double &  max,
double  x1,
double  y1,
double  xc,
double  yc,
double  x2,
double  y2 
) [private]

fieldOfView calculate field of view (angle)

Parameters:
min
max
x1
y1
xc
yc
x2
y2

Definition at line 239 of file laserscan_kinect.cpp.

double LaserScanKinect::lengthOfVector ( const cv::Point3d &  ray) const [private]

lengthOfVector calculate length of 3D vector

Parameters:
ray
Returns:

Definition at line 225 of file laserscan_kinect.cpp.

sensor_msgs::LaserScanPtr LaserScanKinect::prepareLaserScanMsg ( 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 54 of file laserscan_kinect.cpp.

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

setCamModelUpdate sets the camera parameters

Parameters:
enable

Definition at line 103 of file laserscan_kinect.h.

void LaserScanKinect::setDepthImgRowStep ( const int  row_step)

setDepthImgRowStep

Parameters:
row_step

Definition at line 175 of file laserscan_kinect.cpp.

void LaserScanKinect::setGroundMargin ( const float  margin)

setGroundMargin sets the floor margin (in meters)

Parameters:
margin

Definition at line 211 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 119 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 78 of file laserscan_kinect.h.

void 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 144 of file laserscan_kinect.cpp.

void laserscan_kinect::LaserScanKinect::setScanConfigurated ( const bool  configurated) [inline]

setScanConfigurated sets the configuration status

Parameters:
enable

Definition at line 137 of file laserscan_kinect.h.

void 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 163 of file laserscan_kinect.cpp.

void LaserScanKinect::setSensorMountHeight ( const float  height)

setSensorMountHeight sets the height of sensor mount (in meters)

Definition at line 187 of file laserscan_kinect.cpp.

void LaserScanKinect::setSensorTiltAngle ( const float  angle)

setSensorTiltAngle sets the sensor tilt angle (in degrees)

Parameters:
angle

Definition at line 199 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 131 of file laserscan_kinect.h.


Member Data Documentation

If continously calibration update required.

Definition at line 202 of file laserscan_kinect.h.

Class for managing CameraInfo messages.

Definition at line 214 of file laserscan_kinect.h.

Row step in depth map processing.

Definition at line 201 of file laserscan_kinect.h.

std::vector<unsigned int> laserscan_kinect::LaserScanKinect::dist_to_ground_ [private]

Calculated maximal distances for measurements not included as floor.

Definition at line 223 of file laserscan_kinect.h.

Margin for floor remove feature (in meters)

Definition at line 206 of file laserscan_kinect.h.

Determines if remove ground from output scan.

Definition at line 205 of file laserscan_kinect.h.

Determines if laser scan message is configurated.

Definition at line 217 of file laserscan_kinect.h.

Output frame_id for laserscan message.

Definition at line 197 of file laserscan_kinect.h.

Stores the current maximum range to use.

Definition at line 199 of file laserscan_kinect.h.

Stores the current minimum range to use.

Definition at line 198 of file laserscan_kinect.h.

Number of pixel rows used to scan computing.

Definition at line 200 of file laserscan_kinect.h.

sensor_msgs::LaserScanPtr laserscan_kinect::LaserScanKinect::scan_msg_ [private]

Published scan message.

Definition at line 211 of file laserscan_kinect.h.

std::vector<unsigned int> laserscan_kinect::LaserScanKinect::scan_msg_index_ [private]

Calculated laser scan msg indexes for each depth image column.

Definition at line 220 of file laserscan_kinect.h.

Height of sensor mount from ground.

Definition at line 203 of file laserscan_kinect.h.

Angle of sensor tilt.

Definition at line 204 of file laserscan_kinect.h.

Determines if tilt compensation feature is on.

Definition at line 207 of file laserscan_kinect.h.

Calculated sensor tilt compensation factors.

Definition at line 226 of file laserscan_kinect.h.


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


laserscan_kinect
Author(s): Michal Drwiega
autogenerated on Thu Jun 6 2019 22:10:52