This example may be run after building mrs_lib by executing rosrun mrs_lib param_loader_example
. It demonstrates loading of parameters from the rosparam
server inside your node/nodelet using ParamLoader
.
To load parameters into the rosparam
server, use a launchfile prefferably. See documentation of ROS launchfiles here: http://wiki.ros.org/roslaunch/XML. Specifically, the param
XML tag is used for loading parameters directly from the launchfile: http://wiki.ros.org/roslaunch/XML/param, and the rosparam
XML tag tag is used for loading parameters from a yaml
file: http://wiki.ros.org/roslaunch/XML/rosparam.
Example code for using the ParamLoader (see documentation of the ParamLoader class):
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;
}