explore_client.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <nav2d_navigator/ExploreAction.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::ExploreGoal goal;
15  gExploreClient->sendGoal(goal);
16  res.success = true;
17  res.message = "Send ExploreGoal to Navigator.";
18  return true;
19 }
20 
21 int main(int argc, char **argv)
22 {
23  ros::init(argc, argv, "Explore");
25 
27  gExploreClient = new ExploreClient(NAV_EXPLORE_ACTION, true);
28  gExploreClient->waitForServer();
29 
30  ros::spin();
31 
32  delete gExploreClient;
33  return 0;
34 }
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
int main(int argc, char **argv)
ExploreClient * gExploreClient
#define NAV_EXPLORE_SERVICE
Definition: commands.h:7
actionlib::SimpleActionClient< nav2d_navigator::ExploreAction > ExploreClient
ROSCPP_DECL void spin()
bool receiveCommand(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
#define NAV_EXPLORE_ACTION
Definition: commands.h:13


nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Tue Nov 7 2017 06:02:48