Public Member Functions | Private Member Functions | Private Attributes
depthimage_to_laserscan::DepthImageToLaserScan Class Reference

#include <DepthImageToLaserScan.h>

List of all members.

Public Member Functions

sensor_msgs::LaserScanPtr convert_msg (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
 DepthImageToLaserScan ()
void set_output_frame (const std::string output_frame_id)
void set_range_limits (const float range_min, const float range_max)
void set_scan_height (const int scan_height)
void set_scan_time (const float scan_time)
 ~DepthImageToLaserScan ()

Private Member Functions

double angle_between_rays (const cv::Point3d &ray1, const cv::Point3d &ray2) const
template<typename T >
void convert (const sensor_msgs::ImageConstPtr &depth_msg, const image_geometry::PinholeCameraModel &cam_model, const sensor_msgs::LaserScanPtr &scan_msg, const int &scan_height) const
double magnitude_of_ray (const cv::Point3d &ray) const
bool use_point (const float new_value, const float old_value, const float range_min, const float range_max) const

Private Attributes

image_geometry::PinholeCameraModel cam_model_
 image_geometry helper class for managing sensor_msgs/CameraInfo messages.
std::string output_frame_id_
 Output frame_id for each laserscan. This is likely NOT the camera's frame_id.
float range_max_
 Stores the current maximum range to use.
float range_min_
 Stores the current minimum range to use.
int scan_height_
 Number of pixel rows to use when producing a laserscan from an area.
float scan_time_
 Stores the time between scans.

Detailed Description

Definition at line 48 of file DepthImageToLaserScan.h.


Constructor & Destructor Documentation

Definition at line 38 of file DepthImageToLaserScan.cpp.

Definition at line 41 of file DepthImageToLaserScan.cpp.


Member Function Documentation

double DepthImageToLaserScan::angle_between_rays ( const cv::Point3d &  ray1,
const cv::Point3d &  ray2 
) const [private]

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 48 of file DepthImageToLaserScan.cpp.

template<typename T >
void depthimage_to_laserscan::DepthImageToLaserScan::convert ( const sensor_msgs::ImageConstPtr &  depth_msg,
const image_geometry::PinholeCameraModel cam_model,
const sensor_msgs::LaserScanPtr &  scan_msg,
const int &  scan_height 
) const [inline, private]

Converts the depth image to a laserscan using the DepthTraits to assist.

This uses a method to inverse project each pixel into a LaserScan angular increment. This method first projects the pixel forward into Cartesian coordinates, then calculates the range and angle for this point. When multiple points coorespond to a specific angular measurement, then the shortest range is used.

Parameters:
depth_msgThe UInt16 or Float32 encoded depth message.
cam_modelThe image_geometry camera model for this image.
scan_msgThe output LaserScan.
scan_heightThe number of vertical pixels to feed into each angular_measurement.

Definition at line 170 of file DepthImageToLaserScan.h.

sensor_msgs::LaserScanPtr DepthImageToLaserScan::convert_msg ( 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 or Float32 encoding) 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 83 of file DepthImageToLaserScan.cpp.

double DepthImageToLaserScan::magnitude_of_ray ( const cv::Point3d &  ray) const [private]

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 44 of file DepthImageToLaserScan.cpp.

void DepthImageToLaserScan::set_output_frame ( const std::string  output_frame_id)

Sets the frame_id for the output LaserScan.

Output frame_id for the LaserScan. Will probably NOT be the same frame_id as the depth image. Example: For OpenNI cameras, this should be set to 'camera_depth_frame' while the camera uses 'camera_depth_optical_frame'.

Parameters:
output_frame_idFrame_id to use for the output sensor_msgs::LaserScan.

Definition at line 160 of file DepthImageToLaserScan.cpp.

void DepthImageToLaserScan::set_range_limits ( const float  range_min,
const float  range_max 
)

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

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

Parameters:
range_minMinimum range to assign points to the laserscan, also minimum range to use points in the output scan.
range_maxMaximum range to use points in the output scan.

Definition at line 151 of file DepthImageToLaserScan.cpp.

void DepthImageToLaserScan::set_scan_height ( const int  scan_height)

Sets the number of image rows to use in the output LaserScan.

scan_height is the number of rows (pixels) to use in the output. This will provide scan_height number of radii for each angular increment. The output scan will output the closest radius that is still not smaller than range_min. This function can be used to vertically compress obstacles into a single LaserScan.

Parameters:
scan_heightNumber of pixels centered around the center of the image to compress into the LaserScan.

Definition at line 156 of file DepthImageToLaserScan.cpp.

void DepthImageToLaserScan::set_scan_time ( const float  scan_time)

Sets the scan time parameter.

This function stores the desired value for scan_time. In sensor_msgs::LaserScan, scan_time is defined as "time between scans [seconds]". This value is not easily calculated from consquetive messages, and is thus left to the user to set correctly.

Parameters:
scan_timeThe value to use for outgoing sensor_msgs::LaserScan.

Definition at line 147 of file DepthImageToLaserScan.cpp.

bool DepthImageToLaserScan::use_point ( const float  new_value,
const float  old_value,
const float  range_min,
const float  range_max 
) const [private]

Determines whether or not new_value should replace old_value in the LaserScan.

Uses the values of range_min, and range_max to determine if new_value is a valid point. Then it determines if new_value is 'more ideal' (currently shorter range) than old_value.

Parameters:
new_valueThe current calculated range.
old_valueThe current range in the output LaserScan.
range_minThe minimum acceptable range for the output LaserScan.
range_maxThe maximum acceptable range for the output LaserScan.
Returns:
If true, insert new_value into the output LaserScan.

Definition at line 55 of file DepthImageToLaserScan.cpp.


Member Data Documentation

image_geometry helper class for managing sensor_msgs/CameraInfo messages.

Definition at line 214 of file DepthImageToLaserScan.h.

Output frame_id for each laserscan. This is likely NOT the camera's frame_id.

Definition at line 220 of file DepthImageToLaserScan.h.

Stores the current maximum range to use.

Definition at line 218 of file DepthImageToLaserScan.h.

Stores the current minimum range to use.

Definition at line 217 of file DepthImageToLaserScan.h.

Number of pixel rows to use when producing a laserscan from an area.

Definition at line 219 of file DepthImageToLaserScan.h.

Stores the time between scans.

Definition at line 216 of file DepthImageToLaserScan.h.


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


depthimage_to_laserscan
Author(s): Chad Rockey
autogenerated on Sun Oct 5 2014 23:25:32