46 #ifndef __PARAMETER_PA_ROS_H
47 #define __PARAMETER_PA_ROS_H
56 #include <eigen3/Eigen/Core>
61 bool load(
const std::string name,
bool &value,
62 const bool print_default =
true)
const;
64 bool load(
const std::string name, std::string &value,
65 const bool print_default =
true)
const;
66 bool loadTopic(
const std::string name, std::string &value,
67 const bool print_default =
true)
const;
68 bool loadPath(
const std::string name, std::string &value,
69 const bool print_default =
true)
const;
71 bool load(
const std::string name,
int &value,
72 const bool print_default =
true)
const;
74 bool load(
const std::string name,
double &value,
75 const bool print_default =
true)
const;
78 bool load(
const std::string name, std::vector<bool > &value,
79 const bool print_default =
true)
const;
81 bool load(
const std::string name, std::vector<std::string> &value,
82 const bool print_default =
true)
const;
84 bool load(
const std::string name, std::vector<int > &value,
85 const bool print_default =
true)
const;
87 bool load(
const std::string name, std::vector<double > &value,
88 const bool print_default =
true)
const;
90 bool load(
const std::string name, Eigen::MatrixXf &value,
91 const bool print_default =
true)
const;
95 static std::string
boolToStr(
const bool value);
101 bool load_topic(
const std::string name, std::string &value,
102 const bool print_default =
true)
const;
104 bool load_path(
const std::string name, std::string &value,
105 const bool print_default =
true)
const;
115 void loadSub(
const std::string &n,
const std::string &v,
116 const bool p,
const bool r)
const;
118 const std::string name);
123 #endif // __PARAMETER_PA_ROS_H