localize_client.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <nav2d_navigator/LocalizeAction.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::LocalizeGoal goal;
15  goal.velocity = 0.5;
17  res.success = true;
18  res.message = "Send LocalizeGoal to Navigator.";
19  return true;
20 }
21 
22 int main(int argc, char **argv)
23 {
24  ros::init(argc, argv, "Localize");
26 
30 
31  ros::spin();
32 
33  delete gLocalizeClient;
34  return 0;
35 }
receiveCommand
bool receiveCommand(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Definition: localize_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
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
ros::ServiceServer
main
int main(int argc, char **argv)
Definition: localize_client.cpp:22
actionlib::SimpleActionClient
simple_action_client.h
actionlib::SimpleActionClient::sendGoal
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
LocalizeClient
actionlib::SimpleActionClient< nav2d_navigator::LocalizeAction > LocalizeClient
Definition: localize_client.cpp:8
gLocalizeClient
LocalizeClient * gLocalizeClient
Definition: localize_client.cpp:10
NAV_LOCALIZE_ACTION
#define NAV_LOCALIZE_ACTION
Definition: commands.h:15
ros::spin
ROSCPP_DECL void spin()
commands.h
NAV_LOCALIZE_SERVICE
#define NAV_LOCALIZE_SERVICE
Definition: commands.h:9
ros::NodeHandle


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