|
From: <tf...@us...> - 2009-06-30 02:34:34
|
Revision: 17938
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17938&view=rev
Author: tfoote
Date: 2009-06-30 02:30:45 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
moving LaserScan from laser_scan package to sensor_msgs package #1254
Modified Paths:
--------------
pkg/trunk/calibration/laser_camera_calibration/gatherdata.py
pkg/trunk/calibration/laser_camera_calibration/manifest.xml
pkg/trunk/calibration/laser_cb_processing/manifest.xml
pkg/trunk/calibration/laser_cb_processing/src/laser_cb_processing.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp
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/robot/pr2/dense_laser_assembler/manifest.xml
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/scripts/assembler_node.py
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/drivers/simulator/test_pr2_sensors_gazebo/test_scan.py
pkg/trunk/mapping/door_tracker/manifest.xml
pkg/trunk/mapping/door_tracker/src/door_tracker.cpp
pkg/trunk/mapping/hallway_tracker/manifest.xml
pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp
pkg/trunk/nav/amcl/manifest.xml
pkg/trunk/nav/amcl/src/amcl_node.cpp
pkg/trunk/nav/base_local_planner/include/base_local_planner/trajectory_planner_ros.h
pkg/trunk/nav/base_local_planner/src/trajectory_planner_ros.cpp
pkg/trunk/nav/wavefront/manifest.xml
pkg/trunk/nav/wavefront/src/wavefront_node.cpp
pkg/trunk/stacks/common/laser_scan/CMakeLists.txt
pkg/trunk/stacks/common/laser_scan/include/laser_scan/footprint_filter.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/intensity_filter.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_processor.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_scan.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/median_filter.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/scan_shadows_filter.h
pkg/trunk/stacks/common/laser_scan/manifest.xml
pkg/trunk/stacks/common/laser_scan/src/generic_laser_filter_node.cpp
pkg/trunk/stacks/common/laser_scan/src/laser_processor.cpp
pkg/trunk/stacks/common/laser_scan/src/laser_scan.cc
pkg/trunk/stacks/common/laser_scan/src/scan_shadows_filter.cpp
pkg/trunk/stacks/common/laser_scan/src/scan_to_cloud.cpp
pkg/trunk/stacks/common/laser_scan/test/projection_test.cpp
pkg/trunk/stacks/laser_drivers/hokuyo_node/manifest.xml
pkg/trunk/stacks/laser_drivers/hokuyo_node/src/node/hokuyo_node.cpp
pkg/trunk/stacks/laser_drivers/sicktoolbox_wrapper/manifest.xml
pkg/trunk/stacks/laser_drivers/sicktoolbox_wrapper/ros/sicklms/sicklms.cpp
pkg/trunk/stacks/map_building/slam_gmapping/src/slam_gmapping.cpp
pkg/trunk/stacks/map_building/slam_gmapping/src/slam_gmapping.h
pkg/trunk/stacks/map_building/slam_gmapping/src/tftest.cpp
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/manifest.xml
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/laser_scan_assembler_srv.cpp
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/point_cloud_assembler_srv.cpp
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/test/test_assembler.cpp
pkg/trunk/stacks/simulators/stage/manifest.xml
pkg/trunk/stacks/simulators/stage/src/stageros.cpp
pkg/trunk/stacks/visualization/rviz/manifest.xml
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/laser_scan_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/laser_scan_display.h
pkg/trunk/stacks/world_models/costmap_2d/include/costmap_2d/costmap_2d_ros.h
pkg/trunk/stacks/world_models/costmap_2d/manifest.xml
pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp
pkg/trunk/stacks/world_models/costmap_2d/src/costmap_test.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/vision/people/manifest.xml
pkg/trunk/vision/people/src/calc_leg_features.cpp
pkg/trunk/vision/people/src/calc_leg_features.h
pkg/trunk/vision/people/src/leg_detector.cpp
pkg/trunk/vision/people/src/train_leg_detector.cpp
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/LaserScan.msg
Removed Paths:
-------------
pkg/trunk/stacks/common/laser_scan/msg/LaserScan.msg
Modified: pkg/trunk/calibration/laser_camera_calibration/gatherdata.py
===================================================================
--- pkg/trunk/calibration/laser_camera_calibration/gatherdata.py 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/laser_camera_calibration/gatherdata.py 2009-06-30 02:30:45 UTC (rev 17938)
@@ -46,7 +46,7 @@
import rospy
from roslib import rostime
-from laser_scan.msg import LaserScan
+from sensor_msgs.msg import LaserScan
from mechanism_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-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/laser_camera_calibration/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -11,7 +11,7 @@
<review status="unreviewed" notes=""/>
<depend package="robot_msgs"/>
<depend package="std_msgs"/>
- <depend package="laser_scan"/>
+ <depend package="sensor_msgs"/>
<depend package="rospy"/>
<depend package="rosoct"/>
<depend package="openraveros"/>
Modified: pkg/trunk/calibration/laser_cb_processing/manifest.xml
===================================================================
--- pkg/trunk/calibration/laser_cb_processing/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/laser_cb_processing/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -10,7 +10,7 @@
<depend package="topic_synchronizer" />
<depend package="robot_msgs" />
<depend package="opencv_latest" />
- <depend package="laser_scan" />
+ <depend package="sensor_msgs" />
<depend package="dense_laser_assembler" />
<!-- For the pr2 tilt-laser projector -->
Modified: pkg/trunk/calibration/laser_cb_processing/src/laser_cb_processing.cpp
===================================================================
--- pkg/trunk/calibration/laser_cb_processing/src/laser_cb_processing.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/laser_cb_processing/src/laser_cb_processing.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -38,7 +38,7 @@
#include "dense_laser_assembler/Float32MultiArrayStamped.h"
#include "robot_msgs/PointCloud.h"
#include "robot_msgs/Point32.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "topic_synchronizer/topic_synchronizer.h"
@@ -162,7 +162,7 @@
}
- inline float pointingAngle(const laser_scan::LaserScan& info, const float& ray)
+ inline float pointingAngle(const sensor_msgs::LaserScan& info, const float& ray)
{
return info.angle_min + info.angle_increment * ray;
}
@@ -198,7 +198,7 @@
robot_msgs::PointCloud pixel_corners_;
dense_laser_assembler::Float32MultiArrayStamped dense_range_;
dense_laser_assembler::Float32MultiArrayStamped joint_info_;
- laser_scan::LaserScan scan_info_;
+ sensor_msgs::LaserScan scan_info_;
};
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -39,7 +39,7 @@
#include "tf/tfMessage.h"
#include "tf/transform_datatypes.h"
#include "mechanism_msgs/MechanismState.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "image_msgs/RawStereo.h"
class LaserHeadKinematics
@@ -57,7 +57,7 @@
this) ;
// Tilt Scan Updates
- laser_pub_ = nh.advertise<laser_scan::LaserScan>("tilt_scan_cal", 100) ;
+ laser_pub_ = nh.advertise<sensor_msgs::LaserScan>("tilt_scan_cal", 100) ;
laser_sub_ = nh.subscribe("tilt_scan", 100,
&LaserHeadKinematics::updateTiltScan, this) ;
@@ -75,9 +75,9 @@
stereo_pub_.publish(msg_out) ;
}
- void updateTiltScan(const laser_scan::LaserScanConstPtr& msg_in)
+ void updateTiltScan(const sensor_msgs::LaserScanConstPtr& msg_in)
{
- laser_scan::LaserScan msg_out ;
+ sensor_msgs::LaserScan msg_out ;
msg_out = *msg_in ;
msg_out.header.frame_id = "laser_tilt_link_cal" ;
laser_pub_.publish(msg_out) ;
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -39,7 +39,7 @@
#include "tf/tfMessage.h"
#include "tf/transform_datatypes.h"
#include "mechanism_msgs/MechanismState.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "image_msgs/RawStereo.h"
class LaserHeadKinematics
@@ -57,7 +57,7 @@
this) ;
// Tilt Scan Updates
- laser_pub_ = nh.advertise<laser_scan::LaserScan>("tilt_scan_cal", 100) ;
+ laser_pub_ = nh.advertise<sensor_msgs::LaserScan>("tilt_scan_cal", 100) ;
laser_sub_ = nh.subscribe("tilt_scan", 100,
&LaserHeadKinematics::updateTiltScan, this) ;
@@ -76,9 +76,9 @@
stereo_pub_.publish(msg_out) ;
}
- void updateTiltScan(const laser_scan::LaserScanConstPtr& msg_in)
+ void updateTiltScan(const sensor_msgs::LaserScanConstPtr& msg_in)
{
- laser_scan::LaserScan msg_out ;
+ sensor_msgs::LaserScan msg_out ;
msg_out = *msg_in ;
msg_out.header.frame_id = "laser_tilt_link_cal" ;
laser_pub_.publish(msg_out) ;
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -39,7 +39,7 @@
#include "tf/tfMessage.h"
#include "tf/transform_datatypes.h"
#include "mechanism_msgs/MechanismState.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "image_msgs/RawStereo.h"
class LaserHeadKinematics
@@ -57,7 +57,7 @@
this) ;
// Tilt Scan Updates
- laser_pub_ = nh.advertise<laser_scan::LaserScan>("tilt_scan_cal", 100) ;
+ laser_pub_ = nh.advertise<sensor_msgs::LaserScan>("tilt_scan_cal", 100) ;
laser_sub_ = nh.subscribe("tilt_scan", 100,
&LaserHeadKinematics::updateTiltScan, this) ;
@@ -76,9 +76,9 @@
stereo_pub_.publish(msg_out) ;
}
- void updateTiltScan(const laser_scan::LaserScanConstPtr& msg_in)
+ void updateTiltScan(const sensor_msgs::LaserScanConstPtr& msg_in)
{
- laser_scan::LaserScan msg_out ;
+ sensor_msgs::LaserScan msg_out ;
msg_out = *msg_in ;
msg_out.header.frame_id = "laser_tilt_link_cal" ;
laser_pub_.publish(msg_out) ;
Modified: pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml
===================================================================
--- pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -6,7 +6,7 @@
<license>BSD</license>
<review status="experimental" notes=""/>
<url>http://pr.willowgarage.com</url>
-<depend package="laser_scan"/>
+<depend package="sensor_msgs"/>
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
<depend package="roscpp"/>
Modified: pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg
===================================================================
--- pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg 2009-06-30 02:30:45 UTC (rev 17938)
@@ -1,2 +1,2 @@
-laser_scan/LaserScan scan # The original laser scan
+sensor_msgs/LaserScan scan # The original laser scan
robot_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-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -28,14 +28,13 @@
*/
#include "ros/node.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/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 laser_scan ;
namespace laser_scan_annotator
{
@@ -105,7 +104,7 @@
}
protected:
- laser_scan::LaserScan scan_in_ ;
+ sensor_msgs::LaserScan scan_in_ ;
string fixed_frame_ ;
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -14,7 +14,7 @@
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
<depend package="mechanism_msgs" />
- <depend package="laser_scan"/>
+ <depend package="sensor_msgs"/>
<depend package="pr2_mechanism_controllers"/>
<depend package="image_msgs" />
<depend package="mechanism_msgs" />
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/scripts/assembler_node.py
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/scripts/assembler_node.py 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/scripts/assembler_node.py 2009-06-30 02:30:45 UTC (rev 17938)
@@ -39,7 +39,7 @@
import rospy
import threading
from time import sleep
-from laser_scan.msg import *
+from sensor_msgs.msg import LaserScan
from robot_msgs.msg import *
from mechanism_msgs.msg import MechanismState
from std_msgs.msg import *
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-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h 2009-06-30 02:30:45 UTC (rev 17938)
@@ -32,7 +32,7 @@
#include <ros/ros.h>
#include <boost/thread/mutex.hpp>
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/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
- laser_scan::LaserScan ROS topic.
+ sensor_msgs::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 laser_scan::LaserScan.msg over ROS.
+ \li Simulates a laser range sensor and publish sensor_msgs::LaserScan.msg over ROS.
\li Example Usage:
\verbatim
<model:physical name="ray_model">
@@ -145,7 +145,7 @@
private: ros::Publisher pub_;
/// \brief ros message
- private: laser_scan::LaserScan laserMsg;
+ private: sensor_msgs::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-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -19,7 +19,7 @@
<depend package="mechanism_msgs" />
<depend package="image_msgs" />
<depend package="opencv_latest" />
- <depend package="laser_scan" />
+ <depend package="sensor_msgs" />
<depend package="pr2_msgs" />
<depend package="robot_msgs" />
<depend package="diagnostic_msgs" />
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -81,7 +81,7 @@
{
this->topicName = node->GetString("topicName","default_ros_laser",0); //read from xml file
ROS_DEBUG("================= %s", this->topicName.c_str());
- this->pub_ = this->rosnode_->advertise<laser_scan::LaserScan>(this->topicName,10);
+ this->pub_ = this->rosnode_->advertise<sensor_msgs::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/drivers/simulator/test_pr2_sensors_gazebo/test_scan.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/test_scan.py 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/test_scan.py 2009-06-30 02:30:45 UTC (rev 17938)
@@ -46,7 +46,7 @@
import sys, unittest
import os, os.path, threading, time
import rospy, rostest
-from laser_scan.msg import *
+from sensor_msgs.msg import LaserScan
TEST_DURATION = 15
ERROR_TOL = 0.05
Modified: pkg/trunk/mapping/door_tracker/manifest.xml
===================================================================
--- pkg/trunk/mapping/door_tracker/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/mapping/door_tracker/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -10,6 +10,8 @@
<depend package="eigen" />
<depend package="roscpp" />
+ <depend package="laser_scan" />
+ <depend package="sensor_msgs" />
<depend package="robot_msgs" />
<depend package="door_msgs" />
<depend package="robot_srvs" />
Modified: pkg/trunk/mapping/door_tracker/src/door_tracker.cpp
===================================================================
--- pkg/trunk/mapping/door_tracker/src/door_tracker.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/mapping/door_tracker/src/door_tracker.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -80,7 +80,7 @@
#include <sys/time.h>
// Clouds and scans
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/LaserScan.h>
#include <laser_scan/laser_scan.h>
//Filters
@@ -109,7 +109,7 @@
tf::TransformListener *tf_;
- tf::MessageNotifier<laser_scan::LaserScan>* message_notifier_;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* message_notifier_;
door_msgs::Door door_msg_;
@@ -121,7 +121,7 @@
bool active_;
- filters::FilterChain<laser_scan::LaserScan> filter_chain_;
+ filters::FilterChain<sensor_msgs::LaserScan> filter_chain_;
tf::Stamped<tf::Pose> global_pose_;
@@ -352,7 +352,7 @@
node_->advertise<door_msgs::Door>( "~door_message", 0 );
node_->advertiseService ("~doors_detector", &DoorTracker::detectDoorService, this);
- message_notifier_ = new tf::MessageNotifier<laser_scan::LaserScan> (tf_, node_, boost::bind(&DoorTracker::laserCallBack, this, _1), base_laser_topic_.c_str (), fixed_frame_, 1);
+ message_notifier_ = new tf::MessageNotifier<sensor_msgs::LaserScan> (tf_, node_, boost::bind(&DoorTracker::laserCallBack, this, _1), base_laser_topic_.c_str (), fixed_frame_, 1);
message_notifier_->setTolerance(ros::Duration(.02));
active_ = true;
}
@@ -406,7 +406,7 @@
- void laserCallBack(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& scan_msg)
+ void laserCallBack(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& scan_msg)
{
if(!active_)
return;
@@ -417,7 +417,7 @@
cloud_msg_mutex_.lock();
done_detection_ = false;
- laser_scan::LaserScan filtered_scan;
+ sensor_msgs::LaserScan filtered_scan;
filter_chain_.update (*scan_msg, filtered_scan);
// Transform into a PointCloud message
int mask = laser_scan::MASK_INTENSITY | laser_scan::MASK_DISTANCE | laser_scan::MASK_INDEX | laser_scan::MASK_TIMESTAMP;
Modified: pkg/trunk/mapping/hallway_tracker/manifest.xml
===================================================================
--- pkg/trunk/mapping/hallway_tracker/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/mapping/hallway_tracker/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -14,6 +14,7 @@
<depend package="kdl" />
<depend package="point_cloud_mapping" />
<depend package="std_msgs" />
+ <depend package="sensor_msgs" />
<depend package="laser_scan" />
<depend package="filters" />
<depend package="visualization_msgs" />
Modified: pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp
===================================================================
--- pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -75,7 +75,7 @@
// Clouds and scans
#include <robot_msgs/PointCloud.h>
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/LaserScan.h>
#include <laser_scan/laser_scan.h>
@@ -104,8 +104,8 @@
laser_scan::LaserProjection projector_; // Used to project laser scans into point clouds
tf::TransformListener *tf_;
- tf::MessageNotifier<laser_scan::LaserScan>* message_notifier_;
- filters::FilterChain<laser_scan::LaserScan> filter_chain_;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* message_notifier_;
+ filters::FilterChain<sensor_msgs::LaserScan> filter_chain_;
/********** Parameters from the param server *******/
std::string base_laser_topic_; // Topic for the laser scan message.
@@ -156,7 +156,7 @@
node_->advertise<robot_msgs::PointCloud>("parallel_lines_model",0);
// Subscribe to the scans.
- message_notifier_ = new tf::MessageNotifier<laser_scan::LaserScan> (tf_, node_, boost::bind(&HallwayTracker::laserCallBack, this, _1), base_laser_topic_.c_str(), fixed_frame_, 1);
+ message_notifier_ = new tf::MessageNotifier<sensor_msgs::LaserScan> (tf_, node_, boost::bind(&HallwayTracker::laserCallBack, this, _1), base_laser_topic_.c_str(), fixed_frame_, 1);
message_notifier_->setTolerance(ros::Duration(.02));
}
@@ -170,9 +170,9 @@
/**
* \brief Laser callback. Processes a laser scan by converting it into a point cloud, removing points that are too far away, finding two parallel lines and publishing the results.
*/
- void laserCallBack(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& scan_msg)
+ void laserCallBack(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& scan_msg)
{
- laser_scan::LaserScan filtered_scan;
+ sensor_msgs::LaserScan filtered_scan;
filter_chain_.update (*scan_msg, filtered_scan);
Modified: pkg/trunk/nav/amcl/manifest.xml
===================================================================
--- pkg/trunk/nav/amcl/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/amcl/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -12,8 +12,8 @@
<depend package="nav_msgs" />
<depend package="nav_srvs" />
<depend package="std_srvs" />
- <depend package="laser_scan" />
<depend package="visualization_msgs"/>
+ <depend package="sensor_msgs" />
<!-- For tests -->
<depend package="map_server"/>
Modified: pkg/trunk/nav/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -61,7 +61,7 @@
@section topic ROS topics
Subscribes to (name type):
-- @b "scan" laser_scan/LaserScan : laser scans
+- @b "scan" sensor_msgs/LaserScan : laser scans
- @b "tf_message" tf/tfMessage : transforms
Publishes to (name type):
@@ -156,7 +156,7 @@
#include "ros/node.h"
// Messages that I need
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "robot_msgs/PoseWithCovariance.h"
#include "nav_msgs/ParticleCloud.h"
#include "robot_msgs/Pose.h"
@@ -231,7 +231,7 @@
// Message callbacks
bool globalLocalizationCallback(std_srvs::Empty::Request& req,
std_srvs::Empty::Response& res);
- void laserReceived(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& laser_scan);
+ void laserReceived(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& laser_scan);
void initialPoseReceived();
double getYaw(tf::Pose& t);
@@ -254,7 +254,7 @@
double resolution;
bool have_laser_pose;
- tf::MessageNotifier<laser_scan::LaserScan>* laser_scan_notifer;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* laser_scan_notifer;
// Particle filter
pf_t *pf_;
@@ -446,7 +446,7 @@
&AmclNode::globalLocalizationCallback,
this);
laser_scan_notifer =
- new tf::MessageNotifier<laser_scan::LaserScan>
+ new tf::MessageNotifier<sensor_msgs::LaserScan>
(tf_, ros::Node::instance(),
boost::bind(&AmclNode::laserReceived,
this, _1),
@@ -578,7 +578,7 @@
}
void
-AmclNode::laserReceived(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& laser_scan)
+AmclNode::laserReceived(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& laser_scan)
{
// Do we have the base->base_laser Tx yet?
if(!have_laser_pose)
Modified: pkg/trunk/nav/base_local_planner/include/base_local_planner/trajectory_planner_ros.h
===================================================================
--- pkg/trunk/nav/base_local_planner/include/base_local_planner/trajectory_planner_ros.h 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/base_local_planner/include/base_local_planner/trajectory_planner_ros.h 2009-06-30 02:30:45 UTC (rev 17938)
@@ -56,10 +56,8 @@
#include <robot_msgs/PoseDot.h>
#include <robot_msgs/Point.h>
-#include <laser_scan/LaserScan.h>
#include <tf/message_notifier.h>
#include <tf/transform_listener.h>
-#include <laser_scan/laser_scan.h>
#include <boost/thread.hpp>
Modified: pkg/trunk/nav/base_local_planner/src/trajectory_planner_ros.cpp
===================================================================
--- pkg/trunk/nav/base_local_planner/src/trajectory_planner_ros.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/base_local_planner/src/trajectory_planner_ros.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -44,7 +44,6 @@
using namespace std;
using namespace robot_msgs;
using namespace costmap_2d;
-using namespace laser_scan;
namespace base_local_planner {
//register this base local planner with the BaseLocalPlanner factory
Modified: pkg/trunk/nav/wavefront/manifest.xml
===================================================================
--- pkg/trunk/nav/wavefront/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/wavefront/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -6,6 +6,7 @@
<depend package="roscpp" />
<depend package="laser_scan" />
<depend package="nav_srvs" />
+ <depend package="sensor_msgs" />
<depend package="robot_msgs" />
<depend package="robot_actions" />
<depend package="nav_robot_actions" />
Modified: pkg/trunk/nav/wavefront/src/wavefront_node.cpp
===================================================================
--- pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -63,7 +63,7 @@
Subscribes to (name/type):
- @b "tf_message" tf/tfMessage: robot's pose in the "map" frame
- @b "goal" robot_msgs/PoseStamped : goal for the robot.
-- @b "scan" laser_scan/LaserScan : laser scans. Used to temporarily modify the map for dynamic obstacles.
+- @b "scan" sensor_msgs/LaserScan : laser scans. Used to temporarily modify the map for dynamic obstacles.
Publishes to (name / type):
- @b "cmd_vel" robot_msgs/PoseDot : velocity commands to robot
@@ -105,7 +105,7 @@
#include <robot_msgs/PoseStamped.h>
#include <robot_msgs/PoseDot.h>
#include <robot_msgs/PointCloud.h>
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/LaserScan.h>
#include <nav_srvs/StaticMap.h>
// For GUI debug
@@ -202,14 +202,14 @@
//MsgRobotBase2DOdom prevOdom;
bool firstodom;
- tf::MessageNotifier<laser_scan::LaserScan>* scan_notifier;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* scan_notifier;
// Lock for access to class members in callbacks
boost::mutex lock;
// Message callbacks
void goalReceived();
- void laserReceived(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& message);
+ void laserReceived(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& message);
// Internal helpers
void sendVelCmd(double vx, double vy, double vth);
@@ -367,7 +367,7 @@
advertise<robot_msgs::PoseDot>("cmd_vel",1);
subscribe("goal", goalMsg, &WavefrontNode::goalReceived,1);
- scan_notifier = new tf::MessageNotifier<laser_scan::LaserScan>(&tf, this, boost::bind(&WavefrontNode::laserReceived, this, _1), "scan", "/map", 1);
+ scan_notifier = new tf::MessageNotifier<sensor_msgs::LaserScan>(&tf, this, boost::bind(&WavefrontNode::laserReceived, this, _1), "scan", "/map", 1);
}
WavefrontNode::~WavefrontNode()
@@ -423,7 +423,7 @@
}
void
-WavefrontNode::laserReceived(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& message)
+WavefrontNode::laserReceived(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& message)
{
// Assemble a point cloud, in the laser's frame
robot_msgs::PointCloud local_cloud;
Modified: pkg/trunk/stacks/common/laser_scan/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/common/laser_scan/CMakeLists.txt 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/CMakeLists.txt 2009-06-30 02:30:45 UTC (rev 17938)
@@ -23,3 +23,4 @@
rospack_add_gtest(test/projection_test test/projection_test.cpp)
target_link_libraries (test/projection_test laser_scan)
+
Modified: pkg/trunk/stacks/common/laser_scan/include/laser_scan/footprint_filter.h
===================================================================
--- pkg/trunk/stacks/common/laser_scan/include/laser_scan/footprint_filter.h 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/include/laser_scan/footprint_filter.h 2009-06-30 02:30:45 UTC (rev 17938)
@@ -43,7 +43,7 @@
#include "filters/filter_base.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "tf/transform_listener.h"
#include "robot_msgs/PointCloud.h"
#include "ros/ros.h"
@@ -53,7 +53,7 @@
{
template <typename T>
-class LaserScanFootprintFilter : public filters::FilterBase<laser_scan::LaserScan>
+class LaserScanFootprintFilter : public filters::FilterBase<sensor_msgs::LaserScan>
{
public:
LaserScanFootprintFilter(){}
@@ -69,7 +69,7 @@
}
- bool update(const std::vector<laser_scan::LaserScan>& data_in, std::vector<laser_scan::LaserScan>& data_out)
+ bool update(const std::vector<sensor_msgs::LaserScan>& data_in, std::vector<sensor_msgs::LaserScan>& data_out)
{
if (data_in.size() != 1 || data_out.size() != 1)
{
@@ -77,8 +77,8 @@
return false;
}
- const LaserScan& input_scan = data_in[0];
- LaserScan& filtered_scan = data_out[0];
+ const sensor_msgs::LaserScan& input_scan = data_in[0];
+ sensor_msgs::LaserScan& filtered_scan = data_out[0];
filtered_scan = input_scan ;
@@ -134,7 +134,8 @@
double inscribed_radius_;
} ;
-FILTERS_REGISTER_FILTER(LaserScanFootprintFilter, LaserScan);
+typedef sensor_msgs::LaserScan sensor_msgs_laser_scan;
+FILTERS_REGISTER_FILTER(LaserScanFootprintFilter, sensor_msgs_laser_scan);
}
#endif // LASER_SCAN_FOOTPRINT_FILTER_H
Modified: pkg/trunk/stacks/common/laser_scan/include/laser_scan/intensity_filter.h
===================================================================
--- pkg/trunk/stacks/common/laser_scan/include/laser_scan/intensity_filter.h 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/include/laser_scan/intensity_filter.h 2009-06-30 02:30:45 UTC (rev 17938)
@@ -42,13 +42,13 @@
#include "filters/filter_base.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
namespace laser_scan
{
template <typename T>
-class LaserScanIntensityFilter : public filters::FilterBase<laser_scan::LaserScan>
+class LaserScanIntensityFilter : public filters::FilterBase<sensor_msgs::LaserScan>
{
public:
@@ -69,7 +69,7 @@
}
- bool update(const std::vector<laser_scan::LaserScan>& data_in, std::vector<laser_scan::LaserScan>& data_out)
+ bool update(const std::vector<sensor_msgs::LaserScan>& data_in, std::vector<sensor_msgs::LaserScan>& data_out)
{
if (data_in.size() != 1 || data_out.size() != 1)
{
@@ -77,8 +77,8 @@
return false;
}
- const LaserScan& input_scan = data_in[0];
- LaserScan& filtered_scan = data_out[0];
+ const sensor_msgs::LaserScan& input_scan = data_in[0];
+ sensor_msgs::LaserScan& filtered_scan = data_out[0];
const double hist_max = 4*12000.0 ;
const int num_buckets = 24 ;
@@ -115,8 +115,8 @@
return true;
}
} ;
-typedef laser_scan::LaserScan laser_scan_laser_scan;
-FILTERS_REGISTER_FILTER(LaserScanIntensityFilter, laser_scan_laser_scan);
+typedef sensor_msgs::LaserScan sensor_msgs_laser_scan;
+FILTERS_REGISTER_FILTER(LaserScanIntensityFilter, sensor_msgs_laser_scan);
}
#endif // LASER_SCAN_INTENSITY_FILTER_H
Modified: pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_processor.h
===================================================================
--- pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_processor.h 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_processor.h 2009-06-30 02:30:45 UTC (rev 17938)
@@ -45,7 +45,7 @@
#include <unistd.h>
#include <math.h>
#include "ros/node.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "robot_msgs/PointCloud.h"
#include "robot_msgs/Point.h"
@@ -70,7 +70,7 @@
float x;
float y;
- static Sample* Extract(int ind, laser_scan::LaserScan& scan);
+ static Sample* Extract(int ind, sensor_msgs::LaserScan& scan);
private:
Sample() {};
@@ -116,7 +116,7 @@
inline void clear() { mask_.clear(); filled = false; }
- void addScan(laser_scan::LaserScan& scan);
+ void addScan(sensor_msgs::LaserScan& scan);
bool hasSample(Sample* s, float thresh);
};
@@ -126,13 +126,13 @@
class ScanProcessor
{
std::list<SampleSet*> clusters_;
- laser_scan::LaserScan scan_;
+ sensor_msgs::LaserScan scan_;
public:
std::list<SampleSet*>& getClusters() { return clusters_; }
- ScanProcessor(laser_scan::LaserScan& scan, ScanMask& mask_, float mask_threshold = 0.03);
+ ScanProcessor(sensor_msgs::LaserScan& scan, ScanMask& mask_, float mask_threshold = 0.03);
~ScanProcessor();
Modified: pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_scan.h
===================================================================
--- pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_scan.h 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_scan.h 2009-06-30 02:30:45 UTC (rev 17938)
@@ -38,7 +38,7 @@
#include "tf/tf.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "robot_msgs/PointCloud.h"
#include "robot_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 laser_scan::LaserScan& scan_in, robot_msgs::PointCloud & cloud_out, double range_cutoff=-1.0, bool preservative = false, int mask = DEFAULT_MASK);
+ void projectLaser (const sensor_msgs::LaserScan& scan_in, robot_msgs::PointCloud & cloud_out, double range_cutoff=-1.0, bool preservative = false, int mask = DEFAULT_MASK);
- /** \brief Transform a laser_scan::LaserScan into a PointCloud in target frame */
- void transformLaserScanToPointCloud (const std::string& target_frame, robot_msgs::PointCloud & cloudOut, const laser_scan::LaserScan & scanIn, tf::Transformer & tf, int mask = DEFAULT_MASK, bool preservative = false);
+ /** \brief Transform a sensor_msgs::LaserScan into a PointCloud in target frame */
+ void transformLaserScanToPointCloud (const std::string& target_frame, robot_msgs::PointCloud & cloudOut, const sensor_msgs::LaserScan & scanIn, tf::Transformer & tf, int mask = DEFAULT_MASK, bool preservative = false);
/** \brief Return the unit vectors for this configuration
* Return the unit vectors for this configuration.
Modified: pkg/trunk/stacks/common/laser_scan/include/laser_scan/median_filter.h
===================================================================
--- pkg/trunk/stacks/common/laser_scan/include/laser_scan/median_filter.h 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/include/laser_scan/median_filter.h 2009-06-30 02:30:45 UTC (rev 17938)
@@ -36,7 +36,7 @@
#include "boost/thread/mutex.hpp"
#include "boost/scoped_ptr.hpp"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "filters/median.h"
#include "filters/mean.h"
@@ -62,7 +62,7 @@
* \param scan_in The new scan to filter
* \param scan_out The filtered scan
*/
- bool update(const std::vector<laser_scan::LaserScan>& scan_in, std::vector<laser_scan::LaserScan>& scan_out);
+ bool update(const std::vector<sensor_msgs::LaserScan>& scan_in, std::vector<sensor_msgs::LaserScan>& scan_out);
private:
@@ -70,7 +70,7 @@
unsigned int num_ranges_; /// How many data point are in each row
boost::mutex data_lock; /// Protection from multi threaded programs
- laser_scan::LaserScan temp_scan_; /** \todo cache only shallow info not full scan */
+ sensor_msgs::LaserScan temp_scan_; /** \todo cache only shallow info not full scan */
filters::FilterChain<float> * range_filter_;
filters::FilterChain<float> * intensity_filter_;
@@ -78,9 +78,9 @@
boost::scoped_ptr<TiXmlElement> latest_xml_;
};
-typedef laser_scan::LaserScan laser_scan_laser_scan;
+typedef sensor_msgs::LaserScan sensor_msgs_laser_scan;
-FILTERS_REGISTER_FILTER(LaserMedianFilter, laser_scan_laser_scan);
+FILTERS_REGISTER_FILTER(LaserMedianFilter, sensor_msgs_laser_scan);
template <typename T>
LaserMedianFilter<T>::LaserMedianFilter():
@@ -122,7 +122,7 @@
};
template <typename T>
-bool LaserMedianFilter<T>::update(const std::vector<laser_scan::LaserScan>& data_in, std::vector<laser_scan::LaserScan>& data_out)
+bool LaserMedianFilter<T>::update(const std::vector<sensor_msgs::LaserScan>& data_in, std::vector<sensor_msgs::LaserScan>& data_out)
{
if (!this->configured_)
{
@@ -134,8 +134,8 @@
ROS_ERROR("LaserMedianFilter is not vectorized");
return false;
}
- const laser_scan::LaserScan & scan_in = data_in[0];
- laser_scan::LaserScan & scan_out = data_out[0];
+ const sensor_msgs::LaserScan & scan_in = data_in[0];
+ sensor_msgs::LaserScan & scan_out = data_out[0];
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/stacks/common/laser_scan/include/laser_scan/scan_shadows_filter.h
===================================================================
--- pkg/trunk/stacks/common/laser_scan/include/laser_scan/scan_shadows_filter.h 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/include/laser_scan/scan_shadows_filter.h 2009-06-30 02:30:45 UTC (rev 17938)
@@ -40,7 +40,7 @@
#include <set>
#include "filters/filter_base.h"
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/LaserScan.h>
#include "angles/angles.h"
namespace laser_scan{
@@ -109,7 +109,7 @@
* \param scan_in the input LaserScan message
* \param scan_out the output LaserScan message
*/
- bool update(const std::vector<laser_scan::LaserScan>& scans_in, std::vector<laser_scan::LaserScan>& scans_out)
+ bool update(const std::vector<sensor_msgs::LaserScan>& scans_in, std::vector<sensor_msgs::LaserScan>& scans_out)
{
if (scans_in.size() != 1)
{
@@ -123,8 +123,8 @@
}
//Local references for ease of use
- const laser_scan::LaserScan& scan_in = scans_in[0];
- laser_scan::LaserScan& scan_out = scans_out[0];
+ const sensor_msgs::LaserScan& scan_in = scans_in[0];
+ sensor_msgs::LaserScan& scan_out = scans_out[0];
//copy across all data first
scan_out = scan_in;
@@ -163,8 +163,8 @@
////////////////////////////////////////////////////////////////////////////////
} ;
-typedef laser_scan::LaserScan laser_scan_laser_scan;
-FILTERS_REGISTER_FILTER(ScanShadowsFilter, laser_scan_laser_scan);
+typedef sensor_msgs::LaserScan sensor_msgs_laser_scan;
+FILTERS_REGISTER_FILTER(ScanShadowsFilter, sensor_msgs_laser_scan);
}
#endif //LASER_SCAN_SHADOWS_FILTER_H
Modified: pkg/trunk/stacks/common/laser_scan/manifest.xml
===================================================================
--- pkg/trunk/stacks/common/laser_scan/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -8,7 +8,7 @@
<license>BSD</license>
<review status="API cleared" notes=""/>
<url>http://pr.willowgarage.com/wiki/laser_scan</url>
-<depend package="std_msgs"/>
+<depend package="sensor_msgs"/>
<depend package="roscpp"/>
<depend package="tf"/>
<depend package="filters"/>
Deleted: pkg/trunk/stacks/common/laser_scan/msg/LaserScan.msg
===================================================================
--- pkg/trunk/stacks/common/laser_scan/msg/LaserScan.msg 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/msg/LaserScan.msg 2009-06-30 02:30:45 UTC (rev 17938)
@@ -1,15 +0,0 @@
-#
-# 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/stacks/common/laser_scan/src/generic_laser_filter_node.cpp
===================================================================
--- pkg/trunk/stacks/common/laser_scan/src/generic_laser_filter_node.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/src/generic_laser_filter_node.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -28,7 +28,7 @@
*/
#include "ros/node.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "laser_scan/median_filter.h"
#include "laser_scan/intensity_filter.h"
#include "laser_scan/scan_shadows_filter.h"
@@ -43,8 +43,8 @@
public:
GenericLaserScanFilterNode(ros::Node& anode) : filter_chain_(), node_(anode), notifier_(NULL)
{
- node_.advertise<laser_scan::LaserScan>("~output", 1000);
- notifier_ = new tf::MessageNotifier<laser_scan::LaserScan>(&tf_, &node_,
+ node_.advertise<sensor_msgs::LaserScan>("~output", 1000);
+ notifier_ = new tf::MessageNotifier<sensor_msgs::LaserScan>(&tf_, &node_,
boost::bind(&GenericLaserScanFilterNode::callback, this, _1), "scan_in", "base_link", 50);
notifier_->setTolerance(ros::Duration(0.03));
@@ -61,18 +61,18 @@
delete notifier_;
}
- void callback(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& msg_in)
+ void callback(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& msg_in)
{
filter_chain_.update (*msg_in, msg);
node_.publish("~output", msg);
}
protected:
- filters::FilterChain<laser_scan::LaserScan> filter_chain_;
+ filters::FilterChain<sensor_msgs::LaserScan> filter_chain_;
ros::Node& node_;
tf::TransformListener tf_;
- tf::MessageNotifier<laser_scan::LaserScan>* notifier_;
- laser_scan::LaserScan msg;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* notifier_;
+ sensor_msgs::LaserScan msg;
};
Modified: pkg/trunk/stacks/common/laser_scan/src/laser_processor.cpp
===================================================================
--- pkg/trunk/stacks/common/laser_scan/src/laser_processor.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/src/laser_processor.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -40,7 +40,7 @@
using namespace std;
using namespace laser_scan;
-Sample* Sample::Extract(int ind, laser_scan::LaserScan& scan)
+Sample* Sample::Extract(int ind, sensor_msgs::LaserScan& scan)
{
Sample* s = new Sample;
@@ -112,7 +112,7 @@
}
-void ScanMask::addScan(laser_scan::LaserScan& scan)
+void ScanMask::addScan(sensor_msgs::LaserScan& scan)
{
if (!filled)
{
@@ -169,7 +169,7 @@
-ScanProcessor::ScanProcessor(laser_scan::LaserScan& scan, ScanMask& mask_, float mask_threshold)
+ScanProcessor::ScanProcessor(sensor_msgs::LaserScan& scan, ScanMask& mask_, float mask_threshold)
{
scan_ = scan;
Modified: pkg/trunk/stacks/common/laser_scan/src/laser_scan.cc
===================================================================
--- pkg/trunk/stacks/common/laser_scan/src/laser_scan.cc 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/src/laser_scan.cc 2009-06-30 02:30:45 UTC (rev 17938)
@@ -34,7 +34,7 @@
{
void
- LaserProjection::projectLaser (const laser_scan::LaserScan& scan_in, robot_msgs::PointCloud & cloud_out, double range_cutoff,
+ LaserProjection::projectLaser (const sensor_msgs::LaserScan& scan_in, robot_msgs::PointCloud & cloud_out, double range_cutoff,
bool preservative, int mask)
{
boost::numeric::ublas::matrix<double> ranges(2, scan_in.get_ranges_size());
@@ -194,7 +194,7 @@
};
void
- LaserProjection::transformLaserScanToPointCloud (const std::string &target_frame, robot_msgs::PointCloud &cloud_out, const laser_scan::LaserScan &scan_in,
+ LaserProjection::transformLaserScanToPointCloud (const std::string &target_frame, robot_msgs::PointCloud &cloud_out, const sensor_msgs::LaserScan &scan_in,
tf::Transformer& tf, int mask, bool preservative)
{
cloud_out.header = scan_in.header;
Modified: pkg/trunk/stacks/common/laser_scan/src/scan_shadows_filter.cpp
===================================================================
--- pkg/trunk/stacks/common/laser_scan/src/scan_shadows_filter.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/src/scan_shadows_filter.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -36,7 +36,7 @@
#include <ros/node.h>
#include <robot_msgs/PointCloud.h>
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/LaserScan.h>
#include <float.h>
@@ -72,7 +72,7 @@
// TF
tf::TransformListener* tf_;
- tf::MessageNotifier<laser_scan::LaserScan>* notifier_;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* notifier_;
filters::FilterChain<robot_msgs::PointCloud> filter_chain_;
////////////////////////////////////////////////////////////////////////////////
@@ -91,7 +91,7 @@
ros::Node::instance()->param ("~cloud_topic", cloud_topic_, std::string("tilt_laser_cloud_filtered"));
ros::Node::instance()->param ("~laser_max_range", laser_max_range_, DBL_MAX);
- notifier_ = new tf::MessageNotifier<laser_scan::LaserScan>(tf_, ros::Node::instance(),
+ notifier_ = new tf::MessageNotifier<sensor_msgs::LaserScan>(tf_, ros::Node::instance(),
boost::bind(&ScanShadowsFilter::scanCallback, this, _1), scan_topic_, "base_link", 50);
notifier_->setTolerance(ros::Duration(0.03));
@@ -225,9 +225,9 @@
////////////////////////////////////////////////////////////////////////////////
void
- scanCallback (const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& msg_in)
+ scanCallback (const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& msg_in)
{
- laser_scan::LaserScan& scan_msg = *msg_in;
+ sensor_msgs::LaserScan& scan_msg = *msg_in;
// Project laser into point cloud
PointCloud scan_cloud;
int n_scan = scan_msg.ranges.size (); // Save the number of measurements
Modified: pkg/trunk/stacks/common/laser_scan/src/scan_to_cloud.cpp
===================================================================
--- pkg/trunk/stacks/common/laser_scan/src/scan_to_cloud.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/src/scan_to_cloud.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -36,7 +36,7 @@
#include <ros/node.h>
#include <robot_msgs/PointCloud.h>
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/LaserScan.h>
#include <float.h>
@@ -75,9 +75,9 @@
// TF
tf::TransformListener* tf_;
- tf::MessageNotifier<laser_scan::LaserScan>* notifier_;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* notifier_;
filters::FilterChain<robot_msgs::PointCloud> cloud_filter_chain_;
- filters::FilterChain<laser_scan::LaserScan> scan_filter_chain_;
+ filters::FilterChain<sensor_msgs::LaserScan> scan_filter_chain_;
////////////////////////////////////////////////////////////////////////////////
ScanShadowsFilter () : laser_max_range_ (DBL_MAX), notifier_(NULL)
@@ -95,7 +95,7 @@
ros::Node::instance()->param ("~cloud_topic", cloud_topic_, std::string("tilt_laser_cloud_filtered"));
ros::Node::instance()->param ("~laser_max_range", laser_max_range_, DBL_MAX);
- notifier_ = new tf::MessageNotifier<laser_scan::LaserScan>(tf_, ros::Node::instance(),
+ notifier_ = new tf::MessageNotifier<sensor_msgs::LaserScan>(tf_, ros::Node::instance(),
boost::bind(&ScanShadowsFilter::scanCallback, this, _1), scan_topic_, "base_link", 50);
notifier_->setTolerance(ros::Duration(0.03));
@@ -156,10 +156,10 @@
////////////////////////////////////////////////////////////////////////////////
void
- scanCallback (const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& msg_in)
+ scanCallback (const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& msg_in)
{
- laser_scan::LaserScan& scan_msg = *msg_in;
- laser_scan::LaserScan filtered_scan;
+ sensor_msgs::LaserScan& scan_msg = *msg_in;
+ sensor_msgs::LaserScan filtered_scan;
scan_filter_chain_.update (scan_msg, filtered_scan);
// Project laser into point cloud
Modified: pkg/trunk/stacks/common/laser_scan/test/projection_test.cpp
===================================================================
--- pkg/trunk/stacks/common/laser_scan/test/projection_test.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/common/laser_scan/test/projection_test.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -42,11 +42,11 @@
#define PROJECTION_TEST_RANGE_MIN (0.23)
#define PROJECTION_TEST_RANGE_MAX (40.0)
-laser_scan::LaserScan build_constant_scan(double range, double intensity,
+sensor_msgs::LaserScan build_constant_scan(double range, double intensity,
double ang_min, double ang_max, double ang_increment,
ros::Duration scan_time)
{
- laser_scan::LaserScan scan;
+ sensor_msgs::LaserScan scan;
scan.header.stamp = ros::Time::now();
scan.header.frame_id = "laser_frame";
scan.angle_min = ang_min;
@@ -206,7 +206,7 @@
try
{
//printf("%f %f %f %f %f %f\n", range, intensity, min_angle, max_angle, angle_increment, scan_time.toSec());
- laser_scan::LaserScan scan = build_constant_scan(range, intensity, min_angle, max_angle, angle_increment, scan_time);
+ sensor_msgs::LaserScan scan = build_constant_scan(range, intensity, min_angle, max_angle, angle_increment, scan_time);
robot_msgs::PointCloud cloud_out;
projector.projectLaser(scan, cloud_out, -1.0, false, laser_scan::MASK_INDEX);
@@ -320,7 +320,7 @@
try
{
//printf("%f %f %f %f %f %f\n", range, intensity, min_angle, max_angle, angle_increment, scan_time.toSec());
- laser_scan::LaserScan scan = build_constant_scan(range, intensity, min_angle, max_angle, angle_increment, scan_time);
+ sensor_msgs::LaserScan scan = build_constant_scan(range, intensity, min_angle, max_angle, angle_increment, scan_time);
scan.header.frame_id = "laser_frame";
robot_msgs::PointCloud cloud_out;
Copied: pkg/trunk/stacks/common_msgs/sensor_msgs/msg/LaserScan.msg (from rev 17781, pkg/trunk/stacks/common/laser_scan/msg/LaserScan.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/msg/LaserScan.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/msg/LaserScan.msg 2009-06-30 02:30:45 UTC (rev 17938)
@@ -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]
Property changes on: pkg/trunk/stacks/common_msgs/sensor_msgs/msg/LaserScan.msg
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/laser_scan/msg/LaserScan.msg:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Modified: pkg/trunk/stacks/laser_drivers/hokuyo_node/manifest.xml
===================================================================
--- pkg/trunk/stacks/laser_drivers/hokuyo_node/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/laser_drivers/hokuyo_node/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -6,7 +6,7 @@
<license>LGPL</license>
<review status="API cleared" notes="Tully to code review"/>
<depend package="roscpp" />
- <depend package="laser_scan" />
+ <depend package="sensor_msgs" />
<depend package="self_test" />
<depend package="diagnostic_updater" />
<url>http://pr.willowgarage.com/wiki/Hokuyo_TOP-URG</url>
Modified: pkg/trunk/stacks/laser_drivers/hokuyo_node/src/node/hokuyo_node.cpp
===================================================================
--- pkg/trunk/stacks/laser_drivers/hokuyo_node/src/node/hokuyo_node.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/laser_drivers/hokuyo_node/src/node/hokuyo_node.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -71,7 +71,7 @@
- None
Publishes to (name / type):
-- @b "scan"/<a href="../../laser_scan/html/classstd__msgs_1_1LaserScan.html">laser_scan/LaserScan</a> : scan data from the laser.
+- @b "scan"/<a href="../../sensor_msgs/html/classstd__msgs_1_1LaserScan.html">sensor_msgs/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>
@@ -108,7 +108,7 @@
#include "ros/time.h"
#include "ros/common.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "self_test/self_test.h"
#include "diagnostic_updater/diagnostic_updater.h"
@@ -133,7 +133,7 @@
public:
hokuyo::Laser laser_;
- laser_scan::LaserScan scan_msg_;
+ sensor_msgs::LaserScan scan_msg_;
double min_ang_;
double max_ang_;
@@ -151,7 +151,7 @@
HokuyoNode() : ros::Node("hokuyo"), running_(false), count_(0), self_test_(this), diagnostic_(this)
{
- advertise<laser_scan::LaserScan>("scan", 100);
+ advertise<sensor_msgs::LaserScan>("scan", 100);
read_config();
Modified: pkg/trunk/stacks/laser_drivers/sicktoolbox_wrapper/manifest.xml
===================================================================
--- pkg/trunk/stacks/laser_drivers/sicktoolbox_wrapper/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/laser_drivers/sicktoolbox_wrapper/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -8,5 +8,5 @@
<review status="unreviewed" notes=""/>
<depend package="sicktoolbox"/>
<depend package="roscpp"/>
- <depend package="laser_scan"/>
+ <depend package="sensor_msgs"/>
</package>
Modified: pkg/trunk/stacks/laser_drivers/sicktoolbox_wrapper/ros/sicklms/sicklms.cpp
===================================================================
--- pkg/trunk/stacks/laser_drivers/sicktoolbox_wrapper/ros/sicklms/sicklms.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/stacks/laser_drivers/sicktoolbox_wrapper/ros/sicklms/sicklms.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -33,7 +33,7 @@
#include <cstdio>
#include <sicklms-1.0/SickLMS.hh>
#include "ros/node.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
using namespace SickToolbox;
using namespace std;
@@ -46,7 +46,7 @@
class SickNode : public ros::Node
{
public:
- laser_scan::LaserScan scan_msg;
+ sensor_msgs::LaserScan scan_msg;
int scan_count;
string port;
int baud;
@@ -55,7 +55,7 @@
SickNode() : ros::Node("sicklms"), scan_count(0), last_print_time(0)
{
scan_msg.header.frame_id = "base_laser";
- advertise<laser_scan::LaserScan>("scan", 1...
[truncated message content] |