|
From: <tf...@us...> - 2008-12-04 02:50:28
|
Revision: 7556
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7556&view=rev
Author: tfoote
Date: 2008-12-04 02:50:26 +0000 (Thu, 04 Dec 2008)
Log Message:
-----------
moving laser_scan_utils to laser_scan as per API review
Modified Paths:
--------------
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/manifest.xml
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh
pkg/trunk/highlevel/highlevel_controllers/manifest.xml
pkg/trunk/nav/wavefront_player/manifest.xml
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/util/laser_scan/CMakeLists.txt
pkg/trunk/util/laser_scan/manifest.xml
pkg/trunk/util/laser_scan/src/laser_scan.cc
pkg/trunk/util/rosTF/include/rosTF/rosTF.h
pkg/trunk/util/rosTF/manifest.xml
pkg/trunk/util/tf/include/tf/transform_listener.h
pkg/trunk/util/tf/manifest.xml
pkg/trunk/world_models/world_3d_map/manifest.xml
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Added Paths:
-----------
pkg/trunk/util/laser_scan/
pkg/trunk/util/laser_scan/include/laser_scan/
pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h
Removed Paths:
-------------
pkg/trunk/util/laser_scan_utils/
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -8,7 +8,7 @@
<url>http://pr.willowgarage.com/wiki/Point_clouds_from_scanning_URG</url>
<depend package="roscpp"/>
<depend package="std_msgs"/>
- <depend package="laser_scan_utils"/>
+ <depend package="laser_scan"/>
<depend package="tf"/>
<depend package="pr2_mechanism_controllers"/>
</package>
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-12-04 02:50:26 UTC (rev 7556)
@@ -75,7 +75,7 @@
#include "point_cloud_assembler/BuildCloud.h"
// Laser projection
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
#include "math.h"
Modified: pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh 2008-12-04 02:50:26 UTC (rev 7556)
@@ -57,7 +57,7 @@
#include <tf/transform_broadcaster.h>
// Laser projection
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
// Thread suppport
#include <rosthread/member_thread.h>
Modified: pkg/trunk/highlevel/highlevel_controllers/manifest.xml
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/highlevel/highlevel_controllers/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -18,7 +18,7 @@
<depend package="pr2_msgs"/>
<depend package="kinematic_planning"/>
<depend package="trajectory_rollout"/>
- <depend package="laser_scan_utils" />
+ <depend package="laser_scan" />
<depend package="costmap_2d"/>
<depend package="tf"/>
<depend package="ompl"/>
Modified: pkg/trunk/nav/wavefront_player/manifest.xml
===================================================================
--- pkg/trunk/nav/wavefront_player/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/nav/wavefront_player/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -5,7 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp" />
<depend package="player" />
- <depend package="laser_scan_utils" />
+ <depend package="laser_scan" />
<depend package="std_srvs" />
<depend package="tf"/>
<export>
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-04 02:50:26 UTC (rev 7556)
@@ -128,7 +128,7 @@
#include <tf/message_notifier.h>
//Laser projection
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
// For time support
#include <ros/time.h>
Modified: pkg/trunk/util/laser_scan/CMakeLists.txt
===================================================================
--- pkg/trunk/util/laser_scan_utils/CMakeLists.txt 2008-11-13 06:16:44 UTC (rev 6666)
+++ pkg/trunk/util/laser_scan/CMakeLists.txt 2008-12-04 02:50:26 UTC (rev 7556)
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.6)
include(rosbuild)
-rospack(laser_scan_utils)
+rospack(laser_scan)
rospack_add_library(laser_scan src/laser_scan.cc )
\ No newline at end of file
Added: pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h
===================================================================
--- pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h (rev 0)
+++ pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h 2008-12-04 02:50:26 UTC (rev 7556)
@@ -0,0 +1,119 @@
+/*
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ * * Neither the name of the Willow Garage, Inc. nor the names of its
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef LASER_SCAN_UTILS_LASERSCAN_H
+#define LASER_SCAN_UTILS_LASERSCAN_H
+
+#include <map>
+#include <iostream>
+#include <sstream>
+
+#include <newmat10/newmat.h>
+#include <newmat10/newmatio.h>
+#include <newmat10/newmatap.h>
+
+#include "std_msgs/LaserScan.h"
+#include "std_msgs/PointCloud.h"
+#include "std_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_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.
+ */
+ class LaserProjection
+ {
+ public:
+ /** \brief Destructor to deallocate stored unit vectors */
+ ~LaserProjection();
+
+ /** \brief Project Laser Scan
+ * This will project a laser scan from a linear array into a 3D point cloud
+ * \param scan_in The input laser scan
+ * \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 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.
+ */
+ void projectLaser(const std_msgs::LaserScan& scan_in, std_msgs::PointCloud & cloud_out, double range_cutoff=-1.0, bool preservative = false);
+
+
+ /** \brief Return the unit vectors for this configuration
+ * Return the unit vectors for this configuration.
+ * if they have not been calculated yet, calculate them and store them
+ * Otherwise it will return them from memory. */
+ NEWMAT::Matrix& getUnitVectors(float angle_max, float angle_min, float angle_increment);
+ private:
+ ///The map of pointers to stored values
+ std::map<std::string,NEWMAT::Matrix*> unit_vector_map_;
+
+ };
+
+ /** \brief A class to provide median filtering of laser scans */
+ class LaserMedianFilter
+ {
+ public:
+ enum MedianMode_t { MEDIAN_TRAILING, MEDIAN_DOWNSAMPLE};
+
+ /** \brief Constructor
+ * \param averaging_length How many scans to average over.
+ * \param num_ranges Whether to downsample and return or compute a rolling median over the last n scans
+ * \param mode What mode to operate in Trailing or Downsampling (Effectively changes returning true every time or every 3)
+ */
+ LaserMedianFilter(unsigned int averaging_length, unsigned int num_ranges, MedianMode_t mode = MEDIAN_DOWNSAMPLE);
+ /** \brief Add a scan to the filter
+ * \param scan_in The new scan to filter
+ * return whether there is a new output to get */
+ bool addScan(const std_msgs::LaserScan& scan_in);
+ /** \brief get the Filtered results
+ * \param scan_result The scan to fill with the median results */
+ void getMedian(std_msgs::LaserScan& scan_result);
+
+
+ private:
+ unsigned int current_packet_num_; ///The number of scans recieved
+ NEWMAT::Matrix range_data_; ///Storage for range_data
+ NEWMAT::Matrix intensity_data_; ///Storage for intensity data
+ unsigned int filter_length_; ///How many scans to average over
+ unsigned int num_ranges_; /// How many data point are in each row
+ MedianMode_t mode_; ///Whether to return true every time or once every 3
+
+ std_msgs::LaserScan temp_scan_; /** \todo cache only shallow info not full scan */
+
+ };
+
+
+}
+#endif //LASER_SCAN_UTILS_LASERSCAN_H
Modified: pkg/trunk/util/laser_scan/manifest.xml
===================================================================
--- pkg/trunk/util/laser_scan_utils/manifest.xml 2008-11-13 06:16:44 UTC (rev 6666)
+++ pkg/trunk/util/laser_scan/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -6,7 +6,7 @@
</description>
<author>Tully Foote</author>
<license>BSD</license>
-<review status="unreviewed" notes="API review in progress (Tully)"/>
+<review status="API conditionally cleared" notes="API followup in progress (Tully)"/>
<url>http://pr.willowgarage.com</url>
<depend package="newmat10"/>
<depend package="std_msgs"/>
Modified: pkg/trunk/util/laser_scan/src/laser_scan.cc
===================================================================
--- pkg/trunk/util/laser_scan_utils/src/laser_scan.cc 2008-11-13 06:16:44 UTC (rev 6666)
+++ pkg/trunk/util/laser_scan/src/laser_scan.cc 2008-12-04 02:50:26 UTC (rev 7556)
@@ -27,7 +27,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*/
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
#include <algorithm>
namespace laser_scan{
Modified: pkg/trunk/util/rosTF/include/rosTF/rosTF.h
===================================================================
--- pkg/trunk/util/rosTF/include/rosTF/rosTF.h 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/util/rosTF/include/rosTF/rosTF.h 2008-12-04 02:50:26 UTC (rev 7556)
@@ -45,7 +45,7 @@
#include "rosTF/TransformArray.h"
#include "libTF/libTF.h"
#include "std_msgs/PointCloud.h"
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
/** \brief A basic ROS client library for libTF
Modified: pkg/trunk/util/rosTF/manifest.xml
===================================================================
--- pkg/trunk/util/rosTF/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/util/rosTF/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -13,7 +13,7 @@
</export>
<depend package="libTF"/>
<depend package="roscpp"/>
-<depend package="laser_scan_utils"/>
+<depend package="laser_scan"/>
<depend package="std_msgs"/>
<depend package="newmat10"/>
</package>
Modified: pkg/trunk/util/tf/include/tf/transform_listener.h
===================================================================
--- pkg/trunk/util/tf/include/tf/transform_listener.h 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/util/tf/include/tf/transform_listener.h 2008-12-04 02:50:26 UTC (rev 7556)
@@ -33,7 +33,7 @@
#define TF_TRANSFORMLISTENER_H
#include "std_msgs/PointCloud.h"
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
#include "tf/tfMessage.h"
#include "tf/tf.h"
#include "ros/node.h"
Modified: pkg/trunk/util/tf/manifest.xml
===================================================================
--- pkg/trunk/util/tf/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/util/tf/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -15,7 +15,7 @@
<depend package="std_msgs"/>
<depend package="roscpp"/>
<depend package="bullet"/>
-<depend package="laser_scan_utils"/>
+<depend package="laser_scan"/>
<depend package="rosTF"/> <!-- For backwards compatibility only Fixme remove /-->
<depend package="boost"/>
<export>
Modified: pkg/trunk/world_models/world_3d_map/manifest.xml
===================================================================
--- pkg/trunk/world_models/world_3d_map/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/world_models/world_3d_map/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -6,6 +6,7 @@
<depend package="roscpp" />
<depend package="std_msgs" />
<depend package="rosTF" />
+<depend package="laser_scan" />
<depend package="random_utils" />
<depend package="wg_robot_description_parser" />
<depend package="planning_models" />
Modified: pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
===================================================================
--- pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-04 02:50:26 UTC (rev 7556)
@@ -114,7 +114,7 @@
#include <random_utils/random_utils.h>
// Laser projection
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
#include <deque>
#include <cmath>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|