hebiros_clients.cpp
Go to the documentation of this file.
1 #include "hebiros_clients.h"
2 
3 #include "hebiros.h"
4 
5 using namespace hebiros;
6 
7 
8 std::map<std::string, ros::ServiceClient> HebirosClients::clients;
9 
11 
12  clients["hebiros_gazebo_plugin/add_group"] =
13  HebirosNode::n_ptr->serviceClient<AddGroupFromNamesSrv>("hebiros_gazebo_plugin/add_group");
14 }
15 
16 void HebirosClients::registerGroupClients(std::string group_name) {
17 
18  clients["hebiros_gazebo_plugin/set_command_lifetime/"+group_name] =
19  HebirosNode::n_ptr->serviceClient<SetCommandLifetimeSrv>(
20  "hebiros_gazebo_plugin/set_command_lifetime/"+group_name);
21 
22  clients["hebiros_gazebo_plugin/set_feedback_frequency/"+group_name] =
23  HebirosNode::n_ptr->serviceClient<SetFeedbackFrequencySrv>(
24  "hebiros_gazebo_plugin/set_feedback_frequency/"+group_name);
25 
26  clients["hebiros_gazebo_plugin/acknowledge/"+group_name] =
27  HebirosNode::n_ptr->serviceClient<std_srvs::Empty>(
28  "hebiros_gazebo_plugin/acknowledge/"+group_name);
29 }
30 
31 bool HebirosClients::addGroup(AddGroupFromNamesSrv::Request &req) {
32 
33  AddGroupFromNamesSrv srv;
34  srv.request = req;
35  return clients["hebiros_gazebo_plugin/add_group"].call(srv);
36 }
37 
38 bool HebirosClients::setCommandLifetime(SetCommandLifetimeSrv::Request &req,
39  std::string group_name) {
40 
41  SetCommandLifetimeSrv srv;
42  srv.request = req;
43  return clients["hebiros_gazebo_plugin/set_feedback_frequency/"+group_name].call(srv);
44 }
45 
46 bool HebirosClients::setFeedbackFrequency(SetFeedbackFrequencySrv::Request &req,
47  std::string group_name) {
48 
49  SetFeedbackFrequencySrv srv;
50  srv.request = req;
51  return clients["hebiros_gazebo_plugin/set_feedback_frequency/"+group_name].call(srv);
52 }
53 
54 bool HebirosClients::acknowledge(std_srvs::Empty::Request &req,
55  std::string group_name) {
56 
57  std_srvs::Empty srv;
58  srv.request = req;
59  return clients["hebiros_gazebo_plugin/acknowledge/"+group_name].call(srv);
60 }
void registerGroupClients(std::string group_name)
static std::map< std::string, ros::ServiceClient > clients
bool addGroup(hebiros::AddGroupFromNamesSrv::Request &req)
static std::shared_ptr< ros::NodeHandle > n_ptr
Definition: hebiros.h:78
void registerNodeClients()
bool acknowledge(std_srvs::Empty::Request &req, std::string group_name)
bool setCommandLifetime(hebiros::SetCommandLifetimeSrv::Request &req, std::string group_name)
bool setFeedbackFrequency(hebiros::SetFeedbackFrequencySrv::Request &req, std::string group_name)


hebiros
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:08:14