Merge pull request #26 from ros2/parameters-api-review
Skeleton parameters async API
This commit is contained in:
commit
f4bcd83c42
4 changed files with 245 additions and 0 deletions
|
@ -5,6 +5,7 @@ project(rclcpp)
|
||||||
find_package(ament_cmake REQUIRED)
|
find_package(ament_cmake REQUIRED)
|
||||||
|
|
||||||
ament_export_dependencies(rmw)
|
ament_export_dependencies(rmw)
|
||||||
|
ament_export_dependencies(rcl_interfaces)
|
||||||
|
|
||||||
ament_export_include_directories(include)
|
ament_export_include_directories(include)
|
||||||
|
|
||||||
|
|
240
rclcpp/include/rclcpp/parameter.hpp
Normal file
240
rclcpp/include/rclcpp/parameter.hpp
Normal file
|
@ -0,0 +1,240 @@
|
||||||
|
// Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#ifndef RCLCPP_RCLCPP_PARAMETER_HPP_
|
||||||
|
#define RCLCPP_RCLCPP_PARAMETER_HPP_
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#include <rmw/rmw.h>
|
||||||
|
|
||||||
|
#include <rclcpp/macros.hpp>
|
||||||
|
#include <rclcpp/node.hpp>
|
||||||
|
|
||||||
|
#include <rcl_interfaces/GetParameters.h>
|
||||||
|
#include <rcl_interfaces/GetParameterTypes.h>
|
||||||
|
#include <rcl_interfaces/Parameter.h>
|
||||||
|
#include <rcl_interfaces/ParameterDescriptor.h>
|
||||||
|
#include <rcl_interfaces/ParameterType.h>
|
||||||
|
#include <rcl_interfaces/SetParameters.h>
|
||||||
|
#include <rcl_interfaces/SetParametersAtomically.h>
|
||||||
|
#include <rcl_interfaces/ListParameters.h>
|
||||||
|
#include <rcl_interfaces/DescribeParameters.h>
|
||||||
|
|
||||||
|
namespace rclcpp
|
||||||
|
{
|
||||||
|
|
||||||
|
namespace parameter
|
||||||
|
{
|
||||||
|
|
||||||
|
enum ParameterType {
|
||||||
|
PARAMETER_NOT_SET=rcl_interfaces::ParameterType::PARAMETER_NOT_SET,
|
||||||
|
PARAMETER_BOOL=rcl_interfaces::ParameterType::PARAMETER_BOOL,
|
||||||
|
PARAMETER_INTEGER=rcl_interfaces::ParameterType::PARAMETER_INTEGER,
|
||||||
|
PARAMETER_DOUBLE=rcl_interfaces::ParameterType::PARAMETER_DOUBLE,
|
||||||
|
PARAMETER_STRING=rcl_interfaces::ParameterType::PARAMETER_STRING,
|
||||||
|
PARAMETER_BYTES=rcl_interfaces::ParameterType::PARAMETER_BYTES,
|
||||||
|
};
|
||||||
|
|
||||||
|
// Structure to store an arbitrary parameter with templated get/set methods
|
||||||
|
class ParameterVariant
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
ParameterVariant()
|
||||||
|
: name_("")
|
||||||
|
{
|
||||||
|
value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_NOT_SET;
|
||||||
|
}
|
||||||
|
ParameterVariant(const std::string & name, const bool bool_value)
|
||||||
|
: name_(name)
|
||||||
|
{
|
||||||
|
value_.bool_value = bool_value;
|
||||||
|
value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_BOOL;
|
||||||
|
}
|
||||||
|
ParameterVariant(const std::string & name, const int64_t int_value)
|
||||||
|
: name_(name)
|
||||||
|
{
|
||||||
|
value_.integer_value = int_value;
|
||||||
|
value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_INTEGER;
|
||||||
|
}
|
||||||
|
ParameterVariant(const std::string & name, const double double_value)
|
||||||
|
: name_(name)
|
||||||
|
{
|
||||||
|
value_.double_value = double_value;
|
||||||
|
value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_DOUBLE;
|
||||||
|
}
|
||||||
|
ParameterVariant(const std::string & name, const std::string & string_value)
|
||||||
|
: name_(name)
|
||||||
|
{
|
||||||
|
value_.string_value = string_value;
|
||||||
|
value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_STRING;
|
||||||
|
}
|
||||||
|
ParameterVariant(const std::string & name, const std::vector<int8_t> & bytes_value)
|
||||||
|
: name_(name)
|
||||||
|
{
|
||||||
|
value_.bytes_value = bytes_value;
|
||||||
|
value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_BYTES;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Templated getter */
|
||||||
|
template<typename T>
|
||||||
|
T
|
||||||
|
get_value() const;
|
||||||
|
|
||||||
|
inline ParameterType get_type() const {return static_cast<ParameterType>(value_.parameter_type); }
|
||||||
|
|
||||||
|
inline std::string get_name() const & {return name_; }
|
||||||
|
|
||||||
|
inline rcl_interfaces::ParameterValue get_parameter_value() const
|
||||||
|
{
|
||||||
|
return value_;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
std::string name_;
|
||||||
|
rcl_interfaces::ParameterValue value_;
|
||||||
|
};
|
||||||
|
|
||||||
|
template<>
|
||||||
|
inline int64_t ParameterVariant::get_value() const
|
||||||
|
{
|
||||||
|
if (value_.parameter_type != rcl_interfaces::ParameterType::PARAMETER_INTEGER) {
|
||||||
|
// TODO: use custom exception
|
||||||
|
throw std::runtime_error("Invalid type");
|
||||||
|
}
|
||||||
|
return value_.integer_value;
|
||||||
|
}
|
||||||
|
template<>
|
||||||
|
inline double ParameterVariant::get_value() const
|
||||||
|
{
|
||||||
|
if (value_.parameter_type != rcl_interfaces::ParameterType::PARAMETER_DOUBLE) {
|
||||||
|
// TODO: use custom exception
|
||||||
|
throw std::runtime_error("Invalid type");
|
||||||
|
}
|
||||||
|
return value_.double_value;
|
||||||
|
}
|
||||||
|
template<>
|
||||||
|
inline std::string ParameterVariant::get_value() const
|
||||||
|
{
|
||||||
|
if (value_.parameter_type != rcl_interfaces::ParameterType::PARAMETER_STRING) {
|
||||||
|
// TODO: use custom exception
|
||||||
|
throw std::runtime_error("Invalid type");
|
||||||
|
}
|
||||||
|
return value_.string_value;
|
||||||
|
}
|
||||||
|
template<>
|
||||||
|
inline bool ParameterVariant::get_value() const
|
||||||
|
{
|
||||||
|
if (value_.parameter_type != rcl_interfaces::ParameterType::PARAMETER_BOOL) {
|
||||||
|
// TODO: use custom exception
|
||||||
|
throw std::runtime_error("Invalid type");
|
||||||
|
}
|
||||||
|
return value_.bool_value;
|
||||||
|
}
|
||||||
|
template<>
|
||||||
|
inline std::vector<int8_t> ParameterVariant::get_value() const
|
||||||
|
{
|
||||||
|
if (value_.parameter_type != rcl_interfaces::ParameterType::PARAMETER_BYTES) {
|
||||||
|
// TODO: use custom exception
|
||||||
|
throw std::runtime_error("Invalid type");
|
||||||
|
}
|
||||||
|
return value_.bytes_value;
|
||||||
|
}
|
||||||
|
|
||||||
|
class AsyncParametersClient
|
||||||
|
{
|
||||||
|
|
||||||
|
public:
|
||||||
|
AsyncParametersClient(const rclcpp::node::Node::SharedPtr & node)
|
||||||
|
: node_(node)
|
||||||
|
{
|
||||||
|
get_parameters_client_ = node_->create_client<rcl_interfaces::GetParameters>(
|
||||||
|
"get_parameters");
|
||||||
|
get_parameter_types_client_ = node_->create_client<rcl_interfaces::GetParameterTypes>(
|
||||||
|
"get_parameter_types");
|
||||||
|
set_parameters_client_ = node_->create_client<rcl_interfaces::SetParameters>(
|
||||||
|
"set_parameters");
|
||||||
|
list_parameters_client_ = node_->create_client<rcl_interfaces::ListParameters>(
|
||||||
|
"list_parameters");
|
||||||
|
describe_parameters_client_ = node_->create_client<rcl_interfaces::DescribeParameters>(
|
||||||
|
"describe_parameters");
|
||||||
|
}
|
||||||
|
|
||||||
|
std::shared_future<std::vector<ParameterVariant>>
|
||||||
|
get_parameters(
|
||||||
|
std::vector<std::string> names,
|
||||||
|
std::function<void(
|
||||||
|
std::shared_future<std::vector<ParameterVariant>>)> callback = nullptr)
|
||||||
|
{
|
||||||
|
std::shared_future<std::vector<ParameterVariant>> f;
|
||||||
|
return f;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::shared_future<std::vector<ParameterType>>
|
||||||
|
get_parameter_types(
|
||||||
|
std::vector<std::string> parameter_names,
|
||||||
|
std::function<void(
|
||||||
|
std::shared_future<std::vector<ParameterType>>)> callback = nullptr)
|
||||||
|
{
|
||||||
|
std::shared_future<std::vector<ParameterType>> f;
|
||||||
|
return f;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::shared_future<std::vector<rcl_interfaces::ParameterSetResult>>
|
||||||
|
set_parameters(
|
||||||
|
std::vector<ParameterVariant> parameters,
|
||||||
|
std::function<void(
|
||||||
|
std::shared_future<std::vector<rcl_interfaces::ParameterSetResult>>)> callback = nullptr)
|
||||||
|
{
|
||||||
|
std::shared_future<std::vector<rcl_interfaces::ParameterSetResult>> f;
|
||||||
|
return f;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::shared_future<rcl_interfaces::ParameterSetResult>
|
||||||
|
set_parameters_atomically(
|
||||||
|
std::vector<ParameterVariant> parameters,
|
||||||
|
std::function<void(
|
||||||
|
std::shared_future<rcl_interfaces::ParameterSetResult>)> callback = nullptr)
|
||||||
|
{
|
||||||
|
std::shared_future<rcl_interfaces::ParameterSetResult> f;
|
||||||
|
return f;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::shared_future<rcl_interfaces::ParameterListResult>
|
||||||
|
list_parameters(
|
||||||
|
std::vector<std::string> parameter_prefixes,
|
||||||
|
uint64_t depth,
|
||||||
|
std::function<void(
|
||||||
|
std::shared_future<rcl_interfaces::ParameterListResult>)> callback = nullptr)
|
||||||
|
{
|
||||||
|
std::shared_future<rcl_interfaces::ParameterListResult> f;
|
||||||
|
return f;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
const rclcpp::node::Node::SharedPtr node_;
|
||||||
|
rclcpp::client::Client<rcl_interfaces::GetParameters>::SharedPtr get_parameters_client_;
|
||||||
|
rclcpp::client::Client<rcl_interfaces::GetParameterTypes>::SharedPtr get_parameter_types_client_;
|
||||||
|
rclcpp::client::Client<rcl_interfaces::SetParameters>::SharedPtr set_parameters_client_;
|
||||||
|
rclcpp::client::Client<rcl_interfaces::SetParametersAtomically>::SharedPtr
|
||||||
|
set_parameters_atomically_client_;
|
||||||
|
rclcpp::client::Client<rcl_interfaces::ListParameters>::SharedPtr list_parameters_client_;
|
||||||
|
rclcpp::client::Client<rcl_interfaces::DescribeParameters>::SharedPtr describe_parameters_client_;
|
||||||
|
};
|
||||||
|
|
||||||
|
} /* namespace parameter */
|
||||||
|
|
||||||
|
} /* namespace rclcpp */
|
||||||
|
|
||||||
|
#endif /* RCLCPP_RCLCPP_PARAMETER_HPP_ */
|
|
@ -19,6 +19,7 @@
|
||||||
#include <memory>
|
#include <memory>
|
||||||
|
|
||||||
#include <rclcpp/node.hpp>
|
#include <rclcpp/node.hpp>
|
||||||
|
#include <rclcpp/parameter.hpp>
|
||||||
#include <rclcpp/executors.hpp>
|
#include <rclcpp/executors.hpp>
|
||||||
#include <rclcpp/rate.hpp>
|
#include <rclcpp/rate.hpp>
|
||||||
#include <rclcpp/utilities.hpp>
|
#include <rclcpp/utilities.hpp>
|
||||||
|
|
|
@ -10,6 +10,9 @@
|
||||||
|
|
||||||
<build_export_depend>rmw</build_export_depend>
|
<build_export_depend>rmw</build_export_depend>
|
||||||
|
|
||||||
|
<build_depend>rcl_interfaces</build_depend>
|
||||||
|
<build_export_depend>rcl_interfaces</build_export_depend>
|
||||||
|
|
||||||
<test_depend>ament_lint_auto</test_depend>
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
<test_depend>ament_lint_common</test_depend>
|
<test_depend>ament_lint_common</test_depend>
|
||||||
</package>
|
</package>
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue