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


nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Sun Apr 2 2017 04:05:38