Split parameter.hpp into parameter_client.hpp

This commit is contained in:
Esteve Fernandez 2015-05-05 17:01:34 -07:00 committed by Esteve Fernandez
parent 198b40a0bf
commit 346f17aff0
3 changed files with 21 additions and 155 deletions

View file

@ -29,6 +29,9 @@
#include <rclcpp/subscription.hpp>
#include <rclcpp/timer.hpp>
#include <rcl_interfaces/SetParameters.h>
// Forward declaration of ROS middleware class
namespace rmw
{
@ -146,6 +149,20 @@ public:
FunctorT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
const std::vector<rcl_interfaces::SetParametersResult> set_parameters(
const std::vector<rcl_interfaces::Parameter> & parameters)
{
std::vector<rcl_interfaces::SetParametersResult> results;
for (auto p : parameters) {
// parameters_[p.name] = ParameterVariant::from_parameter_value(p.value);
rcl_interfaces::SetParametersResult result;
result.successful = true;
// TODO: handle parameter constraints
results.push_back(result);
}
return results;
}
private:
RCLCPP_DISABLE_COPY(Node);
@ -166,10 +183,9 @@ private:
size_t number_of_services_;
size_t number_of_clients_;
void register_service(
const std::string & service_name,
std::shared_ptr<rclcpp::service::ServiceBase> serv_base_ptr,
rclcpp::callback_group::CallbackGroup::SharedPtr group);
std::mutex mutex_;
// std::map<std::string, ParameterVariant> parameters_;
template<
typename ServiceT,

View file

@ -19,10 +19,6 @@
#include <rmw/rmw.h>
#include <rclcpp/executors.hpp>
#include <rclcpp/macros.hpp>
#include <rclcpp/node.hpp>
#include <rcl_interfaces/GetParameters.h>
#include <rcl_interfaces/GetParameterTypes.h>
#include <rcl_interfaces/Parameter.h>
@ -179,153 +175,6 @@ private:
rcl_interfaces::ParameterValue value_;
};
class AsyncParametersClient
{
public:
RCLCPP_MAKE_SHARED_DEFINITIONS(AsyncParametersClient);
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::SetParametersResult>>
set_parameters(
std::vector<ParameterVariant> parameters,
std::function<void(
std::shared_future<std::vector<rcl_interfaces::SetParametersResult>>)> callback = nullptr)
{
std::shared_future<std::vector<rcl_interfaces::SetParametersResult>> f;
return f;
}
std::shared_future<rcl_interfaces::SetParametersResult>
set_parameters_atomically(
std::vector<ParameterVariant> parameters,
std::function<void(
std::shared_future<rcl_interfaces::SetParametersResult>)> callback = nullptr)
{
std::shared_future<rcl_interfaces::SetParametersResult> f;
return f;
}
std::shared_future<rcl_interfaces::ListParametersResult>
list_parameters(
std::vector<std::string> parameter_prefixes,
uint64_t depth,
std::function<void(
std::shared_future<rcl_interfaces::ListParametersResult>)> callback = nullptr)
{
std::shared_future<rcl_interfaces::ListParametersResult> 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_;
};
class SyncParametersClient
{
public:
RCLCPP_MAKE_SHARED_DEFINITIONS(SyncParametersClient);
SyncParametersClient(
rclcpp::node::Node::SharedPtr & node)
: node_(node)
{
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
async_parameters_client_ = std::make_shared<AsyncParametersClient>(node);
}
SyncParametersClient(
rclcpp::executor::Executor::SharedPtr & executor,
rclcpp::node::Node::SharedPtr & node)
: executor_(executor), node_(node)
{
async_parameters_client_ = std::make_shared<AsyncParametersClient>(node);
}
std::vector<ParameterVariant>
get_parameters(std::vector<std::string> parameter_names)
{
auto f = async_parameters_client_->get_parameters(parameter_names);
return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
}
std::vector<ParameterType>
get_parameter_types(std::vector<std::string> parameter_names)
{
auto f = async_parameters_client_->get_parameter_types(parameter_names);
return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
}
std::vector<rcl_interfaces::SetParametersResult>
set_parameters(std::vector<ParameterVariant> parameters)
{
auto f = async_parameters_client_->set_parameters(parameters);
return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
}
rcl_interfaces::SetParametersResult
set_parameters_atomically(std::vector<ParameterVariant> parameters)
{
auto f = async_parameters_client_->set_parameters_atomically(parameters);
return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
}
rcl_interfaces::ListParametersResult
list_parameters(
std::vector<std::string> parameter_prefixes,
uint64_t depth)
{
auto f = async_parameters_client_->list_parameters(parameter_prefixes, depth);
return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
}
private:
rclcpp::executor::Executor::SharedPtr executor_;
rclcpp::node::Node::SharedPtr node_;
AsyncParametersClient::SharedPtr async_parameters_client_;
};
} /* namespace parameter */
} /* namespace rclcpp */

View file

@ -20,6 +20,7 @@
#include <rclcpp/node.hpp>
#include <rclcpp/parameter.hpp>
#include <rclcpp/parameter_client.hpp>
#include <rclcpp/executors.hpp>
#include <rclcpp/rate.hpp>
#include <rclcpp/utilities.hpp>