hebiros_parameters.cpp
Go to the documentation of this file.
1 #include "hebiros_parameters.h"
2 
3 #include "hebiros.h"
4 
5 
6 std::map<std::string, bool> HebirosParameters::bool_parameters_default =
7  {{"use_sim_time", false}};
8 std::map<std::string, bool> HebirosParameters::bool_parameters;
9 std::map<std::string, int> HebirosParameters::int_parameters_default =
10  {{"hebiros/node_frequency", 200},
11  {"hebiros/action_frequency", 200},
12  {"hebiros/feedback_frequency", 100},
13  {"hebiros/command_lifetime", 100}};
14 std::map<std::string, int> HebirosParameters::int_parameters;
15 
17 
18  loadInt("hebiros/node_frequency");
19  loadInt("hebiros/action_frequency");
20  loadInt("hebiros/feedback_frequency");
21  loadInt("hebiros/command_lifetime");
22 
23  ROS_INFO("Parameters:");
24  ROS_INFO("hebiros/node_frequency=%d", getInt("hebiros/node_frequency"));
25  ROS_INFO("hebiros/action_frequency=%d", getInt("hebiros/action_frequency"));
26  ROS_INFO("hebiros/feedback_frequency=%d", getInt("hebiros/feedback_frequency"));
27  ROS_INFO("hebiros/command_lifetime=%d", getInt("hebiros/command_lifetime"));
28 }
29 
30 void HebirosParameters::loadBool(std::string name) {
31  if (bool_parameters_default.find(name) != bool_parameters_default.end()) {
32  bool value;
34 
35  HebirosNode::n_ptr->param<bool>(name, value, default_value);
36  HebirosNode::n_ptr->setParam(name, value);
37  bool_parameters[name] = value;
38  }
39 }
40 
41 void HebirosParameters::setBool(std::string name, bool value) {
42 
43  if (bool_parameters_default.find(name) != bool_parameters_default.end()) {
44  HebirosNode::n_ptr->setParam(name, value);
45  bool_parameters[name] = value;
46  }
47 }
48 
49 bool HebirosParameters::getBool(std::string name) {
50 
51  if (bool_parameters.find(name) != bool_parameters.end()) {
52  return bool_parameters[name];
53  }
54  else if (bool_parameters_default.find(name) != bool_parameters_default.end()) {
55  return bool_parameters_default[name];
56  }
57  else {
58  return 0;
59  }
60 }
61 
62 void HebirosParameters::loadInt(std::string name) {
63  if (int_parameters_default.find(name) != int_parameters_default.end()) {
64  int value;
66 
67  HebirosNode::n_ptr->param<int>(name, value, default_value);
68  HebirosNode::n_ptr->setParam(name, value);
69  int_parameters[name] = value;
70  }
71 }
72 
73 void HebirosParameters::setInt(std::string name, int value) {
74 
75  if (int_parameters_default.find(name) != int_parameters_default.end()) {
76  HebirosNode::n_ptr->setParam(name, value);
77  int_parameters[name] = value;
78  }
79 }
80 
81 int HebirosParameters::getInt(std::string name) {
82 
83  if (int_parameters.find(name) != int_parameters.end()) {
84  return int_parameters[name];
85  }
86  else if (int_parameters_default.find(name) != int_parameters_default.end()) {
87  return int_parameters_default[name];
88  }
89  else {
90  return 0;
91  }
92 }
static int getInt(std::string name)
static std::map< std::string, bool > bool_parameters_default
static void setInt(std::string name, int value)
static std::map< std::string, bool > bool_parameters
static void loadInt(std::string name)
def default_value(type_)
static std::shared_ptr< ros::NodeHandle > n_ptr
Definition: hebiros.h:78
static bool getBool(std::string name)
static void setNodeParameters()
#define ROS_INFO(...)
static void setBool(std::string name, bool value)
static std::map< std::string, int > int_parameters_default
static void loadBool(std::string name)
static std::map< std::string, int > int_parameters


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