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


robot_navigator
Author(s): Sebastian Kasperski
autogenerated on Fri Feb 21 2014 12:26:47