Namespaces | Functions | Variables
node_utils.hpp File Reference

This file adds utility functions to be used within nodes. It makes ParamHelper templated getParam() functions accessible via static global calls cras::getParam(nh, ...). It also exposes cras::NodeHandle utility class for even easier access to parameter getting. More...

#include <memory>
#include <string>
#include <ros/ros.h>
#include <cras_cpp_common/log_utils/node.h>
#include <cras_cpp_common/node_utils/node_handle.h>
#include <cras_cpp_common/optional.hpp>
#include <cras_cpp_common/param_utils/bound_param_helper.hpp>
#include <cras_cpp_common/param_utils/param_helper.hpp>
#include <cras_cpp_common/param_utils/get_param_adapters/node_handle.hpp>
Include dependency graph for node_utils.hpp:

Go to the source code of this file.

Namespaces

 cras
 

Functions

inline ::std::string cras::getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType cras::getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::std::string cras::getParam (const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions< std::string > &options={})
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType cras::getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
GetParamResult<::std::string > cras::getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
GetParamResult< ResultType > cras::getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
GetParamResult<::std::string > cras::getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
GetParamResult< ResultType > cras::getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::BoundParamHelperPtr cras::nodeParams (const ::ros::NodeHandle &node, const ::std::string &ns="")
 Returns a param helper structure "bound" to the given node handle, so that it is not needed to specify the node handle in the subsequent getParam() calls. More...
 
inline ::cras::BoundParamHelperPtr cras::paramsForNodeHandle (const ::ros::NodeHandle &node)
 Returns a param helper structure "bound" to the given node handle, so that it is not needed to specify the node handle in the subsequent getParam() calls. More...
 

Variables

const ParamHelper cras::paramHelper (::std::make_shared<::cras::NodeLogHelper >())
 

Detailed Description

This file adds utility functions to be used within nodes. It makes ParamHelper templated getParam() functions accessible via static global calls cras::getParam(nh, ...). It also exposes cras::NodeHandle utility class for even easier access to parameter getting.

Author
Martin Pecka SPDX-License-Identifier: BSD-3-Clause SPDX-FileCopyrightText: Czech Technical University in Prague

Definition in file node_utils.hpp.



cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sun Jan 14 2024 03:48:14