1 #ifndef HEBIROS_SERVICES_GAZEBO_H 2 #define HEBIROS_SERVICES_GAZEBO_H 18 EntryListSrv::Request &req, EntryListSrv::Response &res);
21 AddGroupFromNamesSrv::Request &req, AddGroupFromNamesSrv::Response &res,
22 std::map<std::string, std::string> joint_full_names);
25 AddGroupFromNamesSrv::Request &req, AddGroupFromNamesSrv::Response &res);
28 AddGroupFromURDFSrv::Request &req, AddGroupFromURDFSrv::Response &res);
31 AddModelFromURDFSrv::Request &req, AddModelFromURDFSrv::Response &res);
34 SizeSrv::Request &req, SizeSrv::Response &res, std::string group_name);
37 SetFeedbackFrequencySrv::Request &req, SetFeedbackFrequencySrv::Response &res,
38 std::string group_name);
41 SetCommandLifetimeSrv::Request &req, SetCommandLifetimeSrv::Response &res,
42 std::string group_name);
45 SendCommandWithAcknowledgementSrv::Request &req,
46 SendCommandWithAcknowledgementSrv::Response &res, std::string group_name);
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)
void registerNodeServices()
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)