get_map_client.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <nav2d_navigator/GetFirstMapAction.h>
4 #include <std_srvs/Trigger.h>
5 
7 
9 
11 
12 bool receiveCommand(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
13 {
14  nav2d_navigator::GetFirstMapGoal goal;
15  gGetMapClient->sendGoal(goal);
16  res.success = true;
17  res.message = "Send GetFirstMapGoal to Navigator.";
18  return true;
19 }
20 
21 int main(int argc, char **argv)
22 {
23  ros::init(argc, argv, "GetFirstMap");
25 
29 
30  ros::spin();
31 
32  delete gGetMapClient;
33  return 0;
34 }
receiveCommand
bool receiveCommand(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Definition: get_map_client.cpp:12
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
actionlib::SimpleActionClient::waitForServer
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
NAV_GETMAP_SERVICE
#define NAV_GETMAP_SERVICE
Definition: commands.h:8
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
ros::ServiceServer
actionlib::SimpleActionClient
NAV_GETMAP_ACTION
#define NAV_GETMAP_ACTION
Definition: commands.h:14
simple_action_client.h
actionlib::SimpleActionClient::sendGoal
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
main
int main(int argc, char **argv)
Definition: get_map_client.cpp:21
gGetMapClient
GetMapClient * gGetMapClient
Definition: get_map_client.cpp:10
ros::spin
ROSCPP_DECL void spin()
commands.h
GetMapClient
actionlib::SimpleActionClient< nav2d_navigator::GetFirstMapAction > GetMapClient
Definition: get_map_client.cpp:8
ros::NodeHandle


nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Wed Mar 2 2022 00:37:37