|
From: <tf...@us...> - 2009-02-10 05:16:11
|
Revision: 10900
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=10900&view=rev
Author: tfoote
Date: 2009-02-10 05:16:00 +0000 (Tue, 10 Feb 2009)
Log Message:
-----------
LaserScan into laser_scan package #745
Modified Paths:
--------------
pkg/trunk/3rdparty/openrave/manifest.xml
pkg/trunk/calibration/laser_camera_calibration/gatherdata.py
pkg/trunk/calibration/laser_camera_calibration/manifest.xml
pkg/trunk/deprecated/point_cloud_utils/include/point_cloud_utils/scan_assembler.h
pkg/trunk/deprecated/point_cloud_utils/include/point_cloud_utils/timed_scan_assembler.h
pkg/trunk/deprecated/point_cloud_utils/manifest.xml
pkg/trunk/deprecated/point_cloud_utils/src/scan_assembler.cpp
pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp
pkg/trunk/drivers/laser/hokuyo_node/manifest.xml
pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml
pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg
pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp
pkg/trunk/drivers/laser/laser_view/laser_view.cpp
pkg/trunk/drivers/laser/laser_view/manifest.xml
pkg/trunk/drivers/laser/sicktoolbox_wrapper/manifest.xml
pkg/trunk/drivers/laser/sicktoolbox_wrapper/ros/sicklms/sicklms.cpp
pkg/trunk/drivers/robot/katana/nodes/katana_client/katana_client.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/laser_scan_assembler_srv.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler_srv.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/test/test_assembler.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_block_laser.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h
pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp
pkg/trunk/hardware_test/qualification/manifest.xml
pkg/trunk/hardware_test/qualification/scripts/configure_mcbs.py
pkg/trunk/hardware_test/qualification/scripts/confirm_conf.py
pkg/trunk/hardware_test/qualification/scripts/program_mcb.py
pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh
pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/slam_gmapping/manifest.xml
pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
pkg/trunk/nav/slam_gmapping/src/slam_gmapping.h
pkg/trunk/nav/slam_gmapping/src/tftest.cpp
pkg/trunk/simulators/rosstage/manifest.xml
pkg/trunk/simulators/rosstage/rosstage.cc
pkg/trunk/util/laser_scan/CMakeLists.txt
pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h
pkg/trunk/util/laser_scan/include/laser_scan/median_filter.h
pkg/trunk/util/laser_scan/manifest.xml
pkg/trunk/util/laser_scan/src/laser_scan.cc
pkg/trunk/util/laser_scan/src/median_filter.cpp
pkg/trunk/util/laser_scan/src/median_filter_node.cpp
pkg/trunk/util/laser_scan/src/scan_intensity_filter.cpp
pkg/trunk/util/laser_scan/src/scan_shadows_filter.cpp
pkg/trunk/util/logsetta/carmen/carmen_logger/carmen_logger.cpp
pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
pkg/trunk/util/logsetta/laser/laser_extract.cpp
pkg/trunk/util/logsetta/manifest.xml
pkg/trunk/util/mux/manifest.xml
pkg/trunk/util/mux/mux.cpp
pkg/trunk/util/mux/switch.cpp
pkg/trunk/vision/laser_processor/laser_processor.cpp
pkg/trunk/vision/laser_processor/laser_processor.h
pkg/trunk/vision/laser_processor/manifest.xml
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.h
pkg/trunk/visualization/pr2_dashboard/src/pr2_dashboard/reset.py
pkg/trunk/world_models/costmap_2d/manifest.xml
pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp
Added Paths:
-----------
pkg/trunk/drivers/robot/katana/srv/StringString.srv
pkg/trunk/util/laser_scan/msg/
pkg/trunk/util/laser_scan/msg/LaserScan.msg
Modified: pkg/trunk/3rdparty/openrave/manifest.xml
===================================================================
--- pkg/trunk/3rdparty/openrave/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/3rdparty/openrave/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -14,6 +14,7 @@
<depend package="bullet"/>
<depend package="opende"/>
<depend package="std_msgs"/>
+ <depend package="laser_scan"/>
<depend package="roscpp"/>
<versioncontrol type="svn" url="https://openrave.svn.sourceforge.net/svnroot/openrave"/>
<sysdepend os="ubuntu" version="7.04-feisty" package="libglew-dev"/>
Modified: pkg/trunk/calibration/laser_camera_calibration/gatherdata.py
===================================================================
--- pkg/trunk/calibration/laser_camera_calibration/gatherdata.py 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/calibration/laser_camera_calibration/gatherdata.py 2009-02-10 05:16:00 UTC (rev 10900)
@@ -46,7 +46,7 @@
import rospy
from roslib import rostime
-from std_msgs.msg import LaserScan
+from laser_scan.msg import LaserScan
from robot_msgs.msg import MechanismState
from checkerboard_detector.msg import ObjectDetection
import copy
Modified: pkg/trunk/calibration/laser_camera_calibration/manifest.xml
===================================================================
--- pkg/trunk/calibration/laser_camera_calibration/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/calibration/laser_camera_calibration/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -11,6 +11,7 @@
<review status="unreviewed" notes=""/>
<depend package="robot_msgs"/>
<depend package="std_msgs"/>
+ <depend package="laser_scan"/>
<depend package="rosrecord"/>
<depend package="rospy"/>
<depend package="rosoct"/>
Modified: pkg/trunk/deprecated/point_cloud_utils/include/point_cloud_utils/scan_assembler.h
===================================================================
--- pkg/trunk/deprecated/point_cloud_utils/include/point_cloud_utils/scan_assembler.h 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/deprecated/point_cloud_utils/include/point_cloud_utils/scan_assembler.h 2009-02-10 05:16:00 UTC (rev 10900)
@@ -38,7 +38,7 @@
#include "laser_scan/laser_scan.h"
// Messages
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "std_msgs/PointCloud.h"
namespace point_cloud_utils {
@@ -68,7 +68,7 @@
* \param scan The scan that we want to add to the point cloud
* \return Negative value on error
*/
- int addScan(const std_msgs::LaserScan& scan ) ;
+ int addScan(const laser_scan::LaserScan& scan ) ;
/**
* \brief Retrieves the current assembled point cloud
Modified: pkg/trunk/deprecated/point_cloud_utils/include/point_cloud_utils/timed_scan_assembler.h
===================================================================
--- pkg/trunk/deprecated/point_cloud_utils/include/point_cloud_utils/timed_scan_assembler.h 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/deprecated/point_cloud_utils/include/point_cloud_utils/timed_scan_assembler.h 2009-02-10 05:16:00 UTC (rev 10900)
@@ -35,7 +35,7 @@
#include "boost/thread/mutex.hpp"
#include "std_msgs/PointCloud.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "point_cloud_utils/scan_assembler.h"
@@ -62,7 +62,7 @@
private:
void scansCallback() ;
- std_msgs::LaserScan scan_ ;
+ laser_scan::LaserScan scan_ ;
bool got_first_scan_ ;
bool done_getting_scans_ ;
Modified: pkg/trunk/deprecated/point_cloud_utils/manifest.xml
===================================================================
--- pkg/trunk/deprecated/point_cloud_utils/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/deprecated/point_cloud_utils/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -9,6 +9,7 @@
<review status="experimental" notes=""/>
<url>http://pr.willowgarage.com</url>
<depend package="std_msgs"/>
+<depend package="laser_scan"/>
<depend package="roscpp"/>
<depend package="tf"/>
<depend package="bullet"/>
Modified: pkg/trunk/deprecated/point_cloud_utils/src/scan_assembler.cpp
===================================================================
--- pkg/trunk/deprecated/point_cloud_utils/src/scan_assembler.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/deprecated/point_cloud_utils/src/scan_assembler.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -54,7 +54,7 @@
point_count_ = 0 ;
}
-int ScanAssembler::addScan(const std_msgs::LaserScan& scan)
+int ScanAssembler::addScan(const laser_scan::LaserScan& scan)
{
PointCloud target_frame_cloud ; // Stores the current scan in the target frame
Modified: pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp
===================================================================
--- pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -70,7 +70,7 @@
- None
Publishes to (name / type):
-- @b "scan"/<a href="../../std_msgs/html/classstd__msgs_1_1LaserScan.html">std_msgs/LaserScan</a> : scan data from the laser.
+- @b "scan"/<a href="../../laser_scan/html/classstd__msgs_1_1LaserScan.html">laser_scan/LaserScan</a> : scan data from the laser.
- @b "/diagnostics"/<a href="../../robot_msgs/html/classrobot__msgs_1_1DiagnosticMessage.html">robot_msgs/DiagnosticMessage</a> : diagnostic status information.
<hr>
@@ -105,7 +105,7 @@
#include "ros/time.h"
#include "ros/common.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "self_test/self_test.h"
#include "diagnostic_updater/diagnostic_updater.h"
@@ -129,7 +129,7 @@
public:
hokuyo::Laser laser_;
- std_msgs::LaserScan scan_msg_;
+ laser_scan::LaserScan scan_msg_;
double min_ang_;
double max_ang_;
@@ -146,7 +146,7 @@
HokuyoNode() : ros::Node("hokuyo"), running_(false), count_(0), self_test_(this), diagnostic_(this)
{
- advertise<std_msgs::LaserScan>("scan", 100);
+ advertise<laser_scan::LaserScan>("scan", 100);
if (hasParam("~min_ang_degrees") && hasParam("~min_ang"))
{
Modified: pkg/trunk/drivers/laser/hokuyo_node/manifest.xml
===================================================================
--- pkg/trunk/drivers/laser/hokuyo_node/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/laser/hokuyo_node/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -4,7 +4,7 @@
<license>LGPL</license>
<review status="API cleared" notes="Tully to code review"/>
<depend package="roscpp" />
- <depend package="std_msgs" />
+ <depend package="laser_scan" />
<depend package="self_test" />
<depend package="diagnostic_updater" />
<url>http://pr.willowgarage.com/wiki/Hokuyo_TOP-URG</url>
Modified: pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml
===================================================================
--- pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -6,6 +6,7 @@
<license>BSD</license>
<review status="experimental" notes=""/>
<url>http://pr.willowgarage.com</url>
+<depend package="laser_scan"/>
<depend package="std_msgs"/>
<depend package="roscpp"/>
<depend package="tf"/>
Modified: pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg
===================================================================
--- pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg 2009-02-10 05:16:00 UTC (rev 10900)
@@ -1,2 +1,2 @@
-std_msgs/LaserScan scan # The original laser scan
+laser_scan/LaserScan scan # The original laser scan
std_msgs/PoseStamped[] poses # The pose during each ray of the laserscan
\ No newline at end of file
Modified: pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp
===================================================================
--- pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -28,14 +28,14 @@
*/
#include "ros/node.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "tf/transform_listener.h"
#include "tf/message_notifier.h"
#include "laser_scan_annotator/LaserScanAnnotated.h"
#include "boost/thread.hpp"
using namespace std ;
-using namespace std_msgs ;
+using namespace laser_scan ;
namespace laser_scan_annotator
{
@@ -104,7 +104,7 @@
}
protected:
- std_msgs::LaserScan scan_in_ ;
+ laser_scan::LaserScan scan_in_ ;
string fixed_frame_ ;
Modified: pkg/trunk/drivers/laser/laser_view/laser_view.cpp
===================================================================
--- pkg/trunk/drivers/laser/laser_view/laser_view.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/laser/laser_view/laser_view.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -36,7 +36,7 @@
#include <math.h>
#include <GL/gl.h>
#include "ros/node.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "sdlgl/sdlgl.h"
using namespace ros;
@@ -44,7 +44,7 @@
class LaserView : public Node, public SDLGL
{
public:
- std_msgs::LaserScan laser;
+ laser_scan::LaserScan laser;
float view_scale, view_x, view_y;
LaserView() : Node("laser_view"),
Modified: pkg/trunk/drivers/laser/laser_view/manifest.xml
===================================================================
--- pkg/trunk/drivers/laser/laser_view/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/laser/laser_view/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -3,6 +3,6 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="roscpp"/>
- <depend package="std_msgs"/>
+ <depend package="laser_scan"/>
<depend package="sdlgl"/>
</package>
Modified: pkg/trunk/drivers/laser/sicktoolbox_wrapper/manifest.xml
===================================================================
--- pkg/trunk/drivers/laser/sicktoolbox_wrapper/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/laser/sicktoolbox_wrapper/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -8,5 +8,5 @@
<review status="unreviewed" notes=""/>
<depend package="sicktoolbox"/>
<depend package="roscpp"/>
- <depend package="std_msgs"/>
+ <depend package="laser_scan"/>
</package>
Modified: pkg/trunk/drivers/laser/sicktoolbox_wrapper/ros/sicklms/sicklms.cpp
===================================================================
--- pkg/trunk/drivers/laser/sicktoolbox_wrapper/ros/sicklms/sicklms.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/laser/sicktoolbox_wrapper/ros/sicklms/sicklms.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -32,7 +32,7 @@
#include <csignal>
#include <sicklms-1.0/SickLMS.hh>
#include "ros/node.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
using namespace SickToolbox;
using namespace std;
@@ -45,7 +45,7 @@
class SickNode : public ros::Node
{
public:
- std_msgs::LaserScan scan_msg;
+ laser_scan::LaserScan scan_msg;
int scan_count;
string port;
int baud;
@@ -54,7 +54,7 @@
SickNode() : ros::Node("sicklms"), scan_count(0), last_print_time(0)
{
scan_msg.header.frame_id = "base_laser";
- advertise<std_msgs::LaserScan>("scan", 1);
+ advertise<laser_scan::LaserScan>("scan", 1);
param("sicklms/port", port, string("/dev/ttyUSB0"));
param("sicklms/baud", baud, 500000);
param("sicklms/inverted", inverted, true);
Modified: pkg/trunk/drivers/robot/katana/nodes/katana_client/katana_client.cpp
===================================================================
--- pkg/trunk/drivers/robot/katana/nodes/katana_client/katana_client.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/robot/katana/nodes/katana_client/katana_client.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -2,7 +2,7 @@
#include <stdexcept>
#include <string>
#include "ros/node.h"
-#include "std_srvs/StringString.h"
+#include "deprecated_srvs/StringString.h"
using std::vector;
using std::endl;
Added: pkg/trunk/drivers/robot/katana/srv/StringString.srv
===================================================================
--- pkg/trunk/drivers/robot/katana/srv/StringString.srv (rev 0)
+++ pkg/trunk/drivers/robot/katana/srv/StringString.srv 2009-02-10 05:16:00 UTC (rev 10900)
@@ -0,0 +1,3 @@
+string str
+---
+string str
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/laser_scan_assembler_srv.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/laser_scan_assembler_srv.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/laser_scan_assembler_srv.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -35,11 +35,12 @@
#include "laser_scan/laser_scan.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "point_cloud_assembler/base_assembler_srv.h"
using namespace std_msgs;
+using namespace laser_scan;
using namespace std ;
namespace point_cloud_assembler
@@ -55,10 +56,10 @@
* \section services ROS Services
* - "~build_cloud" - Inhertited from point_cloud_assembler::BaseAssemblerSrv
*/
-class LaserScanAssemblerSrv : public BaseAssemblerSrv<std_msgs::LaserScan>
+class LaserScanAssemblerSrv : public BaseAssemblerSrv<laser_scan::LaserScan>
{
public:
- LaserScanAssemblerSrv() : BaseAssemblerSrv<std_msgs::LaserScan>("laser_scan_assembler")
+ LaserScanAssemblerSrv() : BaseAssemblerSrv<laser_scan::LaserScan>("laser_scan_assembler")
{
// ***** Set Laser Projection Method *****
param("~ignore_laser_skew", ignore_laser_skew_, true) ;
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler_srv.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler_srv.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler_srv.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -35,7 +35,7 @@
#include "laser_scan/laser_scan.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "point_cloud_assembler/base_assembler_srv.h"
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/test/test_assembler.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/test/test_assembler.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/test/test_assembler.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -38,11 +38,12 @@
#include <gtest/gtest.h>
#include "ros/node.h"
#include "std_msgs/PointCloud.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "boost/thread.hpp"
using namespace ros;
using namespace std_msgs;
+using namespace laser_scan;
static const unsigned int last_seq = 4100 ;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_block_laser.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_block_laser.h 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_block_laser.h 2009-02-10 05:16:00 UTC (rev 10900)
@@ -32,7 +32,6 @@
#include <ros/node.h>
#include "boost/thread/mutex.hpp"
-#include <std_msgs/LaserScan.h>
#include <std_msgs/PointCloud.h>
namespace gazebo
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h 2009-02-10 05:16:00 UTC (rev 10900)
@@ -32,7 +32,7 @@
#include <ros/node.h>
#include <boost/thread/mutex.hpp>
-#include <std_msgs/LaserScan.h>
+#include <laser_scan/LaserScan.h>
namespace gazebo
{
@@ -45,7 +45,7 @@
\brief ROS Laser Scanner Controller Plugin
This controller gathers range data from a simulated ray sensor, publishes range data through
- std_msgs::LaserScan ROS topic.
+ laser_scan::LaserScan ROS topic.
Example Usage:
\verbatim
@@ -81,7 +81,7 @@
/**
\brief ROS laser scan controller.
\li Starts a ROS node if none exists.
- \li Simulates a laser range sensor and publish std_msgs::LaserScan.msg over ROS.
+ \li Simulates a laser range sensor and publish laser_scan::LaserScan.msg over ROS.
\li Example Usage:
\verbatim
<model:physical name="ray_model">
@@ -144,7 +144,7 @@
private: ros::Node *rosnode;
/// \brief ros message
- private: std_msgs::LaserScan laserMsg;
+ private: laser_scan::LaserScan laserMsg;
/// \brief topic name
private: std::string topicName;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -15,6 +15,7 @@
<depend package="roscpp"/>
<depend package="rospy"/>
<depend package="std_msgs" />
+ <depend package="laser_scan" />
<depend package="pr2_msgs" />
<depend package="robot_msgs" />
<depend package="angles" />
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -82,7 +82,7 @@
{
this->topicName = node->GetString("topicName","default_ros_laser",0); //read from xml file
std::cout << "================= " << this->topicName << std::endl;
- rosnode->advertise<std_msgs::LaserScan>(this->topicName,10);
+ rosnode->advertise<laser_scan::LaserScan>(this->topicName,10);
this->frameName = node->GetString("frameName","default_ros_laser",0); //read from xml file
this->gaussianNoise = node->GetDouble("gaussianNoise",0.0,0); //read from xml file
}
Modified: pkg/trunk/hardware_test/qualification/manifest.xml
===================================================================
--- pkg/trunk/hardware_test/qualification/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/hardware_test/qualification/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -7,7 +7,7 @@
<depend package="rospy" />
<depend package="std_msgs" />
<depend package="robot_msgs" />
- <depend package="std_srvs" />
+ <depend package="deprecated_srvs" />
<depend package="robot_srvs" />
<depend package="hokuyo_node" />
<depend package="imu_node" />
Modified: pkg/trunk/hardware_test/qualification/scripts/configure_mcbs.py
===================================================================
--- pkg/trunk/hardware_test/qualification/scripts/configure_mcbs.py 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/hardware_test/qualification/scripts/configure_mcbs.py 2009-02-10 05:16:00 UTC (rev 10900)
@@ -39,7 +39,7 @@
import subprocess
from optparse import OptionParser
-from std_srvs.srv import *
+from deprecated_srvs.srv import *
rospy.init_node("mcb_configurer")
# block until the add_two_ints service is available
Modified: pkg/trunk/hardware_test/qualification/scripts/confirm_conf.py
===================================================================
--- pkg/trunk/hardware_test/qualification/scripts/confirm_conf.py 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/hardware_test/qualification/scripts/confirm_conf.py 2009-02-10 05:16:00 UTC (rev 10900)
@@ -42,7 +42,7 @@
import roslib
roslib.load_manifest(PKG)
import wx
-from std_srvs.srv import *
+from deprecated_srvs.srv import *
import rospy
import time
Modified: pkg/trunk/hardware_test/qualification/scripts/program_mcb.py
===================================================================
--- pkg/trunk/hardware_test/qualification/scripts/program_mcb.py 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/hardware_test/qualification/scripts/program_mcb.py 2009-02-10 05:16:00 UTC (rev 10900)
@@ -39,7 +39,7 @@
import subprocess
from optparse import OptionParser
-from std_srvs.srv import *
+from deprecated_srvs.srv import *
rospy.init_node("mcb_programmer")
# block until the add_two_ints service is available
Modified: pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh 2009-02-10 05:16:00 UTC (rev 10900)
@@ -55,7 +55,7 @@
#include <robot_msgs/Planner2DState.h>
#include <robot_msgs/Planner2DGoal.h>
#include <std_msgs/PoseDot.h>
-#include <std_msgs/LaserScan.h>
+#include <laser_scan/LaserScan.h>
#include <std_msgs/RobotBase2DOdom.h>
#include <std_msgs/PointCloud.h>
@@ -174,7 +174,7 @@
/**
* @brief Callbacks for perceiving obstalces
*/
- void baseScanCallback(const tf::MessageNotifier<std_msgs::LaserScan>::MessagePtr& message);
+ void baseScanCallback(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& message);
void tiltScanCallback();
void tiltCloudCallback(const tf::MessageNotifier<std_msgs::PointCloud>::MessagePtr& message);
void groundPlaneCloudCallback();
@@ -225,8 +225,8 @@
bool checkWatchDog() const;
// Callback messages
- std_msgs::LaserScan baseScanMsg_; /**< Filled by subscriber with new base laser scans */
- std_msgs::LaserScan tiltScanMsg_; /**< Filled by subscriber with new tilte laser scans */
+ laser_scan::LaserScan baseScanMsg_; /**< Filled by subscriber with new base laser scans */
+ laser_scan::LaserScan tiltScanMsg_; /**< Filled by subscriber with new tilte laser scans */
std_msgs::PointCloud tiltCloudMsg_; /**< Filled by subscriber with new tilte laser scans */
std_msgs::PointCloud groundPlaneCloudMsg_; /**< Filled by subscriber with point clouds */
std_msgs::PointCloud stereoCloudMsg_; /**< Filled by subscriber with point clouds */
@@ -283,7 +283,7 @@
//Robot filter
robot_filter::RobotFilter* filter_;
- tf::MessageNotifier<std_msgs::LaserScan>* baseScanNotifier_;
+ tf::MessageNotifier<laser_scan::LaserScan>* baseScanNotifier_;
tf::MessageNotifier<std_msgs::PointCloud>* tiltLaserNotifier_;
//flag for reseting the costmap.
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -291,7 +291,7 @@
// The cost map is populated with either laser scans in the case that we are unable to use a
// world model source, or point clouds if we are. We shall pick one, and will be dominated by
// point clouds
- baseScanNotifier_ = new tf::MessageNotifier<std_msgs::LaserScan>(&tf_, this,
+ baseScanNotifier_ = new tf::MessageNotifier<laser_scan::LaserScan>(&tf_, this,
boost::bind(&MoveBase::baseScanCallback, this, _1),
"base_scan", global_frame_, 50);
tiltLaserNotifier_ = new tf::MessageNotifier<std_msgs::PointCloud>(&tf_, this,
@@ -419,7 +419,7 @@
stateMsg.pos.th = (float)yaw;
}
- void MoveBase::baseScanCallback(const tf::MessageNotifier<std_msgs::LaserScan>::MessagePtr& message)
+ void MoveBase::baseScanCallback(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& message)
{
// Project laser into point cloud
std_msgs::PointCloud local_cloud;
Modified: pkg/trunk/nav/amcl_player/amcl_player.cc
===================================================================
--- pkg/trunk/nav/amcl_player/amcl_player.cc 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/nav/amcl_player/amcl_player.cc 2009-02-10 05:16:00 UTC (rev 10900)
@@ -97,7 +97,7 @@
#include "ros/node.h"
// Messages that I need
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "std_msgs/RobotBase2DOdom.h"
#include "robot_msgs/ParticleCloud.h"
#include "std_msgs/Pose2DFloat32.h"
@@ -147,7 +147,7 @@
std_msgs::RobotBase2DOdom localizedOdomMsg;
robot_msgs::ParticleCloud particleCloudMsg;
std_msgs::RobotBase2DOdom odomMsg;
- std_msgs::LaserScan laserMsg;
+ laser_scan::LaserScan laserMsg;
std_msgs::Pose2DFloat32 initialPoseMsg;
// Message callbacks
@@ -190,7 +190,7 @@
const ros::Time& t, const std::string& f);
// buffer of not-yet-transformed scans
- std::deque<std_msgs::LaserScan> laser_scans;
+ std::deque<laser_scan::LaserScan> laser_scans;
//time for tolerance on the published transform,
//basically defines how long a map->odom transform is good for
@@ -787,13 +787,13 @@
}
// Put it on the queue
- std_msgs::LaserScan newscan(laserMsg);
+ laser_scan::LaserScan newscan(laserMsg);
laser_scans.push_back(newscan);
// Process the queued scans
while(!laser_scans.empty())
{
- std_msgs::LaserScan scan = laser_scans.front();
+ laser_scan::LaserScan scan = laser_scans.front();
//make sure that we don't fall to far in the past
// To work around the lack of ros::Time support in roscpp, we'll take the time of the
Modified: pkg/trunk/nav/slam_gmapping/manifest.xml
===================================================================
--- pkg/trunk/nav/slam_gmapping/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/nav/slam_gmapping/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -6,6 +6,7 @@
<depend package="roscpp"/>
<depend package="rosconsole"/>
<depend package="std_msgs"/>
+ <depend package="laser_scan"/>
<depend package="robot_srvs"/>
<depend package="gmapping"/>
<depend package="tf"/>
Modified: pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
===================================================================
--- pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -140,7 +140,7 @@
}
bool
-SlamGMapping::initMapper(const std_msgs::LaserScan& scan)
+SlamGMapping::initMapper(const laser_scan::LaserScan& scan)
{
// Get the laser's pose, relative to base.
tf::Stamped<tf::Pose> ident;
@@ -219,7 +219,7 @@
}
bool
-SlamGMapping::addScan(const std_msgs::LaserScan& scan)
+SlamGMapping::addScan(const laser_scan::LaserScan& scan)
{
GMapping::OrientedPoint gmap_pose;
if(!getOdomPose(gmap_pose, scan.header.stamp))
Modified: pkg/trunk/nav/slam_gmapping/src/slam_gmapping.h
===================================================================
--- pkg/trunk/nav/slam_gmapping/src/slam_gmapping.h 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/nav/slam_gmapping/src/slam_gmapping.h 2009-02-10 05:16:00 UTC (rev 10900)
@@ -30,7 +30,7 @@
/* Author: Brian Gerkey */
#include "ros/node.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "robot_srvs/StaticMap.h"
#include "tf/transform_listener.h"
@@ -58,7 +58,7 @@
GMapping::OdometrySensor* gsp_odom_;
bool got_first_scan_;
- std_msgs::LaserScan scan_;
+ laser_scan::LaserScan scan_;
bool got_map_;
robot_srvs::StaticMap::Response map_;
@@ -67,8 +67,8 @@
void updateMap();
bool getOdomPose(GMapping::OrientedPoint& gmap_pose, const ros::Time& t);
- bool initMapper(const std_msgs::LaserScan& scan);
- bool addScan(const std_msgs::LaserScan& scan);
+ bool initMapper(const laser_scan::LaserScan& scan);
+ bool addScan(const laser_scan::LaserScan& scan);
// Parameters used by GMapping
double maxUrange_;
Modified: pkg/trunk/nav/slam_gmapping/src/tftest.cpp
===================================================================
--- pkg/trunk/nav/slam_gmapping/src/tftest.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/nav/slam_gmapping/src/tftest.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -1,4 +1,4 @@
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "ros/node.h"
#include "tf/transform_listener.h"
@@ -52,7 +52,7 @@
private:
ros::Node* node_;
tf::TransformListener* tf_;
- std_msgs::LaserScan scan_;
+ laser_scan::LaserScan scan_;
};
int
Modified: pkg/trunk/simulators/rosstage/manifest.xml
===================================================================
--- pkg/trunk/simulators/rosstage/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/simulators/rosstage/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -6,5 +6,6 @@
<depend package="roscpp" />
<depend package="stage" />
<depend package="std_msgs" />
+ <depend package="laser_scan" />
<depend package="tf" />
</package>
Modified: pkg/trunk/simulators/rosstage/rosstage.cc
===================================================================
--- pkg/trunk/simulators/rosstage/rosstage.cc 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/simulators/rosstage/rosstage.cc 2009-02-10 05:16:00 UTC (rev 10900)
@@ -84,7 +84,7 @@
// roscpp
#include <ros/node.h>
#include "boost/thread/mutex.hpp"
-#include <std_msgs/LaserScan.h>
+#include <laser_scan/LaserScan.h>
#include <std_msgs/RobotBase2DOdom.h>
#include <std_msgs/PoseWithRatesStamped.h>
#include <std_msgs/PoseDot.h>
@@ -100,7 +100,7 @@
private:
// Messages that we'll send or receive
std_msgs::PoseDot velMsg;
- std_msgs::LaserScan laserMsg;
+ laser_scan::LaserScan laserMsg;
std_msgs::RobotBase2DOdom odomMsg;
std_msgs::PoseWithRatesStamped groundTruthMsg;
roslib::Time timeMsg;
@@ -224,7 +224,7 @@
return(-1);
}
- advertise<std_msgs::LaserScan>("base_scan",10);
+ advertise<laser_scan::LaserScan>("base_scan",10);
advertise<std_msgs::RobotBase2DOdom>("odom",10);
advertise<std_msgs::PoseWithRatesStamped>("base_pose_ground_truth",10);
advertise<roslib::Time>("time",10);
Modified: pkg/trunk/util/laser_scan/CMakeLists.txt
===================================================================
--- pkg/trunk/util/laser_scan/CMakeLists.txt 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/laser_scan/CMakeLists.txt 2009-02-10 05:16:00 UTC (rev 10900)
@@ -2,6 +2,7 @@
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
set(ROS_BUILD_TYPE RelWithDebInfo)
rospack(laser_scan)
+genmsg()
rospack_add_boost_directories()
Modified: pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h
===================================================================
--- pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h 2009-02-10 05:16:00 UTC (rev 10900)
@@ -38,7 +38,7 @@
#include "tf/tf.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "std_msgs/PointCloud.h"
#include "std_msgs/PointCloud.h"
@@ -76,11 +76,11 @@
* \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, int mask = DEFAULT_MASK);
+ void projectLaser (const laser_scan::LaserScan& scan_in, std_msgs::PointCloud & cloud_out, double range_cutoff=-1.0, bool preservative = false, int mask = DEFAULT_MASK);
- /** \brief Transform a std_msgs::LaserScan into a PointCloud in target frame */
- void transformLaserScanToPointCloud (const std::string& target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::LaserScan & scanIn, tf::Transformer & tf, int mask = DEFAULT_MASK);
+ /** \brief Transform a laser_scan::LaserScan into a PointCloud in target frame */
+ void transformLaserScanToPointCloud (const std::string& target_frame, std_msgs::PointCloud & cloudOut, const laser_scan::LaserScan & scanIn, tf::Transformer & tf, int mask = DEFAULT_MASK);
private:
Modified: pkg/trunk/util/laser_scan/include/laser_scan/median_filter.h
===================================================================
--- pkg/trunk/util/laser_scan/include/laser_scan/median_filter.h 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/laser_scan/include/laser_scan/median_filter.h 2009-02-10 05:16:00 UTC (rev 10900)
@@ -35,7 +35,7 @@
#include <sstream>
#include "boost/thread/mutex.hpp"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "filters/median.h"
#include "boost/thread/mutex.hpp"
@@ -55,7 +55,7 @@
* \param scan_in The new scan to filter
* \param scan_out The filtered scan
*/
- bool update(const std_msgs::LaserScan& scan_in, std_msgs::LaserScan& scan_out);
+ bool update(const laser_scan::LaserScan& scan_in, laser_scan::LaserScan& scan_out);
private:
@@ -63,7 +63,7 @@
unsigned int num_ranges_; /// How many data point are in each row
boost::mutex data_lock; /// Protection from multi threaded programs
- std_msgs::LaserScan temp_scan_; /** \todo cache only shallow info not full scan */
+ laser_scan::LaserScan temp_scan_; /** \todo cache only shallow info not full scan */
filters::MedianFilter<std::vector<float> > * range_filter_;
filters::MedianFilter<std::vector<float> > * intensity_filter_;
Modified: pkg/trunk/util/laser_scan/manifest.xml
===================================================================
--- pkg/trunk/util/laser_scan/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/laser_scan/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -13,6 +13,6 @@
<depend package="tf"/>
<depend package="filters"/>
<export>
-<cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -llaser_scan"/>
+<cpp cflags="-I${prefix}/include -I${prefix}/msg/cpp" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -llaser_scan"/>
</export>
</package>
Added: pkg/trunk/util/laser_scan/msg/LaserScan.msg
===================================================================
--- pkg/trunk/util/laser_scan/msg/LaserScan.msg (rev 0)
+++ pkg/trunk/util/laser_scan/msg/LaserScan.msg 2009-02-10 05:16:00 UTC (rev 10900)
@@ -0,0 +1,15 @@
+#
+# Laser scans angles are measured counter clockwise, with 0 facing forward
+# (along the x-axis) of the device frame
+#
+
+Header header
+float32 angle_min # start angle of the scan [rad]
+float32 angle_max # end angle of the scan [rad]
+float32 angle_increment # angular distance between measurements [rad]
+float32 time_increment # time between measurements [seconds]
+float32 scan_time # time between scans [seconds]
+float32 range_min # minimum range value [m]
+float32 range_max # maximum range value [m]
+float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)
+float32[] intensities # intensity data [device-specific units]
Modified: pkg/trunk/util/laser_scan/src/laser_scan.cc
===================================================================
--- pkg/trunk/util/laser_scan/src/laser_scan.cc 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/laser_scan/src/laser_scan.cc 2009-02-10 05:16:00 UTC (rev 10900)
@@ -34,7 +34,7 @@
{
void
- LaserProjection::projectLaser (const std_msgs::LaserScan& scan_in, std_msgs::PointCloud & cloud_out, double range_cutoff,
+ LaserProjection::projectLaser (const laser_scan::LaserScan& scan_in, std_msgs::PointCloud & cloud_out, double range_cutoff,
bool preservative, int mask)
{
boost::numeric::ublas::matrix<double> ranges(2, scan_in.get_ranges_size());
@@ -208,7 +208,7 @@
};
void
- LaserProjection::transformLaserScanToPointCloud (const std::string &target_frame, std_msgs::PointCloud &cloud_out, const std_msgs::LaserScan &scan_in,
+ LaserProjection::transformLaserScanToPointCloud (const std::string &target_frame, std_msgs::PointCloud &cloud_out, const laser_scan::LaserScan &scan_in,
tf::Transformer& tf, int mask)
{
cloud_out.header = scan_in.header;
Modified: pkg/trunk/util/laser_scan/src/median_filter.cpp
===================================================================
--- pkg/trunk/util/laser_scan/src/median_filter.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/laser_scan/src/median_filter.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -53,7 +53,7 @@
delete intensity_filter_;
};
-bool LaserMedianFilter::update(const std_msgs::LaserScan& scan_in, std_msgs::LaserScan& scan_out)
+bool LaserMedianFilter::update(const laser_scan::LaserScan& scan_in, laser_scan::LaserScan& scan_out)
{
boost::mutex::scoped_lock lock(data_lock);
scan_out = scan_in; ///Quickly pass through all data \todo don't copy data too
Modified: pkg/trunk/util/laser_scan/src/median_filter_node.cpp
===================================================================
--- pkg/trunk/util/laser_scan/src/median_filter_node.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/laser_scan/src/median_filter_node.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -28,18 +28,18 @@
*/
#include "ros/node.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "laser_scan/median_filter.h"
class MedianFilterNode : public ros::Node
{
public:
- std_msgs::LaserScan msg;
+ laser_scan::LaserScan msg;
MedianFilterNode() : ros::Node("median_filter_node"), filter(5)
{
- advertise<std_msgs::LaserScan>("~output", 1000);
+ advertise<laser_scan::LaserScan>("~output", 1000);
subscribe("scan_in", msg, &MedianFilterNode::callback, 3);
}
void callback()
Modified: pkg/trunk/util/laser_scan/src/scan_intensity_filter.cpp
===================================================================
--- pkg/trunk/util/laser_scan/src/scan_intensity_filter.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/laser_scan/src/scan_intensity_filter.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -47,9 +47,9 @@
#include "ros/node.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
-using namespace std_msgs;
+using namespace laser_scan;
class ScanIntensityFilter : public ros::Node
{
Modified: pkg/trunk/util/laser_scan/src/scan_shadows_filter.cpp
===================================================================
--- pkg/trunk/util/laser_scan/src/scan_shadows_filter.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/laser_scan/src/scan_shadows_filter.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -36,7 +36,7 @@
#include <ros/node.h>
#include <std_msgs/PointCloud.h>
-#include <std_msgs/LaserScan.h>
+#include <laser_scan/LaserScan.h>
#include <float.h>
@@ -55,7 +55,7 @@
public:
// ROS related
- LaserScan tilt_scan_msg_; // Filled by subscriber with new tilte laser scans
+ laser_scan::LaserScan tilt_scan_msg_; // Filled by subscriber with new tilte laser scans
laser_scan::LaserProjection projector_; // Used to project laser scans
double tilt_laser_max_range_; // Used in laser scan projection
Modified: pkg/trunk/util/logsetta/carmen/carmen_logger/carmen_logger.cpp
===================================================================
--- pkg/trunk/util/logsetta/carmen/carmen_logger/carmen_logger.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/logsetta/carmen/carmen_logger/carmen_logger.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -29,13 +29,13 @@
//////////////////////////////////////////////////////////////////////////////
#include "ros/node.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "std_msgs/RobotBase2DOdom.h"
class CarmenLogger : public ros::Node
{
public:
- std_msgs::LaserScan laserMsg;
+ laser_scan::LaserScan laserMsg;
std_msgs::RobotBase2DOdom odomMsg;
double robot_x, robot_y, robot_th, robot_tv, robot_rv;
double start_time;
Modified: pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
===================================================================
--- pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -30,7 +30,7 @@
#include <cmath>
#include "ros/node.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "std_msgs/RobotBase2DOdom.h"
#include <vector>
#include <string>
@@ -84,7 +84,7 @@
dumb_tv, dumb_rv, rel_time, rel_time);
}
-void scan_callback(string name, std_msgs::LaserScan* scan, ros::Time t, ros::Time t_no_use, void* n)
+void scan_callback(string name, laser_scan::LaserScan* scan, ros::Time t, ros::Time t_no_use, void* n)
{
double rel_time = t.toSec();
@@ -128,7 +128,7 @@
player.open(files, ros::Time());
player.addHandler<std_msgs::RobotBase2DOdom>(string("/odom"), &odom_callback, NULL);
- player.addHandler<std_msgs::LaserScan>(string("/scan"), &scan_callback, NULL);
+ player.addHandler<laser_scan::LaserScan>(string("/scan"), &scan_callback, NULL);
clog = fopen("carmen.txt", "w");
Modified: pkg/trunk/util/logsetta/laser/laser_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/laser/laser_extract.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/logsetta/laser/laser_extract.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -28,11 +28,11 @@
// POSSIBILITY OF SUCH DAMAGE.
//////////////////////////////////////////////////////////////////////////////
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include <string>
#include "rosrecord/Player.h"
-void scan_callback(std::string name, std_msgs::LaserScan *scan,
+void scan_callback(std::string name, laser_scan::LaserScan *scan,
ros::Time t, ros::Time t_no_use, void* f)
{
FILE* file = (FILE*)f;
@@ -65,7 +65,7 @@
ros::record::Player player;
player.open(std::string(argv[1]), ros::Time());
FILE* file = fopen((std::string(argv[2])+".txt").c_str() , "w");
- player.addHandler<std_msgs::LaserScan>(std::string(argv[2]), &scan_callback, file);
+ player.addHandler<laser_scan::LaserScan>(std::string(argv[2]), &scan_callback, file);
while(player.nextMsg()) { }
fclose(file);
return 0;
Modified: pkg/trunk/util/logsetta/manifest.xml
===================================================================
--- pkg/trunk/util/logsetta/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/logsetta/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -13,6 +13,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp"/>
<depend package="std_msgs"/>
+ <depend package="laser_scan"/>
<depend package="imu_node"/>
<depend package="rosrecord"/>
<depend package="robot_msgs"/>
Modified: pkg/trunk/util/mux/manifest.xml
===================================================================
--- pkg/trunk/util/mux/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/mux/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -12,5 +12,5 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp"/>
<depend package="std_msgs"/>
- <depend package="std_srvs"/>
+ <depend package="deprecated_srvs"/>
</package>
Modified: pkg/trunk/util/mux/mux.cpp
===================================================================
--- pkg/trunk/util/mux/mux.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/mux/mux.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -29,7 +29,7 @@
#include "ros/node.h"
#include "std_msgs/String.h"
-#include "std_srvs/StringString.h"
+#include "deprecated_srvs/StringString.h"
using namespace std;
using namespace ros;
@@ -120,8 +120,8 @@
break;
}
}
- bool selSrvCB(std_srvs::StringString::Request &req,
- std_srvs::StringString::Response &res)
+ bool selSrvCB(deprecated_srvs::StringString::Request &req,
+ deprecated_srvs::StringString::Response &res)
{
if (selectedTopic)
res.str = selectedTopic->topicName;
Modified: pkg/trunk/util/mux/switch.cpp
===================================================================
--- pkg/trunk/util/mux/switch.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/util/mux/switch.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -28,7 +28,7 @@
/////////////////////////////////////////////////////////////////////////////
#include "ros/node.h"
-#include "std_srvs/StringString.h"
+#include "deprecated_srvs/StringString.h"
using namespace std;
using namespace ros;
@@ -38,8 +38,8 @@
MuxSwitcher() : Node("MuxSwitcher") { }
void switchMux(string s)
{
- std_srvs::StringString::Request req;
- std_srvs::StringString::Response res;
+ deprecated_srvs::StringString::Request req;
+ deprecated_srvs::StringString::Response res;
req.str = s;
bool ok = service::call("mux", req, res);
if (ok)
Modified: pkg/trunk/vision/laser_processor/laser_processor.cpp
===================================================================
--- pkg/trunk/vision/laser_processor/laser_processor.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/vision/laser_processor/laser_processor.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -40,7 +40,7 @@
using namespace std;
using namespace laser_processor;
-Sample* Sample::Extract(int ind, std_msgs::LaserScan& scan)
+Sample* Sample::Extract(int ind, laser_scan::LaserScan& scan)
{
Sample* s = new Sample;
@@ -112,7 +112,7 @@
}
-void ScanMask::addScan(std_msgs::LaserScan& scan)
+void ScanMask::addScan(laser_scan::LaserScan& scan)
{
if (!filled)
{
@@ -169,7 +169,7 @@
-ScanProcessor::ScanProcessor(std_msgs::LaserScan& scan, ScanMask& mask_, float mask_threshold)
+ScanProcessor::ScanProcessor(laser_scan::LaserScan& scan, ScanMask& mask_, float mask_threshold)
{
scan_ = scan;
Modified: pkg/trunk/vision/laser_processor/laser_processor.h
===================================================================
--- pkg/trunk/vision/laser_processor/laser_processor.h 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/vision/laser_processor/laser_processor.h 2009-02-10 05:16:00 UTC (rev 10900)
@@ -45,7 +45,7 @@
#include <unistd.h>
#include <math.h>
#include "ros/node.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include "std_msgs/PointCloud.h"
#include "std_msgs/Point.h"
@@ -70,7 +70,7 @@
float x;
float y;
- static Sample* Extract(int ind, std_msgs::LaserScan& scan);
+ static Sample* Extract(int ind, laser_scan::LaserScan& scan);
private:
Sample() {};
@@ -116,7 +116,7 @@
inline void clear() { mask_.clear(); filled = false; }
- void addScan(std_msgs::LaserScan& scan);
+ void addScan(laser_scan::LaserScan& scan);
bool hasSample(Sample* s, float thresh);
};
@@ -126,13 +126,13 @@
class ScanProcessor
{
std::list<SampleSet*> clusters_;
- std_msgs::LaserScan scan_;
+ laser_scan::LaserScan scan_;
public:
std::list<SampleSet*>& getClusters() { return clusters_; }
- ScanProcessor(std_msgs::LaserScan& scan, ScanMask& mask_, float mask_threshold = 0.03);
+ ScanProcessor(laser_scan::LaserScan& scan, ScanMask& mask_, float mask_threshold = 0.03);
~ScanProcessor();
Modified: pkg/trunk/vision/laser_processor/manifest.xml
===================================================================
--- pkg/trunk/vision/laser_processor/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/vision/laser_processor/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -4,6 +4,7 @@
<license>BSD</license>
<depend package="roscpp" />
<depend package="std_msgs" />
+ <depend package="laser_scan" />
<depend package="tf" />
<export>
<cpp cflags="-I${prefix}" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -llaser_processor"/>
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -52,7 +52,7 @@
, topic_property_( NULL )
{
projector_ = new laser_scan::LaserProjection();
- notifier_ = new tf::MessageNotifier<std_msgs::LaserScan>(tf_, ros_node_, boost::bind(&LaserScanDisplay::incomingScanCallback, this, _1), "", "", 10);
+ notifier_ = new tf::MessageNotifier<laser_scan::LaserScan>(tf_, ros_node_, boost::bind(&LaserScanDisplay::incomingScanCallback, this, _1), "", "", 10);
}
LaserScanDisplay::~LaserScanDisplay()
@@ -110,7 +110,7 @@
}
-void LaserScanDisplay::incomingScanCallback(const boost::shared_ptr<std_msgs::LaserScan>& scan)
+void LaserScanDisplay::incomingScanCallback(const boost::shared_ptr<laser_scan::LaserScan>& scan)
{
boost::shared_ptr<std_msgs::PointCloud> cloud(new std_msgs::PointCloud);
@@ -141,12 +141,12 @@
topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &LaserScanDisplay::getTopic, this ),
boost::bind( &LaserScanDisplay::setTopic, this, _1 ), parent_category_, this );
topic_property_->addLegacyName("Scan Topic");
- topic_property_->setMessageType(std_msgs::LaserScan::__s_getDataType());
+ topic_property_->setMessageType(laser_scan::LaserScan::__s_getDataType());
}
const char* LaserScanDisplay::getDescription()
{
- return "Displays the data from a std_msgs::LaserScan message, with the option to accumulate over a period of time.";
+ return "Displays the data from a laser_scan::LaserScan message, with the option to accumulate over a period of time.";
}
} // namespace ogre_vis
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.h
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.h 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.h 2009-02-10 05:16:00 UTC (rev 10900)
@@ -34,7 +34,7 @@
#include "helpers/color.h"
#include "ogre_tools/point_cloud.h"
-#include "std_msgs/LaserScan.h"
+#include "laser_scan/LaserScan.h"
#include <boost/shared_ptr.hpp>
#include <boost/thread.hpp>
@@ -65,7 +65,7 @@
/**
* \class LaserScanDisplay
- * \brief Visualizes a laser scan, received as a std_msgs::LaserScan
+ * \brief Visualizes a laser scan, received as a laser_scan::LaserScan
*/
class LaserScanDisplay : public PointCloudBase
{
@@ -105,14 +105,14 @@
/**
* \brief ROS callback for an incoming point cloud message
*/
- void incomingScanCallback(const boost::shared_ptr<std_msgs::LaserScan>& scan);
+ void incomingScanCallback(const boost::shared_ptr<laser_scan::LaserScan>& scan);
std::string topic_; ///< The PointCloud topic set by setTopic()
ROSTopicStringProperty* topic_property_;
laser_scan::LaserProjection* projector_;
- tf::MessageNotifier<std_msgs::LaserScan>* notifier_;
+ tf::MessageNotifier<laser_scan::LaserScan>* notifier_;
};
} // namespace ogre_vis
Modified: pkg/trunk/visualization/pr2_dashboard/src/pr2_dashboard/reset.py
===================================================================
--- pkg/trunk/visualization/pr2_dashboard/src/pr2_dashboard/reset.py 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/visualization/pr2_dashboard/src/pr2_dashboard/reset.py 2009-02-10 05:16:00 UTC (rev 10900)
@@ -45,7 +45,7 @@
def __init__(self, parent):
wx.Panel.__init__(self, parent)
- xrc_path = roslib.packspec.get_pkg_dir(PKG) + '/xrc/reset_panel.xrc'
+ xrc_path = roslib.packages.get_pkg_dir(PKG) + '/xrc/reset_panel.xrc'
self._xrc = xrc.XmlResource(xrc_path)
self._real_panel = self._xrc.LoadPanel(self, 'ResetPanel')
Modified: pkg/trunk/world_models/costmap_2d/manifest.xml
===================================================================
--- pkg/trunk/world_models/costmap_2d/manifest.xml 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/world_models/costmap_2d/manifest.xml 2009-02-10 05:16:00 UTC (rev 10900)
@@ -6,6 +6,7 @@
<depend package="rosconsole"/>
<depend package="roscpp" />
<depend package="std_msgs" />
+<depend package="laser_scan" />
<depend package="pr2_msgs" />
<depend package="tf" />
<depend package="robot_filter" />
Modified: pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp
===================================================================
--- pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-02-10 03:28:10 UTC (rev 10899)
+++ pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-02-10 05:16:00 UTC (rev 10900)
@@ -33,7 +33,7 @@
#include <ros/node.h>
// our ros messages
-#include <std_msgs/LaserScan.h>
+#include <laser_scan/LaserScan.h>
#include <std_msgs/PointCloud.h>
#include <pr2_msgs/OccDiff.h>
#include <robot_srvs/StaticMap.h>
@@ -98,13 +98,13 @@
CostMap2D costmap_;
//laser scan message
- std_msgs::LaserScan laser_msg_;
+ laser_scan::LaserScan laser_msg_;
std_msgs::Polyline2D pointcloud_msg_;
//projector for the laser
laser_scan::LaserProjection projector_;
- std::list<std_msgs::LaserScan> buffered_laser_scans;
+ std::list<laser_scan::LaserScan> buffered_laser_scans;
};
@@ -188,13 +188,13 @@
void CostMap2DRos::laserReceived() {
- std_msgs::LaserScan newscan(laser_msg_);
+ laser_scan::LaserScan newscan(laser_msg_);
this->buffered_laser_scans.push_back(newscan);
std::list<unsigned int> new_occ_ids;
std::list<unsigned int> new_unocc_ids;
- for(std::list<std_msgs::LaserScan>::iterator it = this->buffered_laser_scans.begin();
+ for(std::list<laser_scan::LaserScan>::iterator it = this->buffered_laser_scans.begin();
it != this->buffered_laser_scans.end();
it++)
{
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|