get_map_client.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <actionlib/client/simple_action_client.h>
00003 #include <tf/transform_datatypes.h>
00004 #include <nav2d_navigator/GetFirstMapAction.h>
00005 #include <nav2d_navigator/SendCommand.h>
00006 
00007 #include <nav2d_navigator/commands.h>
00008 
00009 typedef actionlib::SimpleActionClient<nav2d_navigator::GetFirstMapAction> GetMapClient;
00010 
00011 GetMapClient* gGetMapClient;
00012 
00013 bool receiveCommand(nav2d_navigator::SendCommand::Request &req, nav2d_navigator::SendCommand::Response &res)
00014 {
00015         if(req.command == NAV_COM_GETMAP)
00016         {
00017                 nav2d_navigator::GetFirstMapGoal goal;
00018                 gGetMapClient->sendGoal(goal);
00019                 return true;
00020         }
00021         return false;
00022 }
00023 
00024 int main(int argc, char **argv)
00025 {
00026         ros::init(argc, argv, "GetFirstMap");
00027         ros::NodeHandle n;
00028         
00029         ros::ServiceServer cmdServer = n.advertiseService(NAV_GETMAP_SERVICE, &receiveCommand);
00030         gGetMapClient = new GetMapClient(NAV_GETMAP_ACTION, true);
00031         gGetMapClient->waitForServer();
00032         
00033         ros::spin();
00034         
00035         delete gGetMapClient;
00036         return 0;
00037 }


nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Thu Aug 27 2015 14:07:13