Go to the documentation of this file.
3 #include <nav2d_navigator/GetFirstMapAction.h>
4 #include <std_srvs/Trigger.h>
12 bool receiveCommand(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
14 nav2d_navigator::GetFirstMapGoal goal;
17 res.message =
"Send GetFirstMapGoal to Navigator.";
21 int main(
int argc,
char **argv)
bool receiveCommand(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
#define NAV_GETMAP_SERVICE
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
#define NAV_GETMAP_ACTION
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
int main(int argc, char **argv)
GetMapClient * gGetMapClient
actionlib::SimpleActionClient< nav2d_navigator::GetFirstMapAction > GetMapClient
nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Wed Mar 2 2022 00:37:37