Example code for using the ParamLoader (see documentation of the ParamLoader class):
#include <mrs_lib/param_loader.h>
int main(int argc, char **argv)
{
const std::string node_name("param_loader_example");
ros::init(argc, argv, node_name);
ros::NodeHandle nh("~");
ROS_INFO_STREAM("[" << node_name << "]: pushing testing parameters to the rosparam server");
nh.setParam("test_param_double", std::numeric_limits<double>::quiet_NaN());
nh.setParam("test_param_vector", std::vector<int>({6, 6, 6}));
ROS_INFO_STREAM("[" << node_name <<" ]: loading parameters using ParamLoader");
double test_param_double;
pl.
loadParam(
"test_param_double", test_param_double);
const auto test_param_vector = pl.
loadParam2<std::vector<int>>(
"test_param_vector");
const auto test_param_int = pl.
loadParam2<
int>(
"test_param_int", 4);
const auto test_param_bool = pl.
loadParam2<
bool>(
"test_param_bool");
Eigen::MatrixXd matxd;
ROS_INFO_STREAM("[" << node_name << "]: Loaded matrix: " << matxd);
const auto string_from_yaml = pl.
loadParam2<std::string>(
"string_from_yaml");
{
ROS_ERROR_STREAM("[" << node_name << "]: parameter loading failure! Ending the node");
ros::shutdown();
return 1;
}
if (test_param_bool)
{
ROS_INFO_STREAM("[" << node_name << "]: Showing values of: " << string_from_yaml);
for (auto& el : test_param_vector)
ROS_INFO_STREAM("[" << node_name << "]: Value: " << test_param_double * el + test_param_int);
}
return 0;
}
Convenience class for loading parameters from rosparam server.
Definition param_loader.h:45
bool loadedSuccessfully() const
Indicates whether all compulsory parameters were successfully loaded.
Definition param_loader.cpp:107
T loadParam2(const std::string &name, const T &default_value)
Loads a parameter from the rosparam server with a default value.
Definition param_loader.hpp:295
bool addYamlFile(const std::string &filepath)
Adds the specified file as a source of static parameters.
Definition param_loader.cpp:122
bool loadParam(const std::string &name, T &out_value, const T &default_value)
Loads a parameter from the rosparam server with a default value.
Definition param_loader.hpp:277
bool loadMatrixDynamic(const std::string &name, MatrixX< T > &mat, int rows, int cols)
Specialized method for loading compulsory dynamic Eigen matrix parameters.
Definition param_loader.hpp:669