Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,10 @@

#include <config_utilities/dynamic_config.h>
#include <config_utilities_msgs/srv/set_config.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/node_interfaces/get_node_base_interface.hpp>
#include <rclcpp/node_interfaces/get_node_parameters_interface.hpp>
#include <rclcpp/node_interfaces/get_node_services_interface.hpp>
#include <rclcpp/node_interfaces/get_node_topics_interface.hpp>
#include <std_msgs/msg/string.hpp>

namespace config {
Expand All @@ -50,23 +53,26 @@ namespace config {
*/
class RosDynamicConfigServer {
public:
explicit RosDynamicConfigServer(rclcpp::Node* node);
template <typename Node>
explicit RosDynamicConfigServer(Node&& node);

using Srv = config_utilities_msgs::srv::SetConfig;

private:
// Helper that manages the exposure of each config.
struct ConfigReceiver {
ConfigReceiver(const DynamicConfigServer::Key& key, RosDynamicConfigServer* server, rclcpp::Node* node);
ConfigReceiver(const DynamicConfigServer::Key& key, RosDynamicConfigServer* server);
const DynamicConfigServer::Key key;
RosDynamicConfigServer* const server;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub;
rclcpp::Service<Srv>::SharedPtr srv;
void handle_service(const std::shared_ptr<Srv::Request> request, std::shared_ptr<Srv::Response> response);
void handle_service(const std::shared_ptr<Srv::Request>& request, std::shared_ptr<Srv::Response> response);
};

// TODO(lschmid): Figure out if we can use smart pointers here. This should allow nice wrapping in the node.
rclcpp::Node* node_;
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base_;
std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface> node_topics_;
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> node_parameters_;
std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface> node_services_;
std::map<DynamicConfigServer::Key, std::unique_ptr<ConfigReceiver>> configs_;
DynamicConfigServer server_;

Expand All @@ -76,4 +82,23 @@ class RosDynamicConfigServer {
YAML::Node onSet(const DynamicConfigServer::Key& key, const YAML::Node& new_values);
};

template <typename Node>
RosDynamicConfigServer::RosDynamicConfigServer(Node&& node)
: node_base_(rclcpp::node_interfaces::get_node_base_interface(node)),
node_topics_(rclcpp::node_interfaces::get_node_topics_interface(node)),
node_parameters_(rclcpp::node_interfaces::get_node_parameters_interface(node)),
node_services_(rclcpp::node_interfaces::get_node_services_interface(node)) {
// Setup all currently registered configs.
for (const auto& key : server_.registeredConfigs()) {
onRegister(key);
}

// Register the hooks for the dynamic config server.
DynamicConfigServer::Hooks hooks;
hooks.onRegister = [this](const DynamicConfigServer::Key& key) { onRegister(key); };
hooks.onDeregister = [this](const DynamicConfigServer::Key& key) { onDeregister(key); };
hooks.onUpdate = [this](const DynamicConfigServer::Key& key, const YAML::Node& values) { onUpdate(key, values); };
server_.setHooks(hooks);
}

} // namespace config
38 changes: 16 additions & 22 deletions config_utilities_ros/src/ros_dynamic_config_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,40 +34,34 @@
* -------------------------------------------------------------------------- */
#include "config_utilities_ros/ros_dynamic_config_server.h"

#include <rclcpp/create_publisher.hpp>
#include <rclcpp/create_service.hpp>

namespace config {

RosDynamicConfigServer::ConfigReceiver::ConfigReceiver(const DynamicConfigServer::Key& key,
RosDynamicConfigServer* server,
rclcpp::Node* node)
RosDynamicConfigServer* server)
: key(key), server(server) {
const auto base_topic = "~/" + key;
const auto qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local();
pub = node->create_publisher<std_msgs::msg::String>("~/" + key + "/get", qos);
srv = node->create_service<Srv>(
"~/" + key + "/set",
std::bind(&ConfigReceiver::handle_service, this, std::placeholders::_1, std::placeholders::_2));
pub = rclcpp::create_publisher<std_msgs::msg::String>(
server->node_parameters_, server->node_topics_, base_topic + "/get", qos);
srv = rclcpp::create_service<Srv>(
server->node_base_,
server->node_services_,
base_topic + "/set",
std::bind(&ConfigReceiver::handle_service, this, std::placeholders::_1, std::placeholders::_2),
{},
nullptr);
}

void RosDynamicConfigServer::ConfigReceiver::handle_service(const std::shared_ptr<Srv::Request> request,
void RosDynamicConfigServer::ConfigReceiver::handle_service(const std::shared_ptr<Srv::Request>& request,
std::shared_ptr<Srv::Response> response) {
response->data = YAML::Dump(server->onSet(key, YAML::Load(request->data)));
}

RosDynamicConfigServer::RosDynamicConfigServer(rclcpp::Node* node) : node_(node) {
// Setup all currently registered configs.
for (const auto& key : server_.registeredConfigs()) {
onRegister(key);
}

// Register the hooks for the dynamic config server.
DynamicConfigServer::Hooks hooks;
hooks.onRegister = [this](const DynamicConfigServer::Key& key) { onRegister(key); };
hooks.onDeregister = [this](const DynamicConfigServer::Key& key) { onDeregister(key); };
hooks.onUpdate = [this](const DynamicConfigServer::Key& key, const YAML::Node& values) { onUpdate(key, values); };
server_.setHooks(hooks);
}

void RosDynamicConfigServer::onRegister(const DynamicConfigServer::Key& key) {
configs_.emplace(key, std::make_unique<ConfigReceiver>(key, this, node_));
configs_.emplace(key, std::make_unique<ConfigReceiver>(key, this));

// Latch the current state of the config.
onUpdate(key, server_.getInfo(key));
Expand Down