Starting to add unit tests for PointCloud2

git-svn-id: https://code.ros.org/svn/ros-pkg/stacks/laser_pipeline/trunk@35266 eb33c2ac-9c88-4c90-87e0-44a10359b0c3
This commit is contained in:
Jeremy Leibs
2011-01-15 02:50:28 +00:00
parent 92e6c455c6
commit 3a00224b10
3 changed files with 149 additions and 4 deletions

View File

@@ -63,6 +63,7 @@ namespace laser_geometry
*/
enum ChannelOption
{
None = 0x00, //!< Enable no channels
Intensity = 0x01, //!< Enable "intensities" channel
Index = 0x02, //!< Enable "index" channel
Distance = 0x04, //!< Enable "distances" channel
@@ -232,14 +233,14 @@ namespace laser_geometry
* channel_option::Intensity, channel_option::Index,
* channel_option::Distance, channel_option::Timestamp.
*/
void transformLaserScanToPointCloud2(const std::string &target_frame,
void transformLaserScanToPointCloud(const std::string &target_frame,
const sensor_msgs::LaserScan &scan_in,
sensor_msgs::PointCloud2 &cloud_out,
tf::Transformer &tf,
double range_cutoff = -1.0,
int channel_options = channel_option::Default)
{
transformLaserScanToPointCloud2_(target_frame, scan_in, cloud_out, tf, range_cutoff, channel_options);
transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, tf, range_cutoff, channel_options);
}
protected:
@@ -280,7 +281,7 @@ namespace laser_geometry
bool preservative);
//! Internal hidden representation of transformLaserScanToPointCloud2
void transformLaserScanToPointCloud2_ (const std::string &target_frame,
void transformLaserScanToPointCloud_ (const std::string &target_frame,
const sensor_msgs::LaserScan &scan_in,
sensor_msgs::PointCloud2 &cloud_out,
tf::Transformer &tf,