1#include "modulo_controllers/BaseControllerInterface.hpp"
3#include <lifecycle_msgs/msg/state.hpp>
5#include <modulo_core/translators/message_readers.hpp>
8struct overloaded : Ts... {
9 using Ts::operator()...;
12overloaded(Ts...) -> overloaded<Ts...>;
15using namespace state_representation;
16using namespace std::chrono_literals;
18namespace modulo_controllers {
21 : controller_interface::
ControllerInterface(), input_validity_period_(std::numeric_limits<double>::quiet_NaN()) {}
26 pre_set_parameter_cb_handle_ = get_node()->add_pre_set_parameters_callback(
27 [
this](std::vector<rclcpp::Parameter>& parameters) {
return this->pre_set_parameters_callback(parameters); });
28 on_set_parameter_cb_handle_ = get_node()->add_on_set_parameters_callback(
29 [
this](
const std::vector<rclcpp::Parameter>& parameters) -> rcl_interfaces::msg::SetParametersResult {
30 return this->on_set_parameters_callback(parameters);
34 parameter_map_.set_parameter(std::make_shared<Parameter<int>>(
"update_rate"));
35 read_only_parameters_.insert_or_assign(
"update_rate",
false);
36 parameter_map_.set_parameter(std::make_shared<Parameter<bool>>(
"is_async",
false));
37 read_only_parameters_.insert_or_assign(
"is_async",
false);
39 add_parameter<double>(
"predicate_publishing_rate", 10.0,
"The rate at which to publish controller predicates");
41 "input_validity_period", 1.0,
"The maximum age of an input state before discarding it as expired");
42 return CallbackReturn::SUCCESS;
45rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
51 if (predicates_.size()) {
52 predicate_publisher_ =
53 get_node()->create_publisher<modulo_interfaces::msg::PredicateCollection>(
"/predicates", qos_);
54 predicate_message_.node = get_node()->get_fully_qualified_name();
55 predicate_message_.type = modulo_interfaces::msg::PredicateCollection::CONTROLLER;
57 predicate_timer_ = get_node()->create_wall_timer(
59 [
this]() { this->publish_predicates(); });
62 RCLCPP_DEBUG(get_node()->get_logger(),
"Configuration of BaseControllerInterface successful");
63 return CallbackReturn::SUCCESS;
67 const std::shared_ptr<ParameterInterface>& parameter,
const std::string& description,
bool read_only) {
68 rclcpp::Parameter ros_param;
74 if (!get_node()->has_parameter(parameter->get_name())) {
75 RCLCPP_DEBUG(get_node()->get_logger(),
"Adding parameter '%s'.", parameter->get_name().c_str());
76 parameter_map_.set_parameter(parameter);
77 read_only_parameters_.insert_or_assign(parameter->get_name(),
false);
79 rcl_interfaces::msg::ParameterDescriptor descriptor;
80 descriptor.description = description;
81 descriptor.read_only = read_only;
83 set_parameters_result_.successful =
true;
84 set_parameters_result_.reason =
"";
85 if (parameter->is_empty()) {
86 descriptor.dynamic_typing =
true;
88 get_node()->declare_parameter(parameter->get_name(), rclcpp::ParameterValue{}, descriptor);
90 get_node()->declare_parameter(parameter->get_name(), ros_param.get_parameter_value(), descriptor);
92 std::vector<rclcpp::Parameter> ros_parameters{get_node()->get_parameters({parameter->get_name()})};
93 pre_set_parameters_callback(ros_parameters);
94 auto result = on_set_parameters_callback(ros_parameters);
95 if (!result.successful) {
96 get_node()->undeclare_parameter(parameter->get_name());
99 read_only_parameters_.at(parameter->get_name()) = read_only;
100 }
catch (
const std::exception& ex) {
101 parameter_map_.remove_parameter(parameter->get_name());
102 read_only_parameters_.erase(parameter->get_name());
106 RCLCPP_DEBUG(get_node()->get_logger(),
"Parameter '%s' already exists.", parameter->get_name().c_str());
112 return parameter_map_.get_parameter(name);
113 }
catch (
const state_representation::exceptions::InvalidParameterException& ex) {
118void BaseControllerInterface::pre_set_parameters_callback(std::vector<rclcpp::Parameter>& parameters) {
119 if (pre_set_parameter_callback_called_) {
120 pre_set_parameter_callback_called_ =
false;
123 rcl_interfaces::msg::SetParametersResult result;
124 result.successful =
true;
125 for (
auto& ros_parameter : parameters) {
127 auto parameter = parameter_map_.get_parameter(ros_parameter.get_name());
128 if (read_only_parameters_.at(ros_parameter.get_name())) {
129 RCLCPP_DEBUG(get_node()->get_logger(),
"Parameter '%s' is read only.", ros_parameter.get_name().c_str());
135 if (!this->validate_parameter(new_parameter)) {
136 result.successful =
false;
137 result.reason +=
"Validation of parameter '" + ros_parameter.get_name() +
"' returned false!";
138 }
else if (!new_parameter->is_empty()) {
143 }
catch (
const std::exception& ex) {
144 result.successful =
false;
145 result.reason += ex.what();
148 set_parameters_result_ = result;
151rcl_interfaces::msg::SetParametersResult
152BaseControllerInterface::on_set_parameters_callback(
const std::vector<rclcpp::Parameter>&) {
153 auto result = set_parameters_result_;
154 set_parameters_result_.successful =
true;
155 set_parameters_result_.reason =
"";
159bool BaseControllerInterface::validate_parameter(
const std::shared_ptr<ParameterInterface>& parameter) {
160 if (parameter->get_name() ==
"predicate_publishing_rate" || parameter->get_name() ==
"input_validity_period") {
161 auto value = parameter->get_parameter_value<
double>();
162 if (value < 0.0 || value > std::numeric_limits<double>::max()) {
164 get_node()->get_logger(),
"Parameter value of parameter '%s' should be a positive finite number",
165 parameter->get_name().c_str());
177 add_predicate(predicate_name, [predicate_value]() {
return predicate_value; });
181 const std::string& predicate_name,
const std::function<
bool(
void)>& predicate_function) {
182 if (predicate_name.empty()) {
183 RCLCPP_ERROR(get_node()->get_logger(),
"Failed to add predicate: Provide a non empty string as a name.");
186 if (predicates_.find(predicate_name) != predicates_.end()) {
188 get_node()->get_logger(),
"Predicate with name '%s' already exists, overwriting.", predicate_name.c_str());
190 RCLCPP_DEBUG(get_node()->get_logger(),
"Adding predicate '%s'.", predicate_name.c_str());
193 this->predicates_.insert_or_assign(predicate_name,
Predicate(predicate_function));
194 }
catch (
const std::exception& ex) {
196 get_node()->get_logger(),
"Failed to evaluate callback of predicate '%s', returning false: %s",
197 predicate_name.c_str(), ex.what());
202 auto predicate_it = predicates_.find(predicate_name);
203 if (predicate_it == predicates_.end()) {
204 RCLCPP_ERROR_THROTTLE(
205 get_node()->get_logger(), *get_node()->get_clock(), 1000,
206 "Failed to get predicate '%s': Predicate does not exists, returning false.", predicate_name.c_str());
210 return predicate_it->second.get_value();
211 }
catch (
const std::exception& ex) {
212 RCLCPP_ERROR_THROTTLE(
213 get_node()->get_logger(), *get_node()->get_clock(), 1000,
214 "Failed to evaluate callback of predicate '%s', returning false: %s", predicate_name.c_str(), ex.what());
220 set_predicate(predicate_name, [predicate_value]() {
return predicate_value; });
224 const std::string& predicate_name,
const std::function<
bool(
void)>& predicate_function) {
225 auto predicate_it = predicates_.find(predicate_name);
226 if (predicate_it == predicates_.end()) {
227 RCLCPP_ERROR_THROTTLE(
228 get_node()->get_logger(), *get_node()->get_clock(), 1000,
229 "Failed to set predicate '%s': Predicate does not exist.", predicate_name.c_str());
232 predicate_it->second.set_predicate(predicate_function);
233 if (
auto new_predicate = predicate_it->second.query(); new_predicate) {
234 publish_predicate(predicate_name, *new_predicate);
239 if (trigger_name.empty()) {
240 RCLCPP_ERROR(get_node()->get_logger(),
"Failed to add trigger: Provide a non empty string as a name.");
243 if (std::find(triggers_.cbegin(), triggers_.cend(), trigger_name) != triggers_.cend()) {
245 get_node()->get_logger(),
"Failed to add trigger: there is already a trigger with name '%s'.",
246 trigger_name.c_str());
249 if (predicates_.find(trigger_name) != predicates_.end()) {
251 get_node()->get_logger(),
"Failed to add trigger: there is already a predicate with name '%s'.",
252 trigger_name.c_str());
255 triggers_.push_back(trigger_name);
260 if (std::find(triggers_.cbegin(), triggers_.cend(), trigger_name) == triggers_.cend()) {
262 get_node()->get_logger(),
"Failed to trigger: could not find trigger with name '%s'.", trigger_name.c_str());
267 predicates_.at(trigger_name).set_predicate([]() {
return false; });
270modulo_interfaces::msg::Predicate
271BaseControllerInterface::get_predicate_message(
const std::string& name,
bool value)
const {
272 modulo_interfaces::msg::Predicate message;
273 message.predicate = name;
274 message.value = value;
278void BaseControllerInterface::publish_predicate(
const std::string& predicate_name,
bool value)
const {
279 auto message(predicate_message_);
280 message.predicates.push_back(get_predicate_message(predicate_name, value));
281 predicate_publisher_->publish(message);
284void BaseControllerInterface::publish_predicates() {
285 auto message(predicate_message_);
286 for (
auto predicate_it = predicates_.begin(); predicate_it != predicates_.end(); ++predicate_it) {
287 if (
auto new_predicate = predicate_it->second.query(); new_predicate) {
288 message.predicates.push_back(get_predicate_message(predicate_it->first, *new_predicate));
291 if (message.predicates.size()) {
292 predicate_publisher_->publish(message);
296std::string BaseControllerInterface::validate_and_declare_signal(
297 const std::string& signal_name,
const std::string& type,
const std::string& default_topic,
bool fixed_topic) {
298 auto parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
299 if (parsed_signal_name.empty()) {
301 get_node()->get_logger(),
302 "The parsed signal name for %s '%s' is empty. Provide a string with valid characters for the signal name "
304 type.c_str(), signal_name.c_str());
307 if (signal_name != parsed_signal_name) {
309 get_node()->get_logger(),
310 "The parsed signal name for %s '%s' is '%s'. Use the parsed signal name to refer to this %s and its topic "
312 type.c_str(), signal_name.c_str(), parsed_signal_name.c_str(), type.c_str());
314 if (inputs_.find(parsed_signal_name) != inputs_.end()) {
315 RCLCPP_WARN(get_node()->get_logger(),
"Signal '%s' already exists as input.", parsed_signal_name.c_str());
318 if (outputs_.find(parsed_signal_name) != outputs_.end()) {
319 RCLCPP_WARN(get_node()->get_logger(),
"Signal '%s' already exists as output", parsed_signal_name.c_str());
322 auto topic = default_topic.empty() ?
"~/" + parsed_signal_name : default_topic;
323 auto parameter_name = parsed_signal_name +
"_topic";
324 if (get_node()->has_parameter(parameter_name) &&
get_parameter(parameter_name)->is_empty()) {
328 parameter_name, topic,
"Signal topic name of " + type +
" '" + parsed_signal_name +
"'", fixed_topic);
331 get_node()->get_logger(),
"Declared %s '%s' and parameter '%s' with value '%s'.", type.c_str(),
332 parsed_signal_name.c_str(), parameter_name.c_str(), topic.c_str());
333 return parsed_signal_name;
336void BaseControllerInterface::create_input(
337 const ControllerInput& input,
const std::string& name,
const std::string& topic_name) {
338 auto parsed_name = validate_and_declare_signal(name,
"input", topic_name);
339 if (!parsed_name.empty()) {
340 inputs_.insert_or_assign(parsed_name, input);
344void BaseControllerInterface::add_inputs() {
345 for (
auto& [name, input] : inputs_) {
350 [&](
const realtime_tools::RealtimeBuffer<std::shared_ptr<EncodedState>>&) {
351 subscriptions_.push_back(create_subscription<EncodedState>(name, topic));
353 [&](
const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>&) {
354 subscriptions_.push_back(create_subscription<std_msgs::msg::Bool>(name, topic));
356 [&](
const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>&) {
357 subscriptions_.push_back(create_subscription<std_msgs::msg::Float64>(name, topic));
359 [&](
const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>&) {
360 subscriptions_.push_back(create_subscription<std_msgs::msg::Float64MultiArray>(name, topic));
362 [&](
const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>&) {
363 subscriptions_.push_back(create_subscription<std_msgs::msg::Int32>(name, topic));
365 [&](
const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>&) {
366 subscriptions_.push_back(create_subscription<std_msgs::msg::String>(name, topic));
368 [&](
const std::any&) {
369 custom_input_configuration_callables_.at(name)(name, topic);
372 }
catch (
const std::exception& ex) {
373 RCLCPP_ERROR(get_node()->get_logger(),
"Failed to add input '%s': %s", name.c_str(), ex.what());
378void BaseControllerInterface::create_output(
379 const PublisherVariant& publishers,
const std::string& name,
const std::string& topic_name) {
380 auto parsed_name = validate_and_declare_signal(name,
"output", topic_name);
381 if (!parsed_name.empty()) {
382 outputs_.insert_or_assign(parsed_name, publishers);
386void BaseControllerInterface::add_outputs() {
387 for (
auto& [name, publishers] : outputs_) {
392 [&](EncodedStatePublishers& pub) {
393 std::get<1>(pub) = get_node()->create_publisher<EncodedState>(topic, qos_);
394 std::get<2>(pub) = std::make_shared<realtime_tools::RealtimePublisher<EncodedState>>(std::get<1>(pub));
396 [&](BoolPublishers& pub) {
397 pub.first = get_node()->create_publisher<std_msgs::msg::Bool>(topic, qos_);
398 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Bool>>(pub.first);
400 [&](DoublePublishers& pub) {
401 pub.first = get_node()->create_publisher<std_msgs::msg::Float64>(topic, qos_);
402 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Float64>>(pub.first);
404 [&](DoubleVecPublishers& pub) {
405 pub.first = get_node()->create_publisher<std_msgs::msg::Float64MultiArray>(topic, qos_);
407 std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Float64MultiArray>>(pub.first);
409 [&](IntPublishers& pub) {
410 pub.first = get_node()->create_publisher<std_msgs::msg::Int32>(topic, qos_);
411 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Int32>>(pub.first);
413 [&](StringPublishers& pub) {
414 pub.first = get_node()->create_publisher<std_msgs::msg::String>(topic, qos_);
415 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::String>>(pub.first);
417 [&](CustomPublishers& pub) {
418 custom_output_configuration_callables_.at(name)(pub, name);
421 }
catch (
const std::bad_any_cast& ex) {
422 RCLCPP_ERROR(get_node()->get_logger(),
"Failed to add custom output '%s': %s", name.c_str(), ex.what());
423 }
catch (
const std::exception& ex) {
424 RCLCPP_ERROR(get_node()->get_logger(),
"Failed to add output '%s': %s", name.c_str(), ex.what());
430 input_validity_period_ = input_validity_period;
433bool BaseControllerInterface::check_input_valid(
const std::string& name)
const {
434 if (inputs_.find(name) == inputs_.end()) {
435 RCLCPP_WARN_THROTTLE(
436 get_node()->get_logger(), *get_node()->get_clock(), 1000,
"Could not find input '%s'", name.c_str());
439 if (
static_cast<double>(std::chrono::duration_cast<std::chrono::nanoseconds>(
440 std::chrono::steady_clock::now() - inputs_.at(name).timestamp)
443 >= input_validity_period_) {
450BaseControllerInterface::validate_service_name(
const std::string& service_name,
const std::string& type)
const {
451 std::string parsed_service_name = modulo_utils::parsing::parse_topic_name(service_name);
452 if (parsed_service_name.empty()) {
454 get_node()->get_logger(),
455 "The parsed service name for %s service '%s' is empty. Provide a string with valid characters for the service "
458 type.c_str(), service_name.c_str());
461 if (service_name != parsed_service_name) {
463 get_node()->get_logger(),
464 "The parsed name for '%s' service '%s' is '%s'. Use the parsed name to refer to this service.", type.c_str(),
465 service_name.c_str(), parsed_service_name.c_str());
467 if (empty_services_.find(parsed_service_name) != empty_services_.cend()) {
469 get_node()->get_logger(),
"Service with name '%s' already exists as empty service.",
470 parsed_service_name.c_str());
473 if (string_services_.find(parsed_service_name) != string_services_.cend()) {
475 get_node()->get_logger(),
"Service with name '%s' already exists as string service.",
476 parsed_service_name.c_str());
479 RCLCPP_DEBUG(get_node()->get_logger(),
"Adding %s service '%s'.", type.c_str(), parsed_service_name.c_str());
480 return parsed_service_name;
485 this->create_service<true>(service_name, callback);
489 const std::string& service_name,
491 this->create_service<true>(service_name, callback);
496 this->create_service<false>(service_name, callback);
500 const std::string& service_name,
502 this->create_service<false>(service_name, callback);
514 return get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE;
518 return command_mutex_;
std::shared_ptr< state_representation::ParameterInterface > get_parameter(const std::string &name) const
Get a parameter by name.
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
Add signals.
rclcpp::QoS get_qos() const
Getter of the Quality of Service attribute.
void add_service_lockfree(const std::string &service_name, const std::function< ControllerServiceResponse(void)> &callback)
bool is_active() const
Check if the controller is currently in state active or not.
void set_parameter_value(const std::string &name, const T &value)
Set the value of a parameter.
T get_parameter_value(const std::string &name) const
Get a parameter value by name.
void set_input_validity_period(double input_validity_period)
Set the input validity period of input signals.
CallbackReturn on_init() override
Declare parameters and register the on_set_parameters callback.
void add_parameter(const std::shared_ptr< state_representation::ParameterInterface > ¶meter, const std::string &description, bool read_only=false)
Add a parameter.
void trigger(const std::string &trigger_name)
Latch the trigger with the provided name.
void set_qos(const rclcpp::QoS &qos)
Set the Quality of Service for ROS publishers and subscribers.
void set_predicate(const std::string &predicate_name, bool predicate_value)
Set the value of the predicate given as parameter, if the predicate is not found does not do anything...
void add_predicate(const std::string &predicate_name, bool predicate_value)
Add a predicate to the map of predicates.
bool get_predicate(const std::string &predicate_name) const
Get the logical value of a predicate.
virtual bool on_validate_parameter_callback(const std::shared_ptr< state_representation::ParameterInterface > ¶meter)
Parameter validation function to be redefined by derived controller classes.
BaseControllerInterface()
Default constructor.
void add_service(const std::string &service_name, const std::function< ControllerServiceResponse(void)> &callback)
Add a service to trigger a callback function with no input arguments.
std::timed_mutex & get_command_mutex()
Get the reference to the command mutex.
void add_trigger(const std::string &trigger_name)
Add a trigger to the controller.
An exception class to notify errors with parameters in modulo classes.
An exception class to notify incompatibility when translating parameters from different sources.
rclcpp::Parameter write_parameter(const std::shared_ptr< state_representation::ParameterInterface > ¶meter)
Write a ROS Parameter from a ParameterInterface pointer.
rclcpp::ParameterType get_ros_parameter_type(const state_representation::ParameterType ¶meter_type)
Given a state representation parameter type, get the corresponding ROS parameter type.
void copy_parameter_value(const std::shared_ptr< const state_representation::ParameterInterface > &source_parameter, const std::shared_ptr< state_representation::ParameterInterface > ¶meter)
Copy the value of one parameter interface into another.
std::shared_ptr< state_representation::ParameterInterface > read_parameter_const(const rclcpp::Parameter &ros_parameter, const std::shared_ptr< const state_representation::ParameterInterface > ¶meter)
Update the parameter value of a ParameterInterface from a ROS Parameter object only if the two parame...
Response structure to be returned by controller services.