|
From: <ei...@us...> - 2009-07-30 18:57:20
|
Revision: 20170
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20170&view=rev
Author: eitanme
Date: 2009-07-30 18:57:04 +0000 (Thu, 30 Jul 2009)
Log Message:
-----------
Moving StaticMap.srv to GetMap.srv and moving Plan.srv to GetPlan.srv, also moving them to nav_msgs and removing the nav_srvs package
Modified Paths:
--------------
pkg/trunk/highlevel/doors/doors_core/include/doors_core/action_check_path.h
pkg/trunk/highlevel/doors/doors_core/manifest.xml
pkg/trunk/nav/people_aware_nav/include/people_aware_nav/move_base_constrained.h
pkg/trunk/nav/people_aware_nav/manifest.xml
pkg/trunk/nav/wavefront/manifest.xml
pkg/trunk/nav/wavefront/src/wavefront_node.cpp
pkg/trunk/sandbox/webteleop/manifest.xml
pkg/trunk/sandbox/webteleop/src/server.py
pkg/trunk/stacks/common_msgs/nav_msgs/CMakeLists.txt
pkg/trunk/stacks/common_msgs/nav_msgs/manifest.xml
pkg/trunk/stacks/map_building/slam_gmapping/manifest.xml
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/nav/amcl/manifest.xml
pkg/trunk/stacks/nav/amcl/src/amcl_node.cpp
pkg/trunk/stacks/nav/costmap_2d/manifest.xml
pkg/trunk/stacks/nav/costmap_2d/src/costmap_2d_ros.cpp
pkg/trunk/stacks/nav/costmap_2d/src/costmap_test.cpp
pkg/trunk/stacks/nav/map_server/include/map_server/image_loader.h
pkg/trunk/stacks/nav/map_server/manifest.xml
pkg/trunk/stacks/nav/map_server/src/image_loader.cpp
pkg/trunk/stacks/nav/map_server/src/main.cpp
pkg/trunk/stacks/nav/map_server/src/map_saver.cpp
pkg/trunk/stacks/nav/map_server/test/consumer.py
pkg/trunk/stacks/nav/map_server/test/rtest.cpp
pkg/trunk/stacks/nav/map_server/test/utest.cpp
pkg/trunk/stacks/nav/move_base/include/move_base/move_base.h
pkg/trunk/stacks/nav/move_base/include/move_base/move_base_old.h
pkg/trunk/stacks/nav/move_base/manifest.xml
pkg/trunk/stacks/nav/move_base/src/move_base.cpp
pkg/trunk/stacks/nav/move_base/src/move_base_old.cpp
pkg/trunk/stacks/nav/nav_view/manifest.xml
pkg/trunk/stacks/nav/nav_view/src/nav_view/nav_view_panel.cpp
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
Removed Paths:
-------------
pkg/trunk/stacks/common/nav_srvs/
Modified: pkg/trunk/highlevel/doors/doors_core/include/doors_core/action_check_path.h
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/include/doors_core/action_check_path.h 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/highlevel/doors/doors_core/include/doors_core/action_check_path.h 2009-07-30 18:57:04 UTC (rev 20170)
@@ -42,7 +42,7 @@
#include <ros/node.h>
#include <tf/tf.h>
#include <tf/transform_listener.h>
-#include <nav_srvs/Plan.h>
+#include <nav_msgs/GetPlan.h>
#include <robot_actions/action.h>
namespace door_handle_detector{
@@ -60,8 +60,8 @@
private:
tf::TransformListener& tf_;
- nav_srvs::Plan::Request req_plan;
- nav_srvs::Plan::Response res_plan;
+ nav_msgs::GetPlan::Request req_plan;
+ nav_msgs::GetPlan::Response res_plan;
};
}
Modified: pkg/trunk/highlevel/doors/doors_core/manifest.xml
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/highlevel/doors/doors_core/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -19,7 +19,7 @@
<depend package="robot_srvs" />
<depend package="deprecated_srvs" />
- <depend package="nav_srvs" />
+ <depend package="nav_msgs" />
<depend package="robot_actions" />
<depend package="nav_robot_actions" />
Modified: pkg/trunk/nav/people_aware_nav/include/people_aware_nav/move_base_constrained.h
===================================================================
--- pkg/trunk/nav/people_aware_nav/include/people_aware_nav/move_base_constrained.h 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/nav/people_aware_nav/include/people_aware_nav/move_base_constrained.h 2009-07-30 18:57:04 UTC (rev 20170)
@@ -49,7 +49,7 @@
#include <base_local_planner/trajectory_planner_ros.h>
#include <vector>
#include <string>
-#include <nav_srvs/Plan.h>
+#include <nav_msgs/GetPlan.h>
namespace people_aware_nav {
/**
@@ -86,7 +86,7 @@
* @param resp The plan request
* @return True if planning succeeded, false otherwise
*/
- bool planService(nav_srvs::Plan::Request &req, nav_srvs::Plan::Response &resp);
+ bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp);
/**
* @brief Make a new global plan
Modified: pkg/trunk/nav/people_aware_nav/manifest.xml
===================================================================
--- pkg/trunk/nav/people_aware_nav/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/nav/people_aware_nav/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -14,7 +14,7 @@
<depend package="costmap_2d"/>
<depend package="angles"/>
<depend package="navfn"/>
-<depend package="nav_srvs"/>
+<depend package="nav_msgs"/>
<depend package="robot_msgs" />
<depend package="robot_actions" />
<depend package="deprecated_msgs" />
Modified: pkg/trunk/nav/wavefront/manifest.xml
===================================================================
--- pkg/trunk/nav/wavefront/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/nav/wavefront/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -5,7 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp" />
<depend package="laser_scan" />
- <depend package="nav_srvs" />
+ <depend package="nav_msgs" />
<depend package="sensor_msgs" />
<depend package="robot_msgs" />
<depend package="robot_actions" />
Modified: pkg/trunk/nav/wavefront/src/wavefront_node.cpp
===================================================================
--- pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -106,7 +106,7 @@
#include <robot_msgs/PoseDot.h>
#include <robot_msgs/PointCloud.h>
#include <sensor_msgs/LaserScan.h>
-#include <nav_srvs/StaticMap.h>
+#include <nav_msgs/GetMap.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
- nav_srvs::StaticMap::Request req;
- nav_srvs::StaticMap::Response resp;
+ nav_msgs::GetMap::Request req;
+ nav_msgs::GetMap::Response resp;
puts("Requesting the map...");
while(!ros::service::call("/static_map", req, resp))
{
Modified: pkg/trunk/sandbox/webteleop/manifest.xml
===================================================================
--- pkg/trunk/sandbox/webteleop/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/sandbox/webteleop/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -11,7 +11,6 @@
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
<depend package="robot_srvs"/>
- <depend package="nav_srvs"/>
<depend package="nav_msgs"/>
<depend package="bullet_python"/>
<depend package="tf"/>
Modified: pkg/trunk/sandbox/webteleop/src/server.py
===================================================================
--- pkg/trunk/sandbox/webteleop/src/server.py 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/sandbox/webteleop/src/server.py 2009-07-30 18:57:04 UTC (rev 20170)
@@ -22,7 +22,7 @@
import bullet
from tf.msg import tfMessage
-from nav_srvs.srv import *
+from nav_msgs.srv import *
from nav_msgs.msg import *
from std_msgs.msg import *
from robot_msgs.msg import *
@@ -314,7 +314,7 @@
data = ''
try:
#staticMap = rospy.ServiceProxy(topic, service_class)
- #staticMap = rospy.ServiceProxy('/static_map', StaticMap)
+ #staticMap = rospy.ServiceProxy('/static_map', GetMap)
map = service_proxy()
mapW = map.map.info.width
Modified: pkg/trunk/stacks/common_msgs/nav_msgs/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/CMakeLists.txt 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/CMakeLists.txt 2009-07-30 18:57:04 UTC (rev 20170)
@@ -19,7 +19,7 @@
#uncomment if you have defined messages
genmsg()
#uncomment if you have defined services
-#gensrv()
+gensrv()
#common commands for building c++ executables and libraries
#rospack_add_library(${PROJECT_NAME} src/example.cpp)
Modified: pkg/trunk/stacks/common_msgs/nav_msgs/manifest.xml
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -10,7 +10,7 @@
<url>http://pr.willowgarage.com/wiki/nav_msgs</url>
<depend package="robot_msgs"/>
<export>
- <cpp cflags="-I${prefix}/msg/cpp"/>
+ <cpp cflags="-I${prefix}/msg/cpp -I${prefix}/srv/cpp"/>
</export>
</package>
Modified: pkg/trunk/stacks/map_building/slam_gmapping/manifest.xml
===================================================================
--- pkg/trunk/stacks/map_building/slam_gmapping/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/map_building/slam_gmapping/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -7,7 +7,7 @@
<depend package="rosconsole"/>
<depend package="std_msgs"/>
<depend package="laser_scan"/>
- <depend package="nav_srvs"/>
+ <depend package="nav_msgs"/>
<depend package="gmapping"/>
<depend package="tf"/>
</package>
Modified: pkg/trunk/stacks/map_building/slam_gmapping/src/slam_gmapping.cpp
===================================================================
--- pkg/trunk/stacks/map_building/slam_gmapping/src/slam_gmapping.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/map_building/slam_gmapping/src/slam_gmapping.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -452,8 +452,8 @@
}
bool
-SlamGMapping::map_cb(nav_srvs::StaticMap::Request &req,
- nav_srvs::StaticMap::Response &res)
+SlamGMapping::map_cb(nav_msgs::GetMap::Request &req,
+ nav_msgs::GetMap::Response &res)
{
if(got_map_ && map_.map.info.width && map_.map.info.height)
{
Modified: pkg/trunk/stacks/map_building/slam_gmapping/src/slam_gmapping.h
===================================================================
--- pkg/trunk/stacks/map_building/slam_gmapping/src/slam_gmapping.h 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/map_building/slam_gmapping/src/slam_gmapping.h 2009-07-30 18:57:04 UTC (rev 20170)
@@ -31,7 +31,7 @@
#include "ros/node.h"
#include "sensor_msgs/LaserScan.h"
-#include "nav_srvs/StaticMap.h"
+#include "nav_msgs/GetMap.h"
#include "tf/transform_listener.h"
#include "tf/transform_broadcaster.h"
#include <tf/message_notifier.h>
@@ -48,8 +48,8 @@
void main_loop();
void laser_cb(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& message);
- bool map_cb(nav_srvs::StaticMap::Request &req,
- nav_srvs::StaticMap::Response &res);
+ bool map_cb(nav_msgs::GetMap::Request &req,
+ nav_msgs::GetMap::Response &res);
private:
ros::Node* node_;
@@ -65,7 +65,7 @@
bool got_first_scan_;
bool got_map_;
- nav_srvs::StaticMap::Response map_;
+ nav_msgs::GetMap::Response map_;
ros::Duration map_update_interval_;
tf::Transform map_to_odom_;
Modified: pkg/trunk/stacks/nav/amcl/manifest.xml
===================================================================
--- pkg/trunk/stacks/nav/amcl/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/amcl/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -10,7 +10,6 @@
<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/stacks/nav/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/stacks/nav/amcl/src/amcl_node.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/amcl/src/amcl_node.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -160,7 +160,7 @@
#include "robot_msgs/PoseWithCovariance.h"
#include "nav_msgs/PoseArray.h"
#include "robot_msgs/Pose.h"
-#include "nav_srvs/StaticMap.h"
+#include "nav_msgs/GetMap.h"
#include "std_srvs/Empty.h"
#include "visualization_msgs/Polyline.h"
@@ -462,8 +462,8 @@
ROS_ASSERT(map);
// get map via RPC
- nav_srvs::StaticMap::Request req;
- nav_srvs::StaticMap::Response resp;
+ nav_msgs::GetMap::Request req;
+ nav_msgs::GetMap::Response resp;
ROS_INFO("Requesting the map...");
while(!ros::service::call("static_map", req, resp))
{
Modified: pkg/trunk/stacks/nav/costmap_2d/manifest.xml
===================================================================
--- pkg/trunk/stacks/nav/costmap_2d/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/costmap_2d/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -20,7 +20,7 @@
<depend package="laser_scan" />
<depend package="tf" />
<depend package="voxel_grid" />
-<depend package="nav_srvs" />
+<depend package="nav_msgs" />
<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/nav/costmap_2d/src/costmap_2d_ros.cpp
===================================================================
--- pkg/trunk/stacks/nav/costmap_2d/src/costmap_2d_ros.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/costmap_2d/src/costmap_2d_ros.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -36,7 +36,7 @@
*********************************************************************/
#include <costmap_2d/costmap_2d_ros.h>
-#include <nav_srvs/StaticMap.h>
+#include <nav_msgs/GetMap.h>
namespace costmap_2d {
@@ -155,8 +155,8 @@
map_height = (unsigned int)(map_height_meters / map_resolution);
if(static_map){
- nav_srvs::StaticMap::Request map_req;
- nav_srvs::StaticMap::Response map_resp;
+ nav_msgs::GetMap::Request map_req;
+ nav_msgs::GetMap::Response map_resp;
ROS_INFO("Requesting the map...\n");
while(!ros::service::call("/static_map", map_req, map_resp))
{
Modified: pkg/trunk/stacks/nav/costmap_2d/src/costmap_test.cpp
===================================================================
--- pkg/trunk/stacks/nav/costmap_2d/src/costmap_test.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/costmap_2d/src/costmap_test.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -38,7 +38,7 @@
#include <ros/console.h>
#include <new_costmap/costmap_2d.h>
#include <new_costmap/observation_buffer.h>
-#include <nav_srvs/StaticMap.h>
+#include <nav_msgs/GetMap.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);
- nav_srvs::StaticMap::Request map_req;
- nav_srvs::StaticMap::Response map_resp;
+ nav_msgs::GetMap::Request map_req;
+ nav_msgs::GetMap::Response map_resp;
ROS_INFO("Requesting the map...\n");
while(!ros::service::call("static_map", map_req, map_resp))
{
Modified: pkg/trunk/stacks/nav/map_server/include/map_server/image_loader.h
===================================================================
--- pkg/trunk/stacks/nav/map_server/include/map_server/image_loader.h 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/map_server/include/map_server/image_loader.h 2009-07-30 18:57:04 UTC (rev 20170)
@@ -33,7 +33,7 @@
* Author: Brian Gerkey
*/
-#include "nav_srvs/StaticMap.h"
+#include "nav_msgs/GetMap.h"
namespace map_server
{
@@ -51,7 +51,7 @@
*
* @throws std::runtime_error If the image file can't be loaded
* */
-void loadMapFromFile(nav_srvs::StaticMap::Response* resp,
+void loadMapFromFile(nav_msgs::GetMap::Response* resp,
const char* fname, double res, bool negate,
double occ_th, double free_th);
}
Modified: pkg/trunk/stacks/nav/map_server/manifest.xml
===================================================================
--- pkg/trunk/stacks/nav/map_server/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/map_server/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -11,7 +11,7 @@
<depend package="rosconsole"/>
<depend package="roscpp"/>
<depend package="rospy" />
- <depend package="nav_srvs"/>
+ <depend package="nav_msgs"/>
<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/stacks/nav/map_server/src/image_loader.cpp
===================================================================
--- pkg/trunk/stacks/nav/map_server/src/image_loader.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/map_server/src/image_loader.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -51,7 +51,7 @@
{
void
-loadMapFromFile(nav_srvs::StaticMap::Response* resp,
+loadMapFromFile(nav_msgs::GetMap::Response* resp,
const char* fname, double res, bool negate,
double occ_th, double free_th)
{
Modified: pkg/trunk/stacks/nav/map_server/src/main.cpp
===================================================================
--- pkg/trunk/stacks/nav/map_server/src/main.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/map_server/src/main.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -70,7 +70,7 @@
@section services ROS services
Offers (name/type):
-- @b "static_map"/nav_srvs::StaticMap : Retrieve the map via this service
+- @b "static_map"/nav_msgs::GetMap : 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(nav_srvs::StaticMap::Request &req,
- nav_srvs::StaticMap::Response &res )
+ bool mapCallback(nav_msgs::GetMap::Request &req,
+ nav_msgs::GetMap::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
*/
- nav_srvs::StaticMap::Response map_resp_;
+ nav_msgs::GetMap::Response map_resp_;
void metadataSubscriptionCallback(const ros::SingleSubscriberPublisher& pub)
{
Modified: pkg/trunk/stacks/nav/map_server/src/map_saver.cpp
===================================================================
--- pkg/trunk/stacks/nav/map_server/src/map_saver.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/map_server/src/map_saver.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -57,14 +57,14 @@
@section topic ROS services
Uses (name type):
-- @b static_map nav_srvs/StaticMap : map service.
+- @b static_map nav_msgs/GetMap : map service.
**/
#include <cstdio>
#include "ros/node.h"
#include "ros/console.h"
-#include "nav_srvs/StaticMap.h"
+#include "nav_msgs/GetMap.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());
- nav_srvs::StaticMap::Request req;
- nav_srvs::StaticMap::Response resp;
+ nav_msgs::GetMap::Request req;
+ nav_msgs::GetMap::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/stacks/nav/map_server/test/consumer.py
===================================================================
--- pkg/trunk/stacks/nav/map_server/test/consumer.py 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/map_server/test/consumer.py 2009-07-30 18:57:04 UTC (rev 20170)
@@ -41,7 +41,7 @@
import sys, unittest, time
import rospy, rostest
-from nav_srvs.srv import StaticMap
+from nav_msgs.srv import GetMap
class TestConsumer(unittest.TestCase):
def __init__(self, *args):
@@ -55,7 +55,7 @@
def test_consumer(self):
rospy.wait_for_service('static_map')
- mapsrv = rospy.ServiceProxy('static_map', StaticMap)
+ mapsrv = rospy.ServiceProxy('static_map', GetMap)
resp = mapsrv()
self.success = True
print resp
Modified: pkg/trunk/stacks/nav/map_server/test/rtest.cpp
===================================================================
--- pkg/trunk/stacks/nav/map_server/test/rtest.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/map_server/test/rtest.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -32,7 +32,7 @@
#include <gtest/gtest.h>
#include <ros/service.h>
#include <ros/node.h>
-#include <nav_srvs/StaticMap.h>
+#include <nav_msgs/GetMap.h>
#include "test_constants.h"
@@ -65,8 +65,8 @@
{
try
{
- nav_srvs::StaticMap::Request req;
- nav_srvs::StaticMap::Response resp;
+ nav_msgs::GetMap::Request req;
+ nav_msgs::GetMap::Response resp;
// Try a few times, because the server may not be up yet.
int i=10;
bool call_result;
Modified: pkg/trunk/stacks/nav/map_server/test/utest.cpp
===================================================================
--- pkg/trunk/stacks/nav/map_server/test/utest.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/map_server/test/utest.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -43,7 +43,7 @@
{
try
{
- nav_srvs::StaticMap::Response map_resp;
+ nav_msgs::GetMap::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
{
- nav_srvs::StaticMap::Response map_resp;
+ nav_msgs::GetMap::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
{
- nav_srvs::StaticMap::Response map_resp;
+ nav_msgs::GetMap::Response map_resp;
map_server::loadMapFromFile(&map_resp, "foo", 0.1, false, 0.65, 0.1);
}
catch(std::runtime_error &e)
Modified: pkg/trunk/stacks/nav/move_base/include/move_base/move_base.h
===================================================================
--- pkg/trunk/stacks/nav/move_base/include/move_base/move_base.h 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/move_base/include/move_base/move_base.h 2009-07-30 18:57:04 UTC (rev 20170)
@@ -48,7 +48,7 @@
#include <costmap_2d/costmap_2d.h>
#include <vector>
#include <string>
-#include <nav_srvs/Plan.h>
+#include <nav_msgs/GetPlan.h>
#include <visualization_msgs/Marker.h>
#include <robot_msgs/PoseDot.h>
@@ -109,7 +109,7 @@
* @param resp The plan request
* @return True if planning succeeded, false otherwise
*/
- bool planService(nav_srvs::Plan::Request &req, nav_srvs::Plan::Response &resp);
+ bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp);
/**
* @brief Make a new global plan
Modified: pkg/trunk/stacks/nav/move_base/include/move_base/move_base_old.h
===================================================================
--- pkg/trunk/stacks/nav/move_base/include/move_base/move_base_old.h 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/move_base/include/move_base/move_base_old.h 2009-07-30 18:57:04 UTC (rev 20170)
@@ -48,7 +48,7 @@
#include <costmap_2d/rate.h>
#include <vector>
#include <string>
-#include <nav_srvs/Plan.h>
+#include <nav_msgs/GetPlan.h>
#include <visualization_msgs/Marker.h>
#include <robot_msgs/PoseDot.h>
@@ -99,7 +99,7 @@
* @param resp The plan request
* @return True if planning succeeded, false otherwise
*/
- bool planService(nav_srvs::Plan::Request &req, nav_srvs::Plan::Response &resp);
+ bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp);
/**
* @brief Make a new global plan
Modified: pkg/trunk/stacks/nav/move_base/manifest.xml
===================================================================
--- pkg/trunk/stacks/nav/move_base/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/move_base/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -19,7 +19,7 @@
<depend package="costmap_2d"/>
<depend package="tf"/>
<depend package="roslib"/>
- <depend package="nav_srvs"/>
+ <depend package="nav_msgs"/>
<!--These deps should go away once the plugin model is implemented -->
<depend package="base_local_planner"/>
Modified: pkg/trunk/stacks/nav/move_base/src/move_base.cpp
===================================================================
--- pkg/trunk/stacks/nav/move_base/src/move_base.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/move_base/src/move_base.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -190,7 +190,7 @@
controller_costmap_ros_->setConvexPolygonCost(clear_poly, costmap_2d::FREE_SPACE);
}
- bool MoveBase::planService(nav_srvs::Plan::Request &req, nav_srvs::Plan::Response &resp){
+ bool MoveBase::planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp){
if(as_.isActive()){
ROS_ERROR("move_base must be in an inactive state to make a plan for an external user");
return false;
Modified: pkg/trunk/stacks/nav/move_base/src/move_base_old.cpp
===================================================================
--- pkg/trunk/stacks/nav/move_base/src/move_base_old.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/move_base/src/move_base_old.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -173,7 +173,7 @@
controller_costmap_ros_->setConvexPolygonCost(clear_poly, costmap_2d::FREE_SPACE);
}
- bool MoveBase::planService(nav_srvs::Plan::Request &req, nav_srvs::Plan::Response &resp){
+ bool MoveBase::planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp){
if(isActive()){
ROS_ERROR("move_base must be in an inactive state to make a plan for an external user");
return false;
Modified: pkg/trunk/stacks/nav/nav_view/manifest.xml
===================================================================
--- pkg/trunk/stacks/nav/nav_view/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/nav_view/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -5,7 +5,6 @@
<review status="proposal cleared" notes=""/>
<url>http://pr.willowgarage.com/wiki/nav_view</url>
<depend package="roscpp"/>
- <depend package="nav_srvs"/>
<depend package="robot_srvs"/>
<depend package="nav_msgs"/>
<depend package="tf"/>
Modified: pkg/trunk/stacks/nav/nav_view/src/nav_view/nav_view_panel.cpp
===================================================================
--- pkg/trunk/stacks/nav/nav_view/src/nav_view/nav_view_panel.cpp 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/nav/nav_view/src/nav_view/nav_view_panel.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -31,7 +31,7 @@
#include "ogre_tools/wx_ogre_render_window.h"
-#include "nav_srvs/StaticMap.h"
+#include "nav_msgs/GetMap.h"
#include "nav_msgs/PoseArray.h"
#include <tf/transform_listener.h>
@@ -193,8 +193,8 @@
void NavViewPanel::loadMap()
{
- nav_srvs::StaticMap::Request req;
- nav_srvs::StaticMap::Response resp;
+ nav_msgs::GetMap::Request req;
+ nav_msgs::GetMap::Response resp;
ROS_INFO("Requesting the map...\n");
if( !ros::service::call("/static_map", req, resp) )
{
Modified: pkg/trunk/stacks/visualization/rviz/manifest.xml
===================================================================
--- pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-07-30 18:57:04 UTC (rev 20170)
@@ -17,7 +17,6 @@
<depend package="robot_msgs"/>
<depend package="sensor_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-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.cpp 2009-07-30 18:57:04 UTC (rev 20170)
@@ -188,9 +188,9 @@
{
if (!new_map_ && (!loaded_ || reload_))
{
- nav_srvs::StaticMap srv;
+ nav_msgs::GetMap srv;
ROS_DEBUG("Requesting the map...");
- ros::ServiceClient client = update_nh_.serviceClient<nav_srvs::StaticMap>(service_);
+ ros::ServiceClient client = update_nh_.serviceClient<nav_msgs::GetMap>(service_);
if(client.call(srv) )
{
{
@@ -442,7 +442,7 @@
const char* MapDisplay::getDescription()
{
- return "Displays an image of a map gotten through a nav_srvs::StaticMap service.";
+ return "Displays an image of a map gotten through a nav_msgs::GetMap 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-07-30 18:53:07 UTC (rev 20169)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h 2009-07-30 18:57:04 UTC (rev 20170)
@@ -43,7 +43,7 @@
#include <boost/thread/thread.hpp>
#include <boost/thread/mutex.hpp>
-#include <nav_srvs/StaticMap.h>
+#include <nav_msgs/GetMap.h>
namespace Ogre
{
@@ -129,7 +129,7 @@
ros::Time last_loaded_map_time_;
boost::thread request_thread_;
- nav_srvs::StaticMap map_srv_;
+ nav_msgs::GetMap map_srv_;
bool new_map_;
boost::mutex map_mutex_;
bool reload_;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|