|
From: <tf...@us...> - 2009-02-09 20:15:38
|
Revision: 10842
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=10842&view=rev
Author: tfoote
Date: 2009-02-09 20:15:35 +0000 (Mon, 09 Feb 2009)
Log Message:
-----------
OccMap2d and MapMetaData -> robot_msgs, and StaticMap.srv -> robot_srvs
Modified Paths:
--------------
pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh
pkg/trunk/highlevel/highlevel_controllers/manifest.xml
pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/amcl_player/manifest.xml
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/nav_view_sdl/manifest.xml
pkg/trunk/nav/nav_view_sdl/nav_view.cpp
pkg/trunk/nav/slam_gmapping/manifest.xml
pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
pkg/trunk/nav/slam_gmapping/src/slam_gmapping.h
pkg/trunk/nav/wavefront_player/manifest.xml
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/visualization/ogre_visualizer/manifest.xml
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/poly_line_2d_display.h
pkg/trunk/world_models/costmap_2d/manifest.xml
pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp
pkg/trunk/world_models/map_saver/manifest.xml
pkg/trunk/world_models/map_saver/src/map_saver.cpp
pkg/trunk/world_models/map_server/include/map_server/image_loader.h
pkg/trunk/world_models/map_server/manifest.xml
pkg/trunk/world_models/map_server/src/image_loader.cpp
pkg/trunk/world_models/map_server/src/main.cpp
pkg/trunk/world_models/map_server/test/rtest.cpp
pkg/trunk/world_models/map_server/test/utest.cpp
pkg/trunk/world_models/static_map_server/manifest.xml
pkg/trunk/world_models/static_map_server/nodes/map_server
pkg/trunk/world_models/static_map_server/test/consumer.py
pkg/trunk/world_models/topological_map/include/topological_map/ros_topological_planner.h
pkg/trunk/world_models/topological_map/manifest.xml
pkg/trunk/world_models/topological_map/src/ros_topological_planner.cpp
Added Paths:
-----------
pkg/trunk/prcore/robot_msgs/msg/MapMetaData.msg
pkg/trunk/prcore/robot_msgs/msg/OccMap2D.msg
pkg/trunk/prcore/robot_srvs/srv/StaticMap.srv
Modified: pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/move_base.hh 2009-02-09 20:15:35 UTC (rev 10842)
@@ -71,7 +71,7 @@
#include <boost/thread.hpp>
// Static map service type (for sending costmap)
-#include "std_srvs/StaticMap.h"
+#include "robot_srvs/StaticMap.h"
#include <list>
@@ -190,7 +190,7 @@
/**
* @brief costmap service callback
*/
- bool costmapCallback(std_srvs::StaticMap::Request &req, std_srvs::StaticMap::Response &res);
+ bool costmapCallback(robot_srvs::StaticMap::Request &req, robot_srvs::StaticMap::Response &res);
void updateGlobalPose();
@@ -254,7 +254,7 @@
costmap_2d::CostMapAccessor* global_map_accessor_; /**< Read-only access to global cost map */
costmap_2d::CostMapAccessor* local_map_accessor_; /**< Read-only access to a window on the cost map */
- std_srvs::StaticMap::Response costmap_response_;
+ robot_srvs::StaticMap::Response costmap_response_;
tf::Stamped<tf::Pose> global_pose_; /**< The global pose in the map frame */
Modified: pkg/trunk/highlevel/highlevel_controllers/manifest.xml
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/highlevel/highlevel_controllers/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -17,7 +17,7 @@
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
<depend package="robot_srvs"/>
- <depend package="std_srvs"/>
+ <!--depend package="std_srvs"/ Trying to remove Tully-->
<depend package="pr2_mechanism_controllers"/>
<depend package="pr2_msgs"/>
<depend package="ransac_ground_plane_extraction"/>
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -38,7 +38,7 @@
#include <std_msgs/PointCloud.h>
#include <std_msgs/Pose2DFloat32.h>
#include <std_msgs/Polyline2D.h>
-#include <std_srvs/StaticMap.h>
+#include <robot_srvs/StaticMap.h>
#include <std_msgs/PointStamped.h>
#include <algorithm>
#include <iterator>
@@ -183,8 +183,8 @@
// get map via RPC
- std_srvs::StaticMap::Request req;
- std_srvs::StaticMap::Response resp;
+ robot_srvs::StaticMap::Request req;
+ robot_srvs::StaticMap::Response resp;
ROS_INFO("Requesting the map...\n");
while(!ros::service::call("static_map", req, resp))
{
@@ -937,7 +937,7 @@
/** Callback invoked when someone requests costmap */
- bool MoveBase::costmapCallback(std_srvs::StaticMap::Request &req, std_srvs::StaticMap::Response &res )
+ bool MoveBase::costmapCallback(robot_srvs::StaticMap::Request &req, robot_srvs::StaticMap::Response &res )
{
const unsigned char* costmap = getCostMap().getMap();
res = costmap_response_;
Modified: pkg/trunk/nav/amcl_player/amcl_player.cc
===================================================================
--- pkg/trunk/nav/amcl_player/amcl_player.cc 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/amcl_player/amcl_player.cc 2009-02-09 20:15:35 UTC (rev 10842)
@@ -101,7 +101,7 @@
#include "std_msgs/RobotBase2DOdom.h"
#include "robot_msgs/ParticleCloud.h"
#include "std_msgs/Pose2DFloat32.h"
-#include "std_srvs/StaticMap.h"
+#include "robot_srvs/StaticMap.h"
// For transform support
#include "tf/transform_broadcaster.h"
@@ -239,8 +239,8 @@
playerxdr_ftable_init();
// get map via RPC
- std_srvs::StaticMap::Request req;
- std_srvs::StaticMap::Response resp;
+ robot_srvs::StaticMap::Request req;
+ robot_srvs::StaticMap::Response resp;
puts("Requesting the map...");
while(!ros::service::call("static_map", req, resp))
{
Modified: pkg/trunk/nav/amcl_player/manifest.xml
===================================================================
--- pkg/trunk/nav/amcl_player/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/amcl_player/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -6,7 +6,7 @@
<depend package="roscpp" />
<depend package="player" />
<depend package="tf" />
- <depend package="std_srvs" />
+ <depend package="robot_srvs" />
<depend package="std_msgs" />
<depend package="robot_msgs" />
</package>
Modified: pkg/trunk/nav/nav_view/manifest.xml
===================================================================
--- pkg/trunk/nav/nav_view/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/nav_view/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -4,7 +4,7 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="roscpp"/>
- <depend package="std_srvs"/>
+ <depend package="robot_srvs"/>
<depend package="pr2_msgs"/>
<depend package="pr2_srvs"/>
<depend package="tf"/>
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-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -197,8 +197,8 @@
void NavViewPanel::loadMap()
{
- std_srvs::StaticMap::Request req;
- std_srvs::StaticMap::Response resp;
+ robot_srvs::StaticMap::Request req;
+ robot_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-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h 2009-02-09 20:15:35 UTC (rev 10842)
@@ -36,7 +36,7 @@
#include "robot_msgs/Planner2DGoal.h"
#include "std_msgs/Polyline2D.h"
#include "std_msgs/Pose2DFloat32.h"
-#include "std_srvs/StaticMap.h"
+#include "robot_srvs/StaticMap.h"
#include <OgreTexture.h>
#include <OgreMaterial.h>
Modified: pkg/trunk/nav/nav_view_sdl/manifest.xml
===================================================================
--- pkg/trunk/nav/nav_view_sdl/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/nav_view_sdl/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -4,7 +4,7 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="roscpp"/>
- <depend package="std_srvs"/>
+ <depend package="robot_srvs"/>
<depend package="pr2_msgs"/>
<depend package="pr2_srvs"/>
<depend package="sdlgl"/>
Modified: pkg/trunk/nav/nav_view_sdl/nav_view.cpp
===================================================================
--- pkg/trunk/nav/nav_view_sdl/nav_view.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/nav_view_sdl/nav_view.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -102,7 +102,7 @@
#include "std_msgs/Polyline2D.h"
#include "std_msgs/Pose2DFloat32.h"
#include "pr2_msgs/OccDiff.h"
-#include "std_srvs/StaticMap.h"
+#include "robot_srvs/StaticMap.h"
#include <pr2_srvs/TransientObstacles.h>
#include "sdlgl/sdlgl.h"
@@ -542,8 +542,8 @@
bool
NavView::load_map()
{
- std_srvs::StaticMap::Request req;
- std_srvs::StaticMap::Response resp;
+ robot_srvs::StaticMap::Request req;
+ robot_srvs::StaticMap::Response resp;
puts("Requesting the map...");
while(!ros::service::call("static_map", req, resp))
{
Modified: pkg/trunk/nav/slam_gmapping/manifest.xml
===================================================================
--- pkg/trunk/nav/slam_gmapping/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/slam_gmapping/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -6,7 +6,7 @@
<depend package="roscpp"/>
<depend package="rosconsole"/>
<depend package="std_msgs"/>
- <depend package="std_srvs"/>
+ <depend package="robot_srvs"/>
<depend package="gmapping"/>
<depend package="tf"/>
</package>
Modified: pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
===================================================================
--- pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -371,8 +371,8 @@
}
bool
-SlamGMapping::map_cb(std_srvs::StaticMap::Request &req,
- std_srvs::StaticMap::Response &res)
+SlamGMapping::map_cb(robot_srvs::StaticMap::Request &req,
+ robot_srvs::StaticMap::Response &res)
{
if(got_map_)
{
Modified: pkg/trunk/nav/slam_gmapping/src/slam_gmapping.h
===================================================================
--- pkg/trunk/nav/slam_gmapping/src/slam_gmapping.h 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/slam_gmapping/src/slam_gmapping.h 2009-02-09 20:15:35 UTC (rev 10842)
@@ -31,7 +31,7 @@
#include "ros/node.h"
#include "std_msgs/LaserScan.h"
-#include "std_srvs/StaticMap.h"
+#include "robot_srvs/StaticMap.h"
#include "tf/transform_listener.h"
#include "gmapping/gridfastslam/gridslamprocessor.h"
@@ -46,8 +46,8 @@
void spin() { node_->spin(); }
void laser_cb();
- bool map_cb(std_srvs::StaticMap::Request &req,
- std_srvs::StaticMap::Response &res);
+ bool map_cb(robot_srvs::StaticMap::Request &req,
+ robot_srvs::StaticMap::Response &res);
private:
ros::Node* node_;
@@ -61,7 +61,7 @@
std_msgs::LaserScan scan_;
bool got_map_;
- std_srvs::StaticMap::Response map_;
+ robot_srvs::StaticMap::Response map_;
ros::Duration map_update_interval_;
Modified: pkg/trunk/nav/wavefront_player/manifest.xml
===================================================================
--- pkg/trunk/nav/wavefront_player/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/wavefront_player/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -6,7 +6,7 @@
<depend package="roscpp" />
<depend package="player" />
<depend package="laser_scan" />
- <depend package="std_srvs" />
+ <depend package="robot_srvs" />
<depend package="robot_msgs" />
<depend package="tf"/>
<export>
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2009-02-09 20:15:35 UTC (rev 10842)
@@ -119,7 +119,7 @@
#include <std_msgs/PoseDot.h>
#include <std_msgs/PointCloud.h>
#include <std_msgs/LaserScan.h>
-#include <std_srvs/StaticMap.h>
+#include <robot_srvs/StaticMap.h>
// For GUI debug
#include <std_msgs/Polyline2D.h>
@@ -300,8 +300,8 @@
param("dist_penalty", dist_penalty, 2.0);
// get map via RPC
- std_srvs::StaticMap::Request req;
- std_srvs::StaticMap::Response resp;
+ robot_srvs::StaticMap::Request req;
+ robot_srvs::StaticMap::Response resp;
puts("Requesting the map...");
while(!ros::service::call("static_map", req, resp))
{
Added: pkg/trunk/prcore/robot_msgs/msg/MapMetaData.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/MapMetaData.msg (rev 0)
+++ pkg/trunk/prcore/robot_msgs/msg/MapMetaData.msg 2009-02-09 20:15:35 UTC (rev 10842)
@@ -0,0 +1,11 @@
+# The time at which the map was loaded
+time map_load_time
+# The map resolution [m/cell]
+float32 resolution
+# Map width [cells]
+uint32 width
+# Map height [cells]
+uint32 height
+# The origin of the map [m, m, rad]. This is the real-world pose of the
+# cell (0,0) in the map.
+std_msgs/Pose2DFloat32 origin
\ No newline at end of file
Added: pkg/trunk/prcore/robot_msgs/msg/OccMap2D.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/OccMap2D.msg (rev 0)
+++ pkg/trunk/prcore/robot_msgs/msg/OccMap2D.msg 2009-02-09 20:15:35 UTC (rev 10842)
@@ -0,0 +1,16 @@
+# A 2-D grid map, in which each cell represents the probability of
+# occupancy. Occupancy values are integers in the range [0,100], or -1
+# for unknown.
+
+# The map resolution [m/cell]
+float32 resolution
+# Map width [cells]
+uint32 width
+# Map height [cells]
+uint32 height
+# The origin of the map [m, m, rad]. This is the real-world pose of the
+# cell (0,0) in the map.
+std_msgs/Pose2DFloat32 origin
+# The map data, in row-major order, starting with (0,0). Occupancy
+# probabilities are in the range [0,100]. Unknown is -1.
+byte[] data
Added: pkg/trunk/prcore/robot_srvs/srv/StaticMap.srv
===================================================================
--- pkg/trunk/prcore/robot_srvs/srv/StaticMap.srv (rev 0)
+++ pkg/trunk/prcore/robot_srvs/srv/StaticMap.srv 2009-02-09 20:15:35 UTC (rev 10842)
@@ -0,0 +1,2 @@
+---
+robot_msgs/OccMap2D map
Modified: pkg/trunk/visualization/ogre_visualizer/manifest.xml
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/visualization/ogre_visualizer/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -21,9 +21,9 @@
<depend package="rxtools"/>
<depend package="planning_models"/>
<depend package="robot_msgs" />
+ <depend package="robot_srvs" />
<depend package="wxswig"/>
<depend package="wxPython_swig_interface"/>
- <depend package="std_srvs"/>
<export>
<cpp cflags="-I${prefix}/src/" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -logre_visualizer.so"/>
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -33,7 +33,7 @@
#include "common.h"
#include <tf/transform_listener.h>
-#include <std_srvs/StaticMap.h>
+#include <robot_srvs/StaticMap.h>
#include <ogre_tools/grid.h>
@@ -181,8 +181,8 @@
void MapDisplay::load()
{
- std_srvs::StaticMap::Request req;
- std_srvs::StaticMap::Response resp;
+ robot_srvs::StaticMap::Request req;
+ robot_srvs::StaticMap::Response resp;
ROS_DEBUG("Requesting the map...");
if( !ros::service::call(service_, req, resp) )
{
@@ -407,7 +407,7 @@
const char* MapDisplay::getDescription()
{
- return "Displays an image of a map gotten through a std_srvs::StaticMap service.";
+ return "Displays an image of a map gotten through a robot_srvs::StaticMap service.";
}
} // namespace ogre_vis
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.h
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.h 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.h 2009-02-09 20:15:35 UTC (rev 10842)
@@ -35,7 +35,7 @@
#include <OgreTexture.h>
#include <OgreMaterial.h>
-#include <std_msgs/MapMetaData.h>
+#include <robot_msgs/MapMetaData.h>
#include <ros/time.h>
namespace Ogre
@@ -112,7 +112,7 @@
float alpha_;
bool new_metadata_;
- std_msgs::MapMetaData metadata_message_;
+ robot_msgs::MapMetaData metadata_message_;
ros::Time last_loaded_map_time_;
StringProperty* service_property_;
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/poly_line_2d_display.h
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/poly_line_2d_display.h 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/poly_line_2d_display.h 2009-02-09 20:15:35 UTC (rev 10842)
@@ -35,7 +35,7 @@
#include "helpers/color.h"
#include <std_msgs/Polyline2D.h>
-#include <std_msgs/MapMetaData.h>
+#include <robot_msgs/MapMetaData.h>
namespace ogre_tools
{
@@ -144,7 +144,7 @@
std_msgs::Polyline2D message_;
bool new_metadata_;
- std_msgs::MapMetaData metadata_message_;
+ robot_msgs::MapMetaData metadata_message_;
ColorProperty* color_property_;
ROSTopicStringProperty* topic_property_;
Modified: pkg/trunk/world_models/costmap_2d/manifest.xml
===================================================================
--- pkg/trunk/world_models/costmap_2d/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/costmap_2d/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -9,6 +9,7 @@
<depend package="pr2_msgs" />
<depend package="tf" />
<depend package="robot_filter" />
+<depend package="robot_srvs" />
<export>
<cpp cflags="-I${prefix}/include `rosboost-cfg --cflags`" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib `rosboost-cfg --lflags thread`"/>
</export>
Modified: pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp
===================================================================
--- pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -36,7 +36,7 @@
#include <std_msgs/LaserScan.h>
#include <std_msgs/PointCloud.h>
#include <pr2_msgs/OccDiff.h>
-#include <std_srvs/StaticMap.h>
+#include <robot_srvs/StaticMap.h>
#include <pr2_srvs/TransientObstacles.h>
//Laser projection
@@ -114,8 +114,8 @@
tf_(*this, true, 1 * 1000000000ULL, 0ULL),
costmap_(WINDOW_LENGTH)
{
- std_srvs::StaticMap::Request req;
- std_srvs::StaticMap::Response resp;
+ robot_srvs::StaticMap::Request req;
+ robot_srvs::StaticMap::Response resp;
puts("Requesting the map...");
while(!ros::service::call("static_map", req, resp))
{
Modified: pkg/trunk/world_models/map_saver/manifest.xml
===================================================================
--- pkg/trunk/world_models/map_saver/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/map_saver/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -3,5 +3,5 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="roscpp"/>
- <depend package="std_srvs"/>
+ <depend package="robot_srvs"/>
</package>
Modified: pkg/trunk/world_models/map_saver/src/map_saver.cpp
===================================================================
--- pkg/trunk/world_models/map_saver/src/map_saver.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/map_saver/src/map_saver.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -56,7 +56,7 @@
**/
#include "ros/node.h"
-#include "std_srvs/StaticMap.h"
+#include "robot_srvs/StaticMap.h"
using namespace std;
@@ -74,8 +74,8 @@
*/
MapGenerator::MapGenerator(string servname) : ros::Node("map_generator") {
puts("Requesting the map...");
- std_srvs::StaticMap::Request req;
- std_srvs::StaticMap::Response resp;
+ robot_srvs::StaticMap::Request req;
+ robot_srvs::StaticMap::Response resp;
while(!ros::service::call("static_map", req, resp))
{
printf("request '%s' failed; trying again...", servname.c_str());
Modified: pkg/trunk/world_models/map_server/include/map_server/image_loader.h
===================================================================
--- pkg/trunk/world_models/map_server/include/map_server/image_loader.h 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/map_server/include/map_server/image_loader.h 2009-02-09 20:15:35 UTC (rev 10842)
@@ -33,7 +33,7 @@
* Author: Brian Gerkey
*/
-#include "std_srvs/StaticMap.h"
+#include "robot_srvs/StaticMap.h"
namespace map_server
{
@@ -49,7 +49,7 @@
*
* @throws std::runtime_error If the image file can't be loaded
* */
-void loadMapFromFile(std_srvs::StaticMap::Response* resp,
+void loadMapFromFile(robot_srvs::StaticMap::Response* resp,
const char* fname, double res, bool negate);
}
Modified: pkg/trunk/world_models/map_server/manifest.xml
===================================================================
--- pkg/trunk/world_models/map_server/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/map_server/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -10,7 +10,7 @@
<review status="unreviewed" notes="API review in progress (Brian)"/>
<url>http://pr.willowgarage.com</url>
<depend package="roscpp"/>
- <depend package="std_srvs"/>
+ <depend package="robot_srvs"/>
<!-- <depend package="sdl_image"/> -->
<sysdepend os="ubuntu" version="7.04-feisty" package="libsdl-image1.2-dev"/>
<sysdepend os="ubuntu" version="8.04-hardy" package="libsdl-image1.2-dev"/>
Modified: pkg/trunk/world_models/map_server/src/image_loader.cpp
===================================================================
--- pkg/trunk/world_models/map_server/src/image_loader.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/map_server/src/image_loader.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -51,7 +51,7 @@
{
void
-loadMapFromFile(std_srvs::StaticMap::Response* resp,
+loadMapFromFile(robot_srvs::StaticMap::Response* resp,
const char* fname, double res, bool negate)
{
SDL_Surface* img;
Modified: pkg/trunk/world_models/map_server/src/main.cpp
===================================================================
--- pkg/trunk/world_models/map_server/src/main.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/map_server/src/main.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -74,7 +74,7 @@
@section services ROS services
Offers (name/type):
-- @b "static_map"/std_srvs::StaticMap : Retrieve the map via this service
+- @b "static_map"/robot_srvs::StaticMap : Retrieve the map via this service
@section parameters ROS parameters
@@ -94,7 +94,7 @@
#include "ros/node.h"
#include "ros/publisher.h"
#include "map_server/image_loader.h"
-#include "std_msgs/MapMetaData.h"
+#include "robot_msgs/MapMetaData.h"
class MapServer : public ros::Node
{
@@ -103,8 +103,8 @@
MapServer() : ros::Node("map_server") {}
/** Callback invoked when someone requests our service */
- bool mapCallback(std_srvs::StaticMap::Request &req,
- std_srvs::StaticMap::Response &res )
+ bool mapCallback(robot_srvs::StaticMap::Request &req,
+ robot_srvs::StaticMap::Response &res )
{
// request is empty; we ignore it
@@ -116,14 +116,14 @@
/** The map response is cached here, to be sent out to service callers
*/
- std_srvs::StaticMap::Response map_resp_;
+ robot_srvs::StaticMap::Response map_resp_;
void metadataSubscriptionCallback(const ros::PublisherPtr& pub)
{
publish( "map_metadata", meta_data_message_ );
}
- std_msgs::MapMetaData meta_data_message_;
+ robot_msgs::MapMetaData meta_data_message_;
};
int main(int argc, char **argv)
Modified: pkg/trunk/world_models/map_server/test/rtest.cpp
===================================================================
--- pkg/trunk/world_models/map_server/test/rtest.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/map_server/test/rtest.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -32,7 +32,7 @@
#include <gtest/gtest.h>
#include <ros/service.h>
#include <ros/node.h>
-#include <std_srvs/StaticMap.h>
+#include <robot_srvs/StaticMap.h>
#include "test_constants.h"
@@ -65,8 +65,8 @@
{
try
{
- std_srvs::StaticMap::Request req;
- std_srvs::StaticMap::Response resp;
+ robot_srvs::StaticMap::Request req;
+ robot_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/world_models/map_server/test/utest.cpp
===================================================================
--- pkg/trunk/world_models/map_server/test/utest.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/map_server/test/utest.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -43,7 +43,7 @@
{
try
{
- std_srvs::StaticMap::Response map_resp;
+ robot_srvs::StaticMap::Response map_resp;
map_server::loadMapFromFile(&map_resp, g_valid_png_file, g_valid_image_res, false);
EXPECT_FLOAT_EQ(map_resp.map.resolution, g_valid_image_res);
EXPECT_EQ(map_resp.map.width, g_valid_image_width);
@@ -63,7 +63,7 @@
{
try
{
- std_srvs::StaticMap::Response map_resp;
+ robot_srvs::StaticMap::Response map_resp;
map_server::loadMapFromFile(&map_resp, g_valid_bmp_file, g_valid_image_res, false);
EXPECT_FLOAT_EQ(map_resp.map.resolution, g_valid_image_res);
EXPECT_EQ(map_resp.map.width, g_valid_image_width);
@@ -83,7 +83,7 @@
{
try
{
- std_srvs::StaticMap::Response map_resp;
+ robot_srvs::StaticMap::Response map_resp;
map_server::loadMapFromFile(&map_resp, "foo", 0.1, false);
}
catch(std::runtime_error &e)
Modified: pkg/trunk/world_models/static_map_server/manifest.xml
===================================================================
--- pkg/trunk/world_models/static_map_server/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/static_map_server/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -8,7 +8,7 @@
<url>http://pr.willowgarage.com/</url>
<depend package="rospy" />
<depend package="std_msgs" />
- <depend package="std_srvs" />
+ <depend package="robot_srvs" />
<depend package="rostest" />
<sysdepend os="ubuntu" version="7.04-feisty" package="python-imaging"/>
Modified: pkg/trunk/world_models/static_map_server/nodes/map_server
===================================================================
--- pkg/trunk/world_models/static_map_server/nodes/map_server 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/static_map_server/nodes/map_server 2009-02-09 20:15:35 UTC (rev 10842)
@@ -39,7 +39,7 @@
import rospy
#import std_msgs.msg
import std_msgs.msg
-import std_srvs.srv
+import robot_srvs.srv
import Image
import yaml
@@ -52,7 +52,7 @@
pass
def map_handler(self, req):
- r = std_srvs.srv.StaticMapResponse(std_msgs.msg.OccMap2D(self.scale,
+ r = robot_srvs.srv.StaticMapResponse(std_msgs.msg.OccMap2D(self.scale,
self.im.size[0],
self.im.size[1],
std_msgs.msg.Pose2DFloat32(*tuple(self.origin)),
@@ -96,7 +96,7 @@
self.origin = yaml_defs['origin']
rospy.init_node(NAME)
- s1 = rospy.Service("static_map", std_srvs.srv.StaticMap, self.map_handler)
+ s1 = rospy.Service("static_map", robot_srvs.srv.StaticMap, self.map_handler)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/world_models/static_map_server/test/consumer.py
===================================================================
--- pkg/trunk/world_models/static_map_server/test/consumer.py 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/static_map_server/test/consumer.py 2009-02-09 20:15:35 UTC (rev 10842)
@@ -41,7 +41,7 @@
import sys, unittest, time
import rospy, rostest
-from std_srvs.srv import *
+from robot_srvs.srv import *
class TestConsumer(unittest.TestCase):
def __init__(self, *args):
Modified: pkg/trunk/world_models/topological_map/include/topological_map/ros_topological_planner.h
===================================================================
--- pkg/trunk/world_models/topological_map/include/topological_map/ros_topological_planner.h 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/topological_map/include/topological_map/ros_topological_planner.h 2009-02-09 20:15:35 UTC (rev 10842)
@@ -39,7 +39,7 @@
#include <boost/thread.hpp>
#include <ros/node.h>
#include <ros/console.h>
-#include <std_srvs/StaticMap.h>
+#include <robot_srvs/StaticMap.h>
#include <std_msgs/RobotBase2DOdom.h>
#include <topological_map/NavigationCost.h>
#include <topological_map/ConnectorCosts.h>
Modified: pkg/trunk/world_models/topological_map/manifest.xml
===================================================================
--- pkg/trunk/world_models/topological_map/manifest.xml 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/topological_map/manifest.xml 2009-02-09 20:15:35 UTC (rev 10842)
@@ -5,7 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp" />
<depend package="std_msgs" />
-<depend package="std_srvs" />
+<depend package="robot_srvs" />
<depend package="rosconsole" />
<depend package="sbpl" />
<depend package="navfn" />
Modified: pkg/trunk/world_models/topological_map/src/ros_topological_planner.cpp
===================================================================
--- pkg/trunk/world_models/topological_map/src/ros_topological_planner.cpp 2009-02-09 20:01:36 UTC (rev 10841)
+++ pkg/trunk/world_models/topological_map/src/ros_topological_planner.cpp 2009-02-09 20:15:35 UTC (rev 10842)
@@ -122,8 +122,8 @@
void BottleneckGraphRos::updateCostMap ()
{
- std_srvs::StaticMap::Request costmap_req;
- std_srvs::StaticMap::Response costmap_resp;
+ robot_srvs::StaticMap::Request costmap_req;
+ robot_srvs::StaticMap::Response costmap_resp;
while (!ros::service::call("costmap", costmap_req, costmap_resp))
{
ROS_WARN("Costmap request failed; trying again...\n");
@@ -254,8 +254,8 @@
{
lock_.lock();
- std_srvs::StaticMap::Request req;
- std_srvs::StaticMap::Response resp;
+ robot_srvs::StaticMap::Request req;
+ robot_srvs::StaticMap::Response resp;
ROS_INFO ("Requesting map... \n");
while (!ros::service::call("static_map", req, resp))
{
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|