add parameter helpers (redo of #233) (#237)

* add parameter helpers

* respond to comments

* remove unnecessary indent comments

* replace temp variable assignment with explicit constructor invocation
This commit is contained in:
gerkey 2016-07-08 15:45:05 -07:00 committed by GitHub
parent ea76716982
commit fc0d539837
3 changed files with 92 additions and 2 deletions

View file

@ -80,6 +80,8 @@ public:
rcl_interfaces::msg::ParameterValue
get_parameter_value() const;
// The following get_value() variants require the use of ParameterType
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_INTEGER, int64_t>::type
get_value() const
@ -125,8 +127,8 @@ public:
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_BYTES,
const std::vector<uint8_t> &>::type
typename std::enable_if<
type == ParameterType::PARAMETER_BYTES, const std::vector<uint8_t> &>::type
get_value() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BYTES) {
@ -136,6 +138,46 @@ public:
return value_.bytes_value;
}
// The following get_value() variants allow the use of primitive types
template<typename type>
typename std::enable_if<
std::is_integral<type>::value && !std::is_same<type, bool>::value, int64_t>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_INTEGER>();
}
template<typename type>
typename std::enable_if<std::is_floating_point<type>::value, double>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_DOUBLE>();
}
template<typename type>
typename std::enable_if<std::is_convertible<type, std::string>::value, const std::string &>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_STRING>();
}
template<typename type>
typename std::enable_if<std::is_same<type, bool>::value, bool>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_BOOL>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<uint8_t> &>::value, const std::vector<uint8_t> &>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_BYTES>();
}
RCLCPP_PUBLIC
int64_t
as_int() const;

View file

@ -134,6 +134,45 @@ public:
std::vector<rclcpp::parameter::ParameterVariant>
get_parameters(const std::vector<std::string> & parameter_names);
RCLCPP_PUBLIC
bool
has_parameter(const std::string & parameter_name);
template<typename T>
T
get_parameter_impl(
const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
{
std::vector<std::string> names;
names.push_back(parameter_name);
auto vars = get_parameters(names);
if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::parameter::PARAMETER_NOT_SET)) {
return parameter_not_found_handler();
} else {
return static_cast<T>(vars[0].get_value<T>());
}
}
template<typename T>
T
get_parameter(const std::string & parameter_name, const T & default_value)
{
// *INDENT-OFF*
return get_parameter_impl(parameter_name,
std::function<T()>([&default_value]() -> T {return default_value; }));
// *INDENT-ON*
}
template<typename T>
T
get_parameter(const std::string & parameter_name)
{
// *INDENT-OFF*
return get_parameter_impl(parameter_name,
std::function<T()>([]() -> T {throw std::runtime_error("Parameter not set"); }));
// *INDENT-ON*
}
RCLCPP_PUBLIC
std::vector<rclcpp::parameter::ParameterType>
get_parameter_types(const std::vector<std::string> & parameter_names);

View file

@ -259,6 +259,15 @@ SyncParametersClient::get_parameters(const std::vector<std::string> & parameter_
return std::vector<rclcpp::parameter::ParameterVariant>();
}
bool
SyncParametersClient::has_parameter(const std::string & parameter_name)
{
std::vector<std::string> names;
names.push_back(parameter_name);
auto vars = list_parameters(names, 1);
return vars.names.size() > 0;
}
std::vector<rclcpp::parameter::ParameterType>
SyncParametersClient::get_parameter_types(const std::vector<std::string> & parameter_names)
{