hebiros_services_gazebo.h
Go to the documentation of this file.
1 #ifndef HEBIROS_SERVICES_GAZEBO_H
2 #define HEBIROS_SERVICES_GAZEBO_H
3 
4 #include "ros/ros.h"
5 
6 #include "hebiros_services.h"
7 
8 
10 
11  public:
12 
13  void registerNodeServices();
14 
15  void registerGroupServices(std::string group_name);
16 
17  bool entryList(
18  EntryListSrv::Request &req, EntryListSrv::Response &res);
19 
20  bool addGroup(
21  AddGroupFromNamesSrv::Request &req, AddGroupFromNamesSrv::Response &res,
22  std::map<std::string, std::string> joint_full_names);
23 
24  bool addGroupFromNames(
25  AddGroupFromNamesSrv::Request &req, AddGroupFromNamesSrv::Response &res);
26 
27  bool addGroupFromURDF(
28  AddGroupFromURDFSrv::Request &req, AddGroupFromURDFSrv::Response &res);
29 
30  bool addModelFromURDF(
31  AddModelFromURDFSrv::Request &req, AddModelFromURDFSrv::Response &res);
32 
33  bool size(
34  SizeSrv::Request &req, SizeSrv::Response &res, std::string group_name);
35 
37  SetFeedbackFrequencySrv::Request &req, SetFeedbackFrequencySrv::Response &res,
38  std::string group_name);
39 
40  bool setCommandLifetime(
41  SetCommandLifetimeSrv::Request &req, SetCommandLifetimeSrv::Response &res,
42  std::string group_name);
43 
45  SendCommandWithAcknowledgementSrv::Request &req,
46  SendCommandWithAcknowledgementSrv::Response &res, std::string group_name);
47 
48 };
49 
50 #endif
bool addModelFromURDF(AddModelFromURDFSrv::Request &req, AddModelFromURDFSrv::Response &res)
bool setCommandLifetime(SetCommandLifetimeSrv::Request &req, SetCommandLifetimeSrv::Response &res, std::string group_name)
bool sendCommandWithAcknowledgement(SendCommandWithAcknowledgementSrv::Request &req, SendCommandWithAcknowledgementSrv::Response &res, std::string group_name)
bool addGroupFromNames(AddGroupFromNamesSrv::Request &req, AddGroupFromNamesSrv::Response &res)
bool size(SizeSrv::Request &req, SizeSrv::Response &res, std::string group_name)
bool addGroup(AddGroupFromNamesSrv::Request &req, AddGroupFromNamesSrv::Response &res, std::map< std::string, std::string > joint_full_names)
void registerGroupServices(std::string group_name)
bool entryList(EntryListSrv::Request &req, EntryListSrv::Response &res)
bool setFeedbackFrequency(SetFeedbackFrequencySrv::Request &req, SetFeedbackFrequencySrv::Response &res, std::string group_name)
bool addGroupFromURDF(AddGroupFromURDFSrv::Request &req, AddGroupFromURDFSrv::Response &res)


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