|
From: <tf...@us...> - 2009-06-30 01:00:42
|
Revision: 17929
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17929&view=rev
Author: tfoote
Date: 2009-06-30 00:56:54 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
moving StaticMap from robot_srvs to nav_srvs #1707
Modified Paths:
--------------
pkg/trunk/nav/amcl/manifest.xml
pkg/trunk/nav/amcl/src/amcl_node.cpp
pkg/trunk/nav/map_server/include/map_server/image_loader.h
pkg/trunk/nav/map_server/manifest.xml
pkg/trunk/nav/map_server/src/image_loader.cpp
pkg/trunk/nav/map_server/src/main.cpp
pkg/trunk/nav/map_server/src/map_saver.cpp
pkg/trunk/nav/map_server/test/consumer.py
pkg/trunk/nav/map_server/test/rtest.cpp
pkg/trunk/nav/map_server/test/utest.cpp
pkg/trunk/nav/nav_view/manifest.xml
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h
pkg/trunk/nav/wavefront/manifest.xml
pkg/trunk/nav/wavefront/src/wavefront_node.cpp
pkg/trunk/stacks/common/nav_srvs/manifest.xml
pkg/trunk/stacks/visualization/rviz/manifest.xml
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.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
Added Paths:
-----------
pkg/trunk/stacks/common/nav_srvs/srv/StaticMap.srv
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv
Modified: pkg/trunk/nav/amcl/manifest.xml
===================================================================
--- pkg/trunk/nav/amcl/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/amcl/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -10,6 +10,7 @@
<depend package="robot_srvs" />
<depend package="robot_msgs" />
<depend package="nav_msgs" />
+ <depend package="nav_srvs" />
<depend package="std_srvs" />
<depend package="laser_scan" />
<depend package="visualization_msgs"/>
Modified: pkg/trunk/nav/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -160,7 +160,7 @@
#include "robot_msgs/PoseWithCovariance.h"
#include "nav_msgs/ParticleCloud.h"
#include "robot_msgs/Pose.h"
-#include "robot_srvs/StaticMap.h"
+#include "nav_srvs/StaticMap.h"
#include "std_srvs/Empty.h"
#include "visualization_msgs/Polyline.h"
@@ -462,8 +462,8 @@
ROS_ASSERT(map);
// get map via RPC
- robot_srvs::StaticMap::Request req;
- robot_srvs::StaticMap::Response resp;
+ nav_srvs::StaticMap::Request req;
+ nav_srvs::StaticMap::Response resp;
ROS_INFO("Requesting the map...");
while(!ros::service::call("static_map", req, resp))
{
Modified: pkg/trunk/nav/map_server/include/map_server/image_loader.h
===================================================================
--- pkg/trunk/nav/map_server/include/map_server/image_loader.h 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/include/map_server/image_loader.h 2009-06-30 00:56:54 UTC (rev 17929)
@@ -33,7 +33,7 @@
* Author: Brian Gerkey
*/
-#include "robot_srvs/StaticMap.h"
+#include "nav_srvs/StaticMap.h"
namespace map_server
{
@@ -51,7 +51,7 @@
*
* @throws std::runtime_error If the image file can't be loaded
* */
-void loadMapFromFile(robot_srvs::StaticMap::Response* resp,
+void loadMapFromFile(nav_srvs::StaticMap::Response* resp,
const char* fname, double res, bool negate,
double occ_th, double free_th);
}
Modified: pkg/trunk/nav/map_server/manifest.xml
===================================================================
--- pkg/trunk/nav/map_server/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -11,7 +11,7 @@
<depend package="rosconsole"/>
<depend package="roscpp"/>
<depend package="rospy" />
- <depend package="robot_srvs"/>
+ <depend package="nav_srvs"/>
<depend package="bullet"/>
<export>
<cpp cflags="-I${prefix}/include `rosboost-cfg --cflags`" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib `rosboost-cfg --lflags thread`"/>
Modified: pkg/trunk/nav/map_server/src/image_loader.cpp
===================================================================
--- pkg/trunk/nav/map_server/src/image_loader.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/src/image_loader.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -51,7 +51,7 @@
{
void
-loadMapFromFile(robot_srvs::StaticMap::Response* resp,
+loadMapFromFile(nav_srvs::StaticMap::Response* resp,
const char* fname, double res, bool negate,
double occ_th, double free_th)
{
Modified: pkg/trunk/nav/map_server/src/main.cpp
===================================================================
--- pkg/trunk/nav/map_server/src/main.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/src/main.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -70,7 +70,7 @@
@section services ROS services
Offers (name/type):
-- @b "static_map"/robot_srvs::StaticMap : Retrieve the map via this service
+- @b "static_map"/nav_srvs::StaticMap : Retrieve the map via this service
@section parameters ROS parameters
@@ -144,8 +144,8 @@
ros::ServiceServer service;
/** Callback invoked when someone requests our service */
- bool mapCallback(robot_srvs::StaticMap::Request &req,
- robot_srvs::StaticMap::Response &res )
+ bool mapCallback(nav_srvs::StaticMap::Request &req,
+ nav_srvs::StaticMap::Response &res )
{
// request is empty; we ignore it
@@ -157,7 +157,7 @@
/** The map response is cached here, to be sent out to service callers
*/
- robot_srvs::StaticMap::Response map_resp_;
+ nav_srvs::StaticMap::Response map_resp_;
void metadataSubscriptionCallback(const ros::SingleSubscriberPublisher& pub)
{
Modified: pkg/trunk/nav/map_server/src/map_saver.cpp
===================================================================
--- pkg/trunk/nav/map_server/src/map_saver.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/src/map_saver.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -57,14 +57,14 @@
@section topic ROS services
Uses (name type):
-- @b static_map robot_srvs/StaticMap : map service.
+- @b static_map nav_srvs/StaticMap : map service.
**/
#include <cstdio>
#include "ros/node.h"
#include "ros/console.h"
-#include "robot_srvs/StaticMap.h"
+#include "nav_srvs/StaticMap.h"
#include "LinearMath/btMatrix3x3.h"
using namespace std;
@@ -84,8 +84,8 @@
ros::Node n("map_generator");
const static std::string servname = "static_map";
ROS_INFO("Requesting the map from %s...", n.mapName(servname).c_str());
- robot_srvs::StaticMap::Request req;
- robot_srvs::StaticMap::Response resp;
+ nav_srvs::StaticMap::Request req;
+ nav_srvs::StaticMap::Response resp;
while(n.ok() && !ros::service::call(servname, req, resp))
{
ROS_WARN("request to %s failed; trying again...", n.mapName(servname).c_str());
Modified: pkg/trunk/nav/map_server/test/consumer.py
===================================================================
--- pkg/trunk/nav/map_server/test/consumer.py 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/test/consumer.py 2009-06-30 00:56:54 UTC (rev 17929)
@@ -41,7 +41,7 @@
import sys, unittest, time
import rospy, rostest
-from robot_srvs.srv import *
+from nav_srvs.srv import StaticMap
class TestConsumer(unittest.TestCase):
def __init__(self, *args):
Modified: pkg/trunk/nav/map_server/test/rtest.cpp
===================================================================
--- pkg/trunk/nav/map_server/test/rtest.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/test/rtest.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -32,7 +32,7 @@
#include <gtest/gtest.h>
#include <ros/service.h>
#include <ros/node.h>
-#include <robot_srvs/StaticMap.h>
+#include <nav_srvs/StaticMap.h>
#include "test_constants.h"
@@ -65,8 +65,8 @@
{
try
{
- robot_srvs::StaticMap::Request req;
- robot_srvs::StaticMap::Response resp;
+ nav_srvs::StaticMap::Request req;
+ nav_srvs::StaticMap::Response resp;
// Try a few times, because the server may not be up yet.
int i=10;
bool call_result;
Modified: pkg/trunk/nav/map_server/test/utest.cpp
===================================================================
--- pkg/trunk/nav/map_server/test/utest.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/test/utest.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -43,7 +43,7 @@
{
try
{
- robot_srvs::StaticMap::Response map_resp;
+ nav_srvs::StaticMap::Response map_resp;
map_server::loadMapFromFile(&map_resp, g_valid_png_file, g_valid_image_res, false, 0.65, 0.1);
EXPECT_FLOAT_EQ(map_resp.map.info.resolution, g_valid_image_res);
EXPECT_EQ(map_resp.map.info.width, g_valid_image_width);
@@ -63,7 +63,7 @@
{
try
{
- robot_srvs::StaticMap::Response map_resp;
+ nav_srvs::StaticMap::Response map_resp;
map_server::loadMapFromFile(&map_resp, g_valid_bmp_file, g_valid_image_res, false, 0.65, 0.1);
EXPECT_FLOAT_EQ(map_resp.map.info.resolution, g_valid_image_res);
EXPECT_EQ(map_resp.map.info.width, g_valid_image_width);
@@ -83,7 +83,7 @@
{
try
{
- robot_srvs::StaticMap::Response map_resp;
+ nav_srvs::StaticMap::Response map_resp;
map_server::loadMapFromFile(&map_resp, "foo", 0.1, false, 0.65, 0.1);
}
catch(std::runtime_error &e)
Modified: pkg/trunk/nav/nav_view/manifest.xml
===================================================================
--- pkg/trunk/nav/nav_view/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/nav_view/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -4,7 +4,9 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="roscpp"/>
+ <depend package="nav_srvs"/>
<depend package="robot_srvs"/>
+ <depend package="nav_msgs"/>
<depend package="tf"/>
<depend package="ogre"/>
<depend package="ogre_tools"/>
Modified: pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
===================================================================
--- pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -31,7 +31,7 @@
#include "ogre_tools/wx_ogre_render_window.h"
-#include "robot_srvs/StaticMap.h"
+#include "nav_srvs/StaticMap.h"
#include "ros/common.h"
#include "ros/node.h"
@@ -199,8 +199,8 @@
void NavViewPanel::loadMap()
{
- robot_srvs::StaticMap::Request req;
- robot_srvs::StaticMap::Response resp;
+ nav_srvs::StaticMap::Request req;
+ nav_srvs::StaticMap::Response resp;
printf("Requesting the map...\n");
if( !ros::service::call("/static_map", req, resp) )
{
Modified: pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h
===================================================================
--- pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h 2009-06-30 00:56:54 UTC (rev 17929)
@@ -32,7 +32,7 @@
#include "nav_view_panel_generated.h"
-#include "robot_msgs/ParticleCloud.h"
+#include "nav_msgs/ParticleCloud.h"
#include "robot_msgs/PoseStamped.h"
#include "visualization_msgs/Polyline.h"
#include "robot_msgs/PoseWithCovariance.h"
@@ -205,7 +205,7 @@
int map_height_;
Ogre::TexturePtr map_texture_;
- robot_msgs::ParticleCloud cloud_;
+ nav_msgs::ParticleCloud cloud_;
robot_msgs::PoseStamped goal_;
visualization_msgs::Polyline path_line_;
visualization_msgs::Polyline local_path_;
Modified: pkg/trunk/nav/wavefront/manifest.xml
===================================================================
--- pkg/trunk/nav/wavefront/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/wavefront/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -5,7 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp" />
<depend package="laser_scan" />
- <depend package="robot_srvs" />
+ <depend package="nav_srvs" />
<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 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -106,7 +106,7 @@
#include <robot_msgs/PoseDot.h>
#include <robot_msgs/PointCloud.h>
#include <laser_scan/LaserScan.h>
-#include <robot_srvs/StaticMap.h>
+#include <nav_srvs/StaticMap.h>
// For GUI debug
#include <visualization_msgs/Polyline.h>
@@ -295,8 +295,8 @@
gui_publish_rate = ros::Duration(1.0/tmp);
// get map via RPC
- robot_srvs::StaticMap::Request req;
- robot_srvs::StaticMap::Response resp;
+ nav_srvs::StaticMap::Request req;
+ nav_srvs::StaticMap::Response resp;
puts("Requesting the map...");
while(!ros::service::call("/static_map", req, resp))
{
Modified: pkg/trunk/stacks/common/nav_srvs/manifest.xml
===================================================================
--- pkg/trunk/stacks/common/nav_srvs/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/common/nav_srvs/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -5,6 +5,7 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="robot_msgs"/>
+ <depend package="nav_msgs"/>
<export>
<cpp cflags="-I${prefix}/srv/cpp"/>
</export>
Copied: pkg/trunk/stacks/common/nav_srvs/srv/StaticMap.srv (from rev 17919, pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv)
===================================================================
--- pkg/trunk/stacks/common/nav_srvs/srv/StaticMap.srv (rev 0)
+++ pkg/trunk/stacks/common/nav_srvs/srv/StaticMap.srv 2009-06-30 00:56:54 UTC (rev 17929)
@@ -0,0 +1,2 @@
+---
+nav_msgs/OccGrid map
Property changes on: pkg/trunk/stacks/common/nav_srvs/srv/StaticMap.srv
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/robot_srvs/srv/StaticMap.srv:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Deleted: pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv 2009-06-30 00:56:54 UTC (rev 17929)
@@ -1,2 +0,0 @@
----
-nav_msgs/OccGrid map
Modified: pkg/trunk/stacks/visualization/rviz/manifest.xml
===================================================================
--- pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -15,6 +15,7 @@
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
<depend package="nav_msgs"/>
+ <depend package="nav_srvs"/>
<depend package="mechanism_msgs" />
<depend package="deprecated_msgs"/>
<depend package="tf"/>
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -190,7 +190,7 @@
{
if (!loaded_ || reload_)
{
- robot_srvs::StaticMap srv;
+ nav_srvs::StaticMap srv;
ROS_DEBUG("Requesting the map...");
if( !ros::service::call(service_, srv) )
{
@@ -444,7 +444,7 @@
const char* MapDisplay::getDescription()
{
- return "Displays an image of a map gotten through a robot_srvs::StaticMap service.";
+ return "Displays an image of a map gotten through a nav_srvs::StaticMap service.";
}
} // namespace rviz
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h 2009-06-30 00:56:54 UTC (rev 17929)
@@ -44,7 +44,7 @@
#include <boost/thread/thread.hpp>
#include <boost/thread/mutex.hpp>
-#include <robot_srvs/StaticMap.h>
+#include <nav_srvs/StaticMap.h>
namespace Ogre
{
@@ -131,7 +131,7 @@
ros::Time last_loaded_map_time_;
boost::thread request_thread_;
- robot_srvs::StaticMap map_srv_;
+ nav_srvs::StaticMap map_srv_;
bool new_map_;
boost::mutex map_mutex_;
bool reload_;
Modified: pkg/trunk/stacks/world_models/costmap_2d/manifest.xml
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/world_models/costmap_2d/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -10,7 +10,7 @@
<depend package="laser_scan" />
<depend package="tf" />
<depend package="voxel_grid" />
-<depend package="robot_srvs" />
+<depend package="nav_srvs" />
<depend package="visualization_msgs" />
<export>
<cpp cflags="-I${prefix}/include -I${prefix}/msg/cpp `rosboost-cfg --cflags`" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib `rosboost-cfg --lflags thread` -lcostmap_2d"/>
Modified: pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -36,7 +36,7 @@
*********************************************************************/
#include <costmap_2d/costmap_2d_ros.h>
-#include <robot_srvs/StaticMap.h>
+#include <nav_srvs/StaticMap.h>
namespace costmap_2d {
@@ -155,8 +155,8 @@
map_height = (unsigned int)(map_height_meters / map_resolution);
if(static_map){
- robot_srvs::StaticMap::Request map_req;
- robot_srvs::StaticMap::Response map_resp;
+ nav_srvs::StaticMap::Request map_req;
+ nav_srvs::StaticMap::Response map_resp;
ROS_INFO("Requesting the map...\n");
while(!ros::service::call("/static_map", map_req, map_resp))
{
Modified: pkg/trunk/stacks/world_models/costmap_2d/src/costmap_test.cpp
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/src/costmap_test.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/world_models/costmap_2d/src/costmap_test.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -38,7 +38,7 @@
#include <ros/console.h>
#include <new_costmap/costmap_2d.h>
#include <new_costmap/observation_buffer.h>
-#include <robot_srvs/StaticMap.h>
+#include <nav_srvs/StaticMap.h>
#include <visualization_msgs/Polyline.h>
#include <map>
#include <vector>
@@ -71,8 +71,8 @@
boost::bind(&CostmapTester::baseScanCallback, this, _1, (int) 1),
"base_scan", global_frame_, 50);
- robot_srvs::StaticMap::Request map_req;
- robot_srvs::StaticMap::Response map_resp;
+ nav_srvs::StaticMap::Request map_req;
+ nav_srvs::StaticMap::Response map_resp;
ROS_INFO("Requesting the map...\n");
while(!ros::service::call("static_map", map_req, map_resp))
{
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|