Deprecating preservative and fixing up documentation.

git-svn-id: https://code.ros.org/svn/ros-pkg/stacks/laser_pipeline/trunk@24323 eb33c2ac-9c88-4c90-87e0-44a10359b0c3
This commit is contained in:
Jeremy Leibs 2009-09-22 21:26:12 +00:00
parent 5bd2038978
commit f7b67fb1b8
6 changed files with 61 additions and 53 deletions

View File

@ -8,9 +8,9 @@ rospack_add_boost_directories()
#todo integrate this #todo integrate this
rospack_add_library(laser_processor src/laser_processor.cpp) rospack_add_library(laser_processor src/laser_processor.cpp)
rospack_add_library(laser_scan src/laser_scan.cc ) rospack_add_library(laser_geometry src/laser_geometry.cpp )
rospack_link_boost(laser_scan thread) rospack_link_boost(laser_geometry thread)
rospack_add_gtest(test/projection_test test/projection_test.cpp) rospack_add_gtest(test/projection_test test/projection_test.cpp)
target_link_libraries (test/projection_test laser_scan) target_link_libraries (test/projection_test laser_geometry)

View File

@ -42,13 +42,6 @@
#include "sensor_msgs/PointCloud.h" #include "sensor_msgs/PointCloud.h"
#include "sensor_msgs/PointCloud.h" #include "sensor_msgs/PointCloud.h"
/* \mainpage
* This is a class for laser scan utilities.
* \todo The first goal will be to project laser scans into point clouds efficiently.
* The second goal is to provide median filtering.
* \todo Other potential additions are upsampling and downsampling algorithms for the scans.
*/
namespace laser_geometry namespace laser_geometry
{ {
@ -60,8 +53,18 @@ namespace laser_geometry
const int DEFAULT_MASK = (MASK_INTENSITY | MASK_INDEX); const int DEFAULT_MASK = (MASK_INTENSITY | MASK_INDEX);
/** \brief A Class to Project Laser Scan /** \brief A Class to Project Laser Scan
* This class will project laser scans into point clouds, and caches unit vectors *
* between runs so as not to need to recalculate. * This class will project laser scans into point clouds. It caches
* unit vectors between runs (provided the angular resolution of
* your scanner is not changing) to avoid excess computation.
*
* By default all range values less than the scanner min_range, and
* greater than the scanner max_range are removed from the generated
* point cloud, as these are assumed to be invalid. If it is
* important to preserve a mapping between the index of range values
* and points in the cloud, the functions have an optional
* "preservative" argument which will leave placeholder points as
* appropriate.
*/ */
class LaserProjection class LaserProjection
{ {
@ -70,26 +73,56 @@ namespace laser_geometry
~LaserProjection(); ~LaserProjection();
/** \brief Project Laser Scan /** \brief Project Laser Scan
* This will project a laser scan from a linear array into a 3D point cloud *
* Project a single laser scan from a linear array into a 3D
* point cloud. The generated cloud will be in the same frame
* as the original laser scan.
*
* \param scan_in The input laser scan * \param scan_in The input laser scan
* \param cloudOut The output point cloud * \param cloudOut The output point cloud
* \param range_cutoff An additional range cutoff which can be applied which is more limiting than max_range in the scan. * \param range_cutoff An additional range cutoff which can be
* \param preservative Default: false If true all points in scan will be projected, including out of range values. Otherwise they will not be added to the cloud. * applied which is more limiting than max_range in the scan.
* \param A bitwise mask of channels to include
*/ */
void projectLaser (const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud & cloud_out, double range_cutoff=-1.0, bool preservative = false, int mask = DEFAULT_MASK); void projectLaser (const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud & cloud_out, double range_cutoff=-1.0, int mask = DEFAULT_MASK)
{
return projectLaser_ (scan_in, cloud_out, range_cutoff, false, mask);
}
__attribute__ ((deprecated)) void projectLaser (const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud & cloud_out, double range_cutoff, bool preservative, int mask = DEFAULT_MASK)
{
return projectLaser_ (scan_in, cloud_out, range_cutoff, preservative, mask);
}
/** \brief Transform a sensor_msgs::LaserScan into a PointCloud in target frame */ /** \brief Transform a sensor_msgs::LaserScan into a PointCloud in target frame */
void transformLaserScanToPointCloud (const std::string& target_frame, sensor_msgs::PointCloud & cloudOut, const sensor_msgs::LaserScan & scanIn, tf::Transformer & tf, int mask = DEFAULT_MASK, bool preservative = false); void transformLaserScanToPointCloud (const std::string& target_frame, sensor_msgs::PointCloud & cloudOut, const sensor_msgs::LaserScan & scanIn, tf::Transformer & tf, int mask = DEFAULT_MASK)
{
return transformLaserScanToPointCloud_ (target_frame, cloudOut, scanIn, tf, mask, false);
}
__attribute__ ((deprecated)) void transformLaserScanToPointCloud (const std::string& target_frame, sensor_msgs::PointCloud & cloudOut, const sensor_msgs::LaserScan & scanIn, tf::Transformer & tf, int mask, bool preservative)
{
return transformLaserScanToPointCloud_ (target_frame, cloudOut, scanIn, tf, mask, preservative);
}
/** \brief Return the unit vectors for this configuration /** \brief Return the unit vectors for this configuration
* Return the unit vectors for this configuration. * Return the unit vectors for this configuration.
* These are dynamically generated and allocated on first request * These are dynamically generated and allocated on first request
* and will be valid until destruction of this node. */ * and will be valid until destruction of this node. */
const boost::numeric::ublas::matrix<double>& getUnitVectors(float angle_max, float angle_min, float angle_increment, unsigned int length); __attribute__ ((deprecated)) const boost::numeric::ublas::matrix<double>& getUnitVectors(float angle_max, float angle_min, float angle_increment, unsigned int length)
{
return getUnitVectors_(angle_max, angle_min, angle_increment, length);
}
private: private:
void projectLaser_ (const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud & cloud_out, double range_cutoff, bool preservative, int mask = DEFAULT_MASK);
void transformLaserScanToPointCloud_ (const std::string& target_frame, sensor_msgs::PointCloud & cloudOut, const sensor_msgs::LaserScan & scanIn, tf::Transformer & tf, int mask, bool preservative);
const boost::numeric::ublas::matrix<double>& getUnitVectors_(float angle_max, float angle_min, float angle_increment, unsigned int length);
///The map of pointers to stored values ///The map of pointers to stored values
std::map<std::string,boost::numeric::ublas::matrix<double>* > unit_vector_map_; std::map<std::string,boost::numeric::ublas::matrix<double>* > unit_vector_map_;

View File

@ -32,10 +32,6 @@
* POSSIBILITY OF SUCH DAMAGE. * POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/ *********************************************************************/
/*! \mainpage
* \htmlinclude manifest.html
*/
//! A namespace containing the laser processor helper classes //! A namespace containing the laser processor helper classes

View File

@ -1,29 +1,8 @@
/** /**
\mainpage \mainpage
This package is designed to provide helper functions/classes for working with laser scans. It provides library functionality only. \htmlinclude manifest.html
\section projection Laser Scan Projection to Point Cloud \section projection Laser Scan Projection to Point Cloud
laser_scan::LaserProjection provides a simple method to project laser scans into point clouds while discarding out-of-range measurements. laser_geometry::LaserProjection provides a simple method to project laser scans into point clouds while discarding out-of-range measurements.
\section filters Laser Scan Filters
There are a number of filters that this class provides.
There is also a factory class to provide easy creation and chaining of laser scan filter
as a input to any process.
\todo implement and document (they're currently basically standalone nodes)
\subsection median Median Filter
laser_scan::LaserMedianFilter applies a median filter to scans both in range and intensity.
\subsection mean Mean Filter
\todo Document
\subsection shadows Scan Shadows Filter
\todo document
\subsection intensity Intensity Filter
\todo document
*/ */

View File

@ -11,12 +11,12 @@ scanners.
<author>Tully Foote</author> <author>Tully Foote</author>
<license>BSD</license> <license>BSD</license>
<review status="API cleared" notes=""/> <review status="API cleared" notes=""/>
<url>http://ros.org/wiki/laser_scan</url> <url>http://ros.org/wiki/laser_geometry</url>
<depend package="sensor_msgs"/> <depend package="sensor_msgs"/>
<depend package="roscpp"/> <depend package="roscpp"/>
<depend package="tf"/> <depend package="tf"/>
<depend package="angles"/> <depend package="angles"/>
<export> <export>
<cpp cflags="-I${prefix}/include -I${prefix}/msg/cpp" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -llaser_scan -llaser_processor"/> <cpp cflags="-I${prefix}/include -I${prefix}/msg/cpp" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -llaser_geometry -llaser_processor"/>
</export> </export>
</package> </package>

View File

@ -34,7 +34,7 @@ namespace laser_geometry
{ {
void void
LaserProjection::projectLaser (const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud & cloud_out, double range_cutoff, LaserProjection::projectLaser_ (const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud & cloud_out, double range_cutoff,
bool preservative, int mask) bool preservative, int mask)
{ {
boost::numeric::ublas::matrix<double> ranges(2, scan_in.get_ranges_size()); boost::numeric::ublas::matrix<double> ranges(2, scan_in.get_ranges_size());
@ -49,7 +49,7 @@ namespace laser_geometry
//Do the projection //Do the projection
// NEWMAT::Matrix output = NEWMAT::SP(ranges, getUnitVectors(scan_in.angle_min, scan_in.angle_max, scan_in.angle_increment)); // NEWMAT::Matrix output = NEWMAT::SP(ranges, getUnitVectors(scan_in.angle_min, scan_in.angle_max, scan_in.angle_increment));
boost::numeric::ublas::matrix<double> output = element_prod(ranges, getUnitVectors(scan_in.angle_min, scan_in.angle_max, scan_in.angle_increment, scan_in.get_ranges_size())); boost::numeric::ublas::matrix<double> output = element_prod(ranges, getUnitVectors_(scan_in.angle_min, scan_in.angle_max, scan_in.angle_increment, scan_in.get_ranges_size()));
//Stuff the output cloud //Stuff the output cloud
cloud_out.header = scan_in.header; cloud_out.header = scan_in.header;
@ -150,7 +150,7 @@ namespace laser_geometry
cloud_out.channels[d].set_values_size(count); cloud_out.channels[d].set_values_size(count);
}; };
const boost::numeric::ublas::matrix<double>& LaserProjection::getUnitVectors(float angle_min, float angle_max, float angle_increment, unsigned int length) const boost::numeric::ublas::matrix<double>& LaserProjection::getUnitVectors_(float angle_min, float angle_max, float angle_increment, unsigned int length)
{ {
if (angle_min >= angle_max) if (angle_min >= angle_max)
{ {
@ -193,7 +193,7 @@ const boost::numeric::ublas::matrix<double>& LaserProjection::getUnitVectors(flo
}; };
void void
LaserProjection::transformLaserScanToPointCloud (const std::string &target_frame, sensor_msgs::PointCloud &cloud_out, const sensor_msgs::LaserScan &scan_in, LaserProjection::transformLaserScanToPointCloud_ (const std::string &target_frame, sensor_msgs::PointCloud &cloud_out, const sensor_msgs::LaserScan &scan_in,
tf::Transformer& tf, int mask, bool preservative) tf::Transformer& tf, int mask, bool preservative)
{ {
cloud_out.header = scan_in.header; cloud_out.header = scan_in.header;
@ -253,7 +253,7 @@ const boost::numeric::ublas::matrix<double>& LaserProjection::getUnitVectors(flo
///\todo this can be optimized ///\todo this can be optimized
sensor_msgs::PointCloud intermediate; //optimize out sensor_msgs::PointCloud intermediate; //optimize out
projectLaser (scan_in, intermediate, -1.0, true, mask); projectLaser_ (scan_in, intermediate, -1.0, true, mask);
// Extract transforms for the beginning and end of the laser scan // Extract transforms for the beginning and end of the laser scan
ros::Time start_time = scan_in.header.stamp ; ros::Time start_time = scan_in.header.stamp ;
@ -334,4 +334,4 @@ const boost::numeric::ublas::matrix<double>& LaserProjection::getUnitVectors(flo
} }
} //laser_scan } //laser_geometry