12 clients[
"hebiros_gazebo_plugin/add_group"] =
13 HebirosNode::n_ptr->serviceClient<AddGroupFromNamesSrv>(
"hebiros_gazebo_plugin/add_group");
18 clients[
"hebiros_gazebo_plugin/set_command_lifetime/"+group_name] =
20 "hebiros_gazebo_plugin/set_command_lifetime/"+group_name);
22 clients[
"hebiros_gazebo_plugin/set_feedback_frequency/"+group_name] =
24 "hebiros_gazebo_plugin/set_feedback_frequency/"+group_name);
26 clients[
"hebiros_gazebo_plugin/acknowledge/"+group_name] =
28 "hebiros_gazebo_plugin/acknowledge/"+group_name);
33 AddGroupFromNamesSrv srv;
35 return clients[
"hebiros_gazebo_plugin/add_group"].call(srv);
39 std::string group_name) {
41 SetCommandLifetimeSrv srv;
43 return clients[
"hebiros_gazebo_plugin/set_feedback_frequency/"+group_name].call(srv);
47 std::string group_name) {
49 SetFeedbackFrequencySrv srv;
51 return clients[
"hebiros_gazebo_plugin/set_feedback_frequency/"+group_name].call(srv);
55 std::string group_name) {
59 return clients[
"hebiros_gazebo_plugin/acknowledge/"+group_name].call(srv);
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
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)