ros_parameter_handler.h
Go to the documentation of this file.
1 // Copyright (c) 2020-2021 Pilz GmbH & Co. KG
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU Lesser General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU Lesser General Public License for more details.
12 //
13 // You should have received a copy of the GNU Lesser General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 
16 #ifndef PSEN_SCAN_V2_ROS_PARAMETER_HANDLER_H
17 #define PSEN_SCAN_V2_ROS_PARAMETER_HANDLER_H
18 
19 #include <string>
20 
21 #include <boost/optional.hpp>
22 
23 #include <ros/ros.h>
24 
26 
27 namespace psen_scan_v2
28 {
29 template <class T>
30 boost::optional<T> getParam(const ros::NodeHandle& node_handle, const std::string& key)
31 {
32  if (!node_handle.hasParam(key))
33  {
34  ROS_WARN_STREAM("Parameter " + key + " doesn't exist on parameter server.");
35  return boost::none;
36  }
37 
38  T default_val{};
39  boost::optional<T> ret_val(default_val);
40  if (!node_handle.getParam(key, ret_val.get()))
41  {
42  throw WrongParameterType("Parameter " + key + " has wrong datatype on parameter server.");
43  }
44  return ret_val;
45 }
46 
47 template <class T>
48 T getOptionalParamFromServer(const ros::NodeHandle& node_handle, const std::string& key, const T& default_value)
49 {
50  boost::optional<T> val{ getParam<T>(node_handle, key) };
51  if (!val)
52  {
53  return default_value;
54  }
55  return val.value();
56 }
57 
58 template <class T>
59 T getRequiredParamFromServer(const ros::NodeHandle& node_handle, const std::string& key)
60 {
61  boost::optional<T> val{ getParam<T>(node_handle, key) };
62  if (!val)
63  {
64  throw ParamMissingOnServer("Parameter " + key + " doesn't exist on parameter server.");
65  }
66  return val.value();
67 }
68 
69 } // namespace psen_scan_v2
70 
71 #endif // PSEN_SCAN_V2_ROS_PARAMETER_HANDLER_H
psen_scan_v2::getParam
boost::optional< T > getParam(const ros::NodeHandle &node_handle, const std::string &key)
Definition: ros_parameter_handler.h:30
psen_scan_v2::WrongParameterType
Exception thrown if a parameter can be found on the ROS parameter server but with an unexpected type.
Definition: get_ros_parameter_exception.h:37
get_ros_parameter_exception.h
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
default_value
string default_value
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
psen_scan_v2::getRequiredParamFromServer
T getRequiredParamFromServer(const ros::NodeHandle &node_handle, const std::string &key)
Definition: ros_parameter_handler.h:59
psen_scan_v2
Root namespace for the ROS part.
Definition: active_zoneset_node.h:29
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ros::NodeHandle
psen_scan_v2::getOptionalParamFromServer
T getOptionalParamFromServer(const ros::NodeHandle &node_handle, const std::string &key, const T &default_value)
Definition: ros_parameter_handler.h:48
psen_scan_v2::ParamMissingOnServer
Exception thrown if a parameter of a certain type cannot be found on the ROS parameter server.
Definition: get_ros_parameter_exception.h:26


psen_scan_v2
Author(s): Pilz GmbH + Co. KG
autogenerated on Sat Jun 22 2024 02:46:11