Modulo 5.0.0
Loading...
Searching...
No Matches
BaseControllerInterface.hpp
1#pragma once
2
3#include <any>
4#include <chrono>
5#include <mutex>
6
7#include <controller_interface/controller_interface.hpp>
8#include <controller_interface/helpers.hpp>
9#include <realtime_tools/realtime_buffer.h>
10#include <realtime_tools/realtime_publisher.h>
11
12#include <state_representation/parameters/ParameterMap.hpp>
13
14#include <modulo_core/EncodedState.hpp>
15#include <modulo_core/Predicate.hpp>
16#include <modulo_core/communication/MessagePair.hpp>
17#include <modulo_core/exceptions.hpp>
18#include <modulo_core/translators/message_writers.hpp>
19#include <modulo_core/translators/parameter_translators.hpp>
20
21#include <modulo_interfaces/msg/predicate_collection.hpp>
22#include <modulo_interfaces/srv/empty_trigger.hpp>
23#include <modulo_interfaces/srv/string_trigger.hpp>
24
25#include <modulo_utils/parsing.hpp>
26
27#include <modulo_core/concepts.hpp>
28
29namespace modulo_controllers {
30
31typedef std::variant<
32 std::shared_ptr<rclcpp::Subscription<modulo_core::EncodedState>>,
33 std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Bool>>,
34 std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Float64>>,
35 std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Float64MultiArray>>,
36 std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Int32>>,
37 std::shared_ptr<rclcpp::Subscription<std_msgs::msg::String>>, std::any>
38 SubscriptionVariant;
39
40typedef std::variant<
41 realtime_tools::RealtimeBuffer<std::shared_ptr<modulo_core::EncodedState>>,
42 realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>,
43 realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>,
44 realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>,
45 realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>,
46 realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>, std::any>
47 BufferVariant;
48
49typedef std::tuple<
50 std::shared_ptr<state_representation::State>, std::shared_ptr<rclcpp::Publisher<modulo_core::EncodedState>>,
51 realtime_tools::RealtimePublisherSharedPtr<modulo_core::EncodedState>>
52 EncodedStatePublishers;
53typedef std::pair<
54 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Bool>>,
55 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Bool>>
56 BoolPublishers;
57typedef std::pair<
58 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Float64>>,
59 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Float64>>
60 DoublePublishers;
61typedef std::pair<
62 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Float64MultiArray>>,
63 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Float64MultiArray>>
64 DoubleVecPublishers;
65typedef std::pair<
66 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Int32>>,
67 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Int32>>
68 IntPublishers;
69typedef std::pair<
70 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::String>>,
71 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::String>>
72 StringPublishers;
73typedef std::pair<std::any, std::any> CustomPublishers;
74
75typedef std::variant<
76 EncodedStatePublishers, BoolPublishers, DoublePublishers, DoubleVecPublishers, IntPublishers, StringPublishers,
77 CustomPublishers>
78 PublisherVariant;
79
85 ControllerInput() = default;
86 ControllerInput(BufferVariant buffer_variant) : buffer(std::move(buffer_variant)) {}
87 BufferVariant buffer;
88 std::chrono::time_point<std::chrono::steady_clock> timestamp;
89};
90
98 bool success;
99 std::string message;
100};
101
106class BaseControllerInterface : public controller_interface::ControllerInterface {
107public:
112
117 CallbackReturn on_init() override;
118
124 CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override;
125
126protected:
136 const std::shared_ptr<state_representation::ParameterInterface>& parameter, const std::string& description,
137 bool read_only = false);
138
149 template<typename T>
150 void add_parameter(const std::string& name, const T& value, const std::string& description, bool read_only = false);
151
162 virtual bool
163 on_validate_parameter_callback(const std::shared_ptr<state_representation::ParameterInterface>& parameter);
164
170 [[nodiscard]] std::shared_ptr<state_representation::ParameterInterface> get_parameter(const std::string& name) const;
171
178 template<typename T>
179 T get_parameter_value(const std::string& name) const;
180
189 template<typename T>
190 void set_parameter_value(const std::string& name, const T& value);
191
197 void add_predicate(const std::string& predicate_name, bool predicate_value);
198
204 void add_predicate(const std::string& predicate_name, const std::function<bool(void)>& predicate_function);
205
212 [[nodiscard]] bool get_predicate(const std::string& predicate_name) const;
213
221 void set_predicate(const std::string& predicate_name, bool predicate_value);
222
230 void set_predicate(const std::string& predicate_name, const std::function<bool(void)>& predicate_function);
231
238 void add_trigger(const std::string& trigger_name);
239
244 void trigger(const std::string& trigger_name);
245
254 template<typename T>
255 void add_input(const std::string& name, const std::string& topic_name = "");
256
265 template<typename T>
266 void add_output(const std::string& name, const std::string& topic_name = "");
267
272 void set_input_validity_period(double input_validity_period);
273
281 template<typename T>
282 std::optional<T> read_input(const std::string& name);
283
292 template<typename T>
293 void write_output(const std::string& name, const T& data);
294
300 void add_service(const std::string& service_name, const std::function<ControllerServiceResponse(void)>& callback);
301
310 void add_service(
311 const std::string& service_name,
312 const std::function<ControllerServiceResponse(const std::string& string)>& callback);
313
318 void
319 add_service_lockfree(const std::string& service_name, const std::function<ControllerServiceResponse(void)>& callback);
320
326 const std::string& service_name,
327 const std::function<ControllerServiceResponse(const std::string& string)>& callback);
328
333 [[nodiscard]] rclcpp::QoS get_qos() const;
334
339 void set_qos(const rclcpp::QoS& qos);
340
345 bool is_active() const;
346
351 std::timed_mutex& get_command_mutex();
352
353private:
361 bool validate_parameter(const std::shared_ptr<state_representation::ParameterInterface>& parameter);
362
367 void pre_set_parameters_callback(std::vector<rclcpp::Parameter>& parameters);
368
375 rcl_interfaces::msg::SetParametersResult on_set_parameters_callback(const std::vector<rclcpp::Parameter>& parameters);
376
382 modulo_interfaces::msg::Predicate get_predicate_message(const std::string& name, bool value) const;
383
389 void publish_predicate(const std::string& predicate_name, bool value) const;
390
394 void publish_predicates();
395
403 std::string validate_and_declare_signal(
404 const std::string& signal_name, const std::string& type, const std::string& default_topic,
405 bool fixed_topic = false);
406
415 void create_input(const ControllerInput& input, const std::string& name, const std::string& topic_name);
416
425 void create_output(const PublisherVariant& publishers, const std::string& name, const std::string& topic_name);
426
433 template<typename T>
434 std::shared_ptr<rclcpp::Subscription<T>> create_subscription(const std::string& name, const std::string& topic_name);
435
440 bool check_input_valid(const std::string& name) const;
441
445 template<typename PublisherT, typename MsgT, typename T>
446 void write_std_output(const std::string& name, const T& data);
447
451 void add_inputs();
452
456 void add_outputs();
457
465 template<bool acquire_lock, typename CallbackT>
466 void create_service(const std::string& service_name, const std::function<CallbackT>& callback)
467 requires(
468 std::is_same_v<CallbackT, ControllerServiceResponse(const std::string&)>
469 || std::is_same_v<CallbackT, ControllerServiceResponse(void)>);
470
477 std::string validate_service_name(const std::string& service_name, const std::string& type) const;
478
479 state_representation::ParameterMap parameter_map_;
480 std::unordered_map<std::string, bool> read_only_parameters_;
481 std::shared_ptr<rclcpp::node_interfaces::PreSetParametersCallbackHandle>
482 pre_set_parameter_cb_handle_;
483 std::shared_ptr<rclcpp::node_interfaces::OnSetParametersCallbackHandle>
484 on_set_parameter_cb_handle_;
485 rcl_interfaces::msg::SetParametersResult set_parameters_result_;
486 bool pre_set_parameter_callback_called_ = false;
487
488 std::vector<SubscriptionVariant> subscriptions_;
489 std::map<std::string, ControllerInput> inputs_;
490 std::map<std::string, std::shared_ptr<modulo_core::communication::MessagePairInterface>>
491 input_message_pairs_;
492 std::map<std::string, PublisherVariant> outputs_;
493 double input_validity_period_;
494 rclcpp::QoS qos_ = rclcpp::QoS(10);
495
496 std::map<std::string, std::shared_ptr<rclcpp::Service<modulo_interfaces::srv::EmptyTrigger>>>
497 empty_services_;
498 std::map<std::string, std::shared_ptr<rclcpp::Service<modulo_interfaces::srv::StringTrigger>>>
499 string_services_;
500
501 std::map<std::string, modulo_core::Predicate> predicates_;
502 std::shared_ptr<rclcpp::Publisher<modulo_interfaces::msg::PredicateCollection>>
503 predicate_publisher_;
504 std::vector<std::string> triggers_;
505 modulo_interfaces::msg::PredicateCollection predicate_message_;
506 std::shared_ptr<rclcpp::TimerBase> predicate_timer_;
507
508 std::timed_mutex command_mutex_;
509
510 std::map<std::string, std::function<void(CustomPublishers&, const std::string&)>>
511 custom_output_configuration_callables_;
512 std::map<std::string, std::function<void(const std::string&, const std::string&)>>
513 custom_input_configuration_callables_;
514};
515
516template<typename T>
518 const std::string& name, const T& value, const std::string& description, bool read_only) {
519 if (name.empty()) {
520 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add parameter: Provide a non empty string as a name.");
521 return;
522 }
523 add_parameter(state_representation::make_shared_parameter(name, value), description, read_only);
524}
525
526template<typename T>
527inline T BaseControllerInterface::get_parameter_value(const std::string& name) const {
528 try {
529 return this->parameter_map_.template get_parameter_value<T>(name);
530 } catch (const state_representation::exceptions::InvalidParameterException& ex) {
532 "Failed to get parameter value of parameter '" + name + "': " + ex.what());
533 }
534}
535
536template<typename T>
537inline void BaseControllerInterface::set_parameter_value(const std::string& name, const T& value) {
538 try {
539 std::vector<rclcpp::Parameter> parameters{
540 modulo_core::translators::write_parameter(state_representation::make_shared_parameter(name, value))};
541 pre_set_parameters_callback(parameters);
542 pre_set_parameter_callback_called_ = true;
543 auto result = get_node()->set_parameters(parameters).at(0);
544 if (!result.successful) {
545 RCLCPP_ERROR_THROTTLE(
546 get_node()->get_logger(), *get_node()->get_clock(), 1000,
547 "Failed to set parameter value of parameter '%s': %s", name.c_str(), result.reason.c_str());
548 }
549 } catch (const std::exception& ex) {
550 RCLCPP_ERROR_THROTTLE(
551 get_node()->get_logger(), *get_node()->get_clock(), 1000, "Failed to set parameter value of parameter '%s': %s",
552 name.c_str(), ex.what());
553 }
554}
555
556template<typename T>
557inline void BaseControllerInterface::add_input(const std::string& name, const std::string& topic_name) {
558 if constexpr (modulo_core::concepts::CustomT<T>) {
559 auto buffer = std::make_shared<realtime_tools::RealtimeBuffer<std::shared_ptr<T>>>();
560 auto input = ControllerInput(buffer);
561 auto parsed_name = validate_and_declare_signal(name, "input", topic_name);
562 if (!parsed_name.empty()) {
563 inputs_.insert_or_assign(parsed_name, input);
564 custom_input_configuration_callables_.insert_or_assign(
565 name, [this](const std::string& name, const std::string& topic) {
566 auto subscription =
567 get_node()->create_subscription<T>(topic, qos_, [this, name](const std::shared_ptr<T> message) {
568 auto buffer_variant = std::get<std::any>(inputs_.at(name).buffer);
569 auto buffer = std::any_cast<std::shared_ptr<realtime_tools::RealtimeBuffer<std::shared_ptr<T>>>>(
570 buffer_variant);
571 buffer->writeFromNonRT(message);
572 inputs_.at(name).timestamp = std::chrono::steady_clock::now();
573 });
574 subscriptions_.push_back(subscription);
575 });
576 }
577 } else {
578 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<modulo_core::EncodedState>>();
579 auto input = ControllerInput(buffer);
580 auto parsed_name = validate_and_declare_signal(name, "input", topic_name);
581 if (!parsed_name.empty()) {
582 inputs_.insert_or_assign(parsed_name, input);
583 input_message_pairs_.insert_or_assign(
584 parsed_name,
585 modulo_core::communication::make_shared_message_pair(std::make_shared<T>(), get_node()->get_clock()));
586 }
587 }
588}
589
590template<>
591inline void BaseControllerInterface::add_input<bool>(const std::string& name, const std::string& topic_name) {
592 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>();
593 auto input = ControllerInput(buffer);
594 create_input(input, name, topic_name);
595}
596
597template<>
598inline void BaseControllerInterface::add_input<double>(const std::string& name, const std::string& topic_name) {
599 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>();
600 auto input = ControllerInput(buffer);
601 create_input(input, name, topic_name);
602}
603
604template<>
605inline void
606BaseControllerInterface::add_input<std::vector<double>>(const std::string& name, const std::string& topic_name) {
607 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>();
608 auto input = ControllerInput(buffer);
609 create_input(input, name, topic_name);
610}
611
612template<>
613inline void BaseControllerInterface::add_input<int>(const std::string& name, const std::string& topic_name) {
614 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>();
615 auto input = ControllerInput(buffer);
616 create_input(input, name, topic_name);
617}
618
619template<>
620inline void BaseControllerInterface::add_input<std::string>(const std::string& name, const std::string& topic_name) {
621 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>();
622 auto input = ControllerInput(buffer);
623 create_input(input, name, topic_name);
624}
625
626template<typename T>
627inline std::shared_ptr<rclcpp::Subscription<T>>
628BaseControllerInterface::create_subscription(const std::string& name, const std::string& topic_name) {
629 return get_node()->create_subscription<T>(topic_name, qos_, [this, name](const std::shared_ptr<T> message) {
630 std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<T>>>(inputs_.at(name).buffer).writeFromNonRT(message);
631 inputs_.at(name).timestamp = std::chrono::steady_clock::now();
632 });
633}
634
635template<typename T>
636inline void BaseControllerInterface::add_output(const std::string& name, const std::string& topic_name) {
637 if constexpr (modulo_core::concepts::CustomT<T>) {
638 typedef std::pair<std::shared_ptr<rclcpp::Publisher<T>>, realtime_tools::RealtimePublisherSharedPtr<T>> PublisherT;
639 auto parsed_name = validate_and_declare_signal(name, "output", topic_name);
640 if (!parsed_name.empty()) {
641 outputs_.insert_or_assign(parsed_name, PublisherT());
642 custom_output_configuration_callables_.insert_or_assign(
643 name, [this](CustomPublishers& pub, const std::string& topic) {
644 auto publisher = get_node()->create_publisher<T>(topic, qos_);
645 pub.first = publisher;
646 pub.second = std::make_shared<realtime_tools::RealtimePublisher<T>>(publisher);
647 });
648 }
649 } else {
650 std::shared_ptr<state_representation::State> state_ptr = std::make_shared<T>();
651 create_output(EncodedStatePublishers(state_ptr, {}, {}), name, topic_name);
652 }
653}
654
655template<>
656inline void BaseControllerInterface::add_output<bool>(const std::string& name, const std::string& topic_name) {
657 create_output(BoolPublishers(), name, topic_name);
658}
659
660template<>
661inline void BaseControllerInterface::add_output<double>(const std::string& name, const std::string& topic_name) {
662 create_output(DoublePublishers(), name, topic_name);
663}
664
665template<>
666inline void
667BaseControllerInterface::add_output<std::vector<double>>(const std::string& name, const std::string& topic_name) {
668 create_output(DoubleVecPublishers(), name, topic_name);
669}
670
671template<>
672inline void BaseControllerInterface::add_output<int>(const std::string& name, const std::string& topic_name) {
673 create_output(IntPublishers(), name, topic_name);
674}
675
676template<>
677inline void BaseControllerInterface::add_output<std::string>(const std::string& name, const std::string& topic_name) {
678 create_output(StringPublishers(), name, topic_name);
679}
680
681template<typename T>
682inline std::optional<T> BaseControllerInterface::read_input(const std::string& name) {
683 if (!check_input_valid(name)) {
684 return {};
685 }
686
687 if constexpr (modulo_core::concepts::CustomT<T>) {
688 try {
689 auto buffer_variant = std::get<std::any>(inputs_.at(name).buffer);
690 auto buffer = std::any_cast<std::shared_ptr<realtime_tools::RealtimeBuffer<std::shared_ptr<T>>>>(buffer_variant);
691 return **(buffer->readFromNonRT());
692 } catch (const std::bad_any_cast& ex) {
693 RCLCPP_ERROR(get_node()->get_logger(), "Failed to read custom input: %s", ex.what());
694 }
695 return {};
696 } else {
697 auto message =
698 **std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<modulo_core::EncodedState>>>(inputs_.at(name).buffer)
699 .readFromNonRT();
700 std::shared_ptr<state_representation::State> state;
701 try {
702 auto message_pair = input_message_pairs_.at(name);
703 message_pair->read<modulo_core::EncodedState, state_representation::State>(message);
704 state = message_pair->get_message_pair<modulo_core::EncodedState, state_representation::State>()->get_data();
705 } catch (const std::exception& ex) {
706 RCLCPP_WARN_THROTTLE(
707 get_node()->get_logger(), *get_node()->get_clock(), 1000,
708 "Could not read EncodedState message on input '%s': %s", name.c_str(), ex.what());
709 return {};
710 }
711 if (state->is_empty()) {
712 return {};
713 }
714 auto cast_ptr = std::dynamic_pointer_cast<T>(state);
715 if (cast_ptr != nullptr) {
716 return *cast_ptr;
717 } else {
718 RCLCPP_WARN_THROTTLE(
719 get_node()->get_logger(), *get_node()->get_clock(), 1000,
720 "Dynamic cast of message on input '%s' from type '%s' to type '%s' failed.", name.c_str(),
721 get_state_type_name(state->get_type()).c_str(), get_state_type_name(T().get_type()).c_str());
722 }
723 return {};
724 }
725}
726
727template<>
728inline std::optional<bool> BaseControllerInterface::read_input<bool>(const std::string& name) {
729 if (!check_input_valid(name)) {
730 return {};
731 }
732 // no need to check for emptiness of the pointer: timestamps are default constructed to 0, so an input being valid
733 // means that a message was received
734 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>>(inputs_.at(name).buffer)
735 .readFromNonRT())
736 ->data;
737}
738
739template<>
740inline std::optional<double> BaseControllerInterface::read_input<double>(const std::string& name) {
741 if (!check_input_valid(name)) {
742 return {};
743 }
744 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>>(inputs_.at(name).buffer)
745 .readFromNonRT())
746 ->data;
747}
748
749template<>
750inline std::optional<std::vector<double>>
752 if (!check_input_valid(name)) {
753 return {};
754 }
755 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>>(
756 inputs_.at(name).buffer)
757 .readFromNonRT())
758 ->data;
759}
760
761template<>
762inline std::optional<int> BaseControllerInterface::read_input<int>(const std::string& name) {
763 if (!check_input_valid(name)) {
764 return {};
765 }
766 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>>(inputs_.at(name).buffer)
767 .readFromNonRT())
768 ->data;
769}
770
771template<>
772inline std::optional<std::string> BaseControllerInterface::read_input<std::string>(const std::string& name) {
773 if (!check_input_valid(name)) {
774 return {};
775 }
776 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>>(inputs_.at(name).buffer)
777 .readFromNonRT())
778 ->data;
779}
780
781template<typename T>
782inline void BaseControllerInterface::write_output(const std::string& name, const T& data) {
783 if (outputs_.find(name) == outputs_.end()) {
784 RCLCPP_WARN_THROTTLE(
785 get_node()->get_logger(), *get_node()->get_clock(), 1000, "Could not find output '%s'", name.c_str());
786 return;
787 }
788
789 if constexpr (modulo_core::concepts::CustomT<T>) {
790 CustomPublishers publishers;
791 try {
792 publishers = std::get<CustomPublishers>(outputs_.at(name));
793 } catch (const std::bad_variant_access&) {
794 RCLCPP_WARN_THROTTLE(
795 get_node()->get_logger(), *get_node()->get_clock(), 1000,
796 "Could not retrieve publisher for output '%s': Invalid output type", name.c_str());
797 return;
798 }
799
800 std::shared_ptr<realtime_tools::RealtimePublisher<T>> rt_pub;
801 try {
802 rt_pub = std::any_cast<std::shared_ptr<realtime_tools::RealtimePublisher<T>>>(publishers.second);
803 } catch (const std::bad_any_cast& ex) {
804 RCLCPP_ERROR_THROTTLE(
805 get_node()->get_logger(), *get_node()->get_clock(), 1000,
806 "Skipping publication of output '%s' due to wrong data type: %s", name.c_str(), ex.what());
807 return;
808 }
809 if (rt_pub && rt_pub->trylock()) {
810 rt_pub->msg_ = data;
811 rt_pub->unlockAndPublish();
812 }
813 } else {
814 if (data.is_empty()) {
815 RCLCPP_DEBUG_THROTTLE(
816 get_node()->get_logger(), *get_node()->get_clock(), 1000,
817 "Skipping publication of output '%s' due to emptiness of state", name.c_str());
818 return;
819 }
820 EncodedStatePublishers publishers;
821 try {
822 publishers = std::get<EncodedStatePublishers>(outputs_.at(name));
823 } catch (const std::bad_variant_access&) {
824 RCLCPP_WARN_THROTTLE(
825 get_node()->get_logger(), *get_node()->get_clock(), 1000,
826 "Could not retrieve publisher for output '%s': Invalid output type", name.c_str());
827 return;
828 }
829 if (const auto output_type = std::get<0>(publishers)->get_type(); output_type != data.get_type()) {
830 RCLCPP_WARN_THROTTLE(
831 get_node()->get_logger(), *get_node()->get_clock(), 1000,
832 "Skipping publication of output '%s' due to wrong data type (expected '%s', got '%s')",
833 state_representation::get_state_type_name(output_type).c_str(),
834 state_representation::get_state_type_name(data.get_type()).c_str(), name.c_str());
835 return;
836 }
837 auto rt_pub = std::get<2>(publishers);
838 if (rt_pub && rt_pub->trylock()) {
839 try {
840 modulo_core::translators::write_message<T>(rt_pub->msg_, data, get_node()->get_clock()->now());
842 RCLCPP_ERROR_THROTTLE(
843 get_node()->get_logger(), *get_node()->get_clock(), 1000, "Failed to publish output '%s': %s", name.c_str(),
844 ex.what());
845 }
846 rt_pub->unlockAndPublish();
847 }
848 }
849}
850
851template<typename PublisherT, typename MsgT, typename T>
852void BaseControllerInterface::write_std_output(const std::string& name, const T& data) {
853 if (outputs_.find(name) == outputs_.end()) {
854 RCLCPP_WARN_THROTTLE(
855 get_node()->get_logger(), *get_node()->get_clock(), 1000, "Could not find output '%s'", name.c_str());
856 return;
857 }
858 PublisherT publishers;
859 try {
860 publishers = std::get<PublisherT>(outputs_.at(name));
861 } catch (const std::bad_variant_access&) {
862 RCLCPP_WARN_THROTTLE(
863 get_node()->get_logger(), *get_node()->get_clock(), 1000,
864 "Could not retrieve publisher for output '%s': Invalid output type", name.c_str());
865 return;
866 }
867 auto rt_pub = publishers.second;
868 if (rt_pub && rt_pub->trylock()) {
869 rt_pub->msg_.data = data;
870 rt_pub->unlockAndPublish();
871 }
872}
873
874template<>
875inline void BaseControllerInterface::write_output(const std::string& name, const bool& data) {
876 write_std_output<BoolPublishers, std_msgs::msg::Bool, bool>(name, data);
877}
878
879template<>
880inline void BaseControllerInterface::write_output(const std::string& name, const double& data) {
881 write_std_output<DoublePublishers, std_msgs::msg::Float64, double>(name, data);
882}
883
884template<>
885inline void BaseControllerInterface::write_output(const std::string& name, const std::vector<double>& data) {
886 write_std_output<DoubleVecPublishers, std_msgs::msg::Float64MultiArray, std::vector<double>>(name, data);
887}
888
889template<>
890inline void BaseControllerInterface::write_output(const std::string& name, const int& data) {
891 write_std_output<IntPublishers, std_msgs::msg::Int32, int>(name, data);
892}
893
894template<>
895inline void BaseControllerInterface::write_output(const std::string& name, const std::string& data) {
896 write_std_output<StringPublishers, std_msgs::msg::String, std::string>(name, data);
897}
898
899template<bool acquire_lock, typename CallbackT>
900inline void
901BaseControllerInterface::create_service(const std::string& service_name, const std::function<CallbackT>& callback)
902 requires(
903 std::is_same_v<CallbackT, ControllerServiceResponse(const std::string&)>
904 || std::is_same_v<CallbackT, ControllerServiceResponse(void)>)
905{
906 constexpr bool is_empty = std::is_same_v<CallbackT, ControllerServiceResponse(void)>;
907 using ServiceT =
908 std::conditional_t<is_empty, modulo_interfaces::srv::EmptyTrigger, modulo_interfaces::srv::StringTrigger>;
909
910 auto parsed_service_name = validate_service_name(service_name, is_empty ? "empty" : "string");
911 if (parsed_service_name.empty()) {
912 return;
913 }
914
915 try {
916 auto service = get_node()->create_service<ServiceT>(
917 "~/" + parsed_service_name,
918 [this, callback](
919 const std::shared_ptr<typename ServiceT::Request> request,
920 std::shared_ptr<typename ServiceT::Response> response) {
921 try {
922 auto run_callback = [&]() {
923 ControllerServiceResponse callback_response;
924 if constexpr (is_empty) {
925 callback_response = callback();
926 } else {
927 callback_response = callback(request->payload);
928 }
929 response->success = callback_response.success;
930 response->message = callback_response.message;
931 };
932
933 if constexpr (!acquire_lock) {
934 run_callback();
935 } else {
936 std::unique_lock<std::timed_mutex> lock(this->command_mutex_, std::defer_lock);
937 if (lock.try_lock_for(std::chrono::milliseconds{100})) {
938 run_callback();
939 } else {
940 response->success = false;
941 response->message = "Unable to acquire lock for command interface within 100ms";
942 }
943 }
944 } catch (const std::exception& ex) {
945 response->success = false;
946 response->message = ex.what();
947 }
948 },
949 qos_);
950 if constexpr (is_empty) {
951 empty_services_.insert_or_assign(parsed_service_name, service);
952 } else {
953 string_services_.insert_or_assign(parsed_service_name, service);
954 }
955 } catch (const std::exception& ex) {
956 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add service '%s': %s", parsed_service_name.c_str(), ex.what());
957 }
958}
959
960}// namespace modulo_controllers
Base controller class to combine ros2_control, control libraries and modulo.
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 add_output(const std::string &name, const std::string &topic_name="")
Add an output to the controller.
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.
std::optional< T > read_input(const std::string &name)
Read the most recent message of an input.
void add_parameter(const std::shared_ptr< state_representation::ParameterInterface > &parameter, const std::string &description, bool read_only=false)
Add a parameter.
void write_output(const std::string &name, const T &data)
Write an object to an output.
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 add_input(const std::string &name, const std::string &topic_name="")
Add an input to the controller.
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 > &parameter)
Parameter validation function to be redefined by derived controller classes.
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 that the translation of a ROS message failed.
An exception class to notify errors with parameters in modulo classes.
void write_message(geometry_msgs::msg::Accel &message, const state_representation::CartesianState &state, const rclcpp::Time &time)
Convert a CartesianState to a ROS geometry_msgs::msg::Accel.
rclcpp::Parameter write_parameter(const std::shared_ptr< state_representation::ParameterInterface > &parameter)
Write a ROS Parameter from a ParameterInterface pointer.
Input structure to save topic data in a realtime buffer and timestamps in one object.
Response structure to be returned by controller services.