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>
12#include <state_representation/parameters/ParameterMap.hpp>
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>
21#include <modulo_interfaces/msg/assignment.hpp>
22#include <modulo_interfaces/msg/predicate_collection.hpp>
23#include <modulo_interfaces/srv/empty_trigger.hpp>
24#include <modulo_interfaces/srv/string_trigger.hpp>
26#include <modulo_utils/parsing.hpp>
28#include <modulo_core/concepts.hpp>
30namespace modulo_controllers {
33 std::shared_ptr<rclcpp::Subscription<modulo_core::EncodedState>>,
34 std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Bool>>,
35 std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Float64>>,
36 std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Float64MultiArray>>,
37 std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Int32>>,
38 std::shared_ptr<rclcpp::Subscription<std_msgs::msg::String>>, std::any>
42 realtime_tools::RealtimeBuffer<std::shared_ptr<modulo_core::EncodedState>>,
43 realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>,
44 realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>,
45 realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>,
46 realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>,
47 realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>, std::any>
51 std::shared_ptr<state_representation::State>, std::shared_ptr<rclcpp::Publisher<modulo_core::EncodedState>>,
52 realtime_tools::RealtimePublisherSharedPtr<modulo_core::EncodedState>>
53 EncodedStatePublishers;
55 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Bool>>,
56 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Bool>>
59 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Float64>>,
60 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Float64>>
63 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Float64MultiArray>>,
64 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Float64MultiArray>>
67 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Int32>>,
68 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Int32>>
71 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::String>>,
72 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::String>>
74typedef std::pair<std::any, std::any> CustomPublishers;
77 EncodedStatePublishers, BoolPublishers, DoublePublishers, DoubleVecPublishers, IntPublishers, StringPublishers,
87 ControllerInput(BufferVariant buffer_variant) : buffer(std::move(buffer_variant)) {}
89 std::chrono::time_point<std::chrono::steady_clock> timestamp;
118 CallbackReturn
on_init()
override;
125 CallbackReturn
on_configure(
const rclcpp_lifecycle::State& previous_state)
override;
137 const std::shared_ptr<state_representation::ParameterInterface>& parameter,
const std::string& description,
138 bool read_only =
false);
151 void add_parameter(
const std::string& name,
const T& value,
const std::string& description,
bool read_only =
false);
171 [[nodiscard]] std::shared_ptr<state_representation::ParameterInterface>
get_parameter(
const std::string& name)
const;
208 void set_assignment(
const std::string& assignment_name,
const T& assignment_value);
226 void add_predicate(
const std::string& predicate_name,
bool predicate_value);
233 void add_predicate(
const std::string& predicate_name,
const std::function<
bool(
void)>& predicate_function);
241 [[nodiscard]]
bool get_predicate(
const std::string& predicate_name)
const;
250 void set_predicate(
const std::string& predicate_name,
bool predicate_value);
259 void set_predicate(
const std::string& predicate_name,
const std::function<
bool(
void)>& predicate_function);
273 void trigger(
const std::string& trigger_name);
284 void add_input(
const std::string& name,
const std::string& topic_name =
"");
295 void add_output(
const std::string& name,
const std::string& topic_name =
"");
311 std::optional<T>
read_input(
const std::string& name);
322 void write_output(
const std::string& name,
const T& data);
340 const std::string& service_name,
355 const std::string& service_name,
362 [[nodiscard]] rclcpp::QoS
get_qos()
const;
368 void set_qos(
const rclcpp::QoS& qos);
390 bool validate_parameter(
const std::shared_ptr<state_representation::ParameterInterface>& parameter);
396 void pre_set_parameters_callback(std::vector<rclcpp::Parameter>& parameters);
404 rcl_interfaces::msg::SetParametersResult on_set_parameters_callback(
const std::vector<rclcpp::Parameter>& parameters);
411 modulo_interfaces::msg::Predicate get_predicate_message(
const std::string& name,
bool value)
const;
418 void publish_predicate(
const std::string& predicate_name,
bool value)
const;
423 void publish_predicates();
432 std::string validate_and_declare_signal(
433 const std::string& signal_name,
const std::string& type,
const std::string& default_topic,
434 bool fixed_topic =
false);
444 void create_input(
const ControllerInput& input,
const std::string& name,
const std::string& topic_name);
454 void create_output(
const PublisherVariant& publishers,
const std::string& name,
const std::string& topic_name);
463 std::shared_ptr<rclcpp::Subscription<T>> create_subscription(
const std::string& name,
const std::string& topic_name);
469 bool check_input_valid(
const std::string& name)
const;
474 template<
typename PublisherT,
typename MsgT,
typename T>
475 void write_std_output(
const std::string& name,
const T& data);
494 template<
bool acquire_lock,
typename CallbackT>
495 void create_service(
const std::string& service_name,
const std::function<CallbackT>& callback)
506 std::string validate_service_name(
const std::string& service_name,
const std::string& type)
const;
508 state_representation::ParameterMap parameter_map_;
509 std::unordered_map<std::string, bool> read_only_parameters_;
510 std::shared_ptr<rclcpp::node_interfaces::PreSetParametersCallbackHandle>
511 pre_set_parameter_cb_handle_;
512 std::shared_ptr<rclcpp::node_interfaces::OnSetParametersCallbackHandle>
513 on_set_parameter_cb_handle_;
514 rcl_interfaces::msg::SetParametersResult set_parameters_result_;
515 bool pre_set_parameter_callback_called_ =
false;
517 std::vector<SubscriptionVariant> subscriptions_;
518 std::map<std::string, ControllerInput> inputs_;
519 std::map<std::string, std::shared_ptr<modulo_core::communication::MessagePairInterface>>
520 input_message_pairs_;
521 std::map<std::string, PublisherVariant> outputs_;
522 double input_validity_period_;
523 rclcpp::QoS qos_ = rclcpp::QoS(10);
525 std::map<std::string, std::shared_ptr<rclcpp::Service<modulo_interfaces::srv::EmptyTrigger>>>
527 std::map<std::string, std::shared_ptr<rclcpp::Service<modulo_interfaces::srv::StringTrigger>>>
530 state_representation::ParameterMap assignments_map_;
531 std::shared_ptr<rclcpp::Publisher<modulo_interfaces::msg::Assignment>> assignment_publisher_;
533 std::map<std::string, modulo_core::Predicate> predicates_;
534 std::shared_ptr<rclcpp::Publisher<modulo_interfaces::msg::PredicateCollection>>
535 predicate_publisher_;
536 std::vector<std::string> triggers_;
537 modulo_interfaces::msg::PredicateCollection predicate_message_;
538 std::shared_ptr<rclcpp::TimerBase> predicate_timer_;
540 std::timed_mutex command_mutex_;
542 std::map<std::string, std::function<void(CustomPublishers&,
const std::string&)>>
543 custom_output_configuration_callables_;
544 std::map<std::string, std::function<void(
const std::string&,
const std::string&)>>
545 custom_input_configuration_callables_;
550 const std::string& name,
const T& value,
const std::string& description,
bool read_only) {
552 RCLCPP_ERROR(get_node()->get_logger(),
"Failed to add parameter: Provide a non empty string as a name.");
555 add_parameter(state_representation::make_shared_parameter(name, value), description, read_only);
562 }
catch (
const state_representation::exceptions::InvalidParameterException& ex) {
564 "Failed to get parameter value of parameter '" + name +
"': " + ex.what());
571 std::vector<rclcpp::Parameter> parameters{
573 pre_set_parameters_callback(parameters);
574 pre_set_parameter_callback_called_ =
true;
575 auto result = get_node()->set_parameters(parameters).at(0);
576 if (!result.successful) {
577 RCLCPP_ERROR_THROTTLE(
578 get_node()->get_logger(), *get_node()->get_clock(), 1000,
579 "Failed to set parameter value of parameter '%s': %s", name.c_str(), result.reason.c_str());
581 }
catch (
const std::exception& ex) {
582 RCLCPP_ERROR_THROTTLE(
583 get_node()->get_logger(), *get_node()->get_clock(), 1000,
"Failed to set parameter value of parameter '%s': %s",
584 name.c_str(), ex.what());
591 auto buffer = std::make_shared<realtime_tools::RealtimeBuffer<std::shared_ptr<T>>>();
593 auto parsed_name = validate_and_declare_signal(name,
"input", topic_name);
594 if (!parsed_name.empty()) {
595 inputs_.insert_or_assign(parsed_name, input);
596 custom_input_configuration_callables_.insert_or_assign(
597 name, [
this](
const std::string& name,
const std::string& topic) {
599 get_node()->create_subscription<T>(topic, qos_, [
this, name](
const std::shared_ptr<T> message) {
600 auto buffer_variant = std::get<std::any>(inputs_.at(name).buffer);
601 auto buffer = std::any_cast<std::shared_ptr<realtime_tools::RealtimeBuffer<std::shared_ptr<T>>>>(
603 buffer->writeFromNonRT(message);
604 inputs_.at(name).timestamp = std::chrono::steady_clock::now();
606 subscriptions_.push_back(subscription);
610 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<modulo_core::EncodedState>>();
612 auto parsed_name = validate_and_declare_signal(name,
"input", topic_name);
613 if (!parsed_name.empty()) {
614 inputs_.insert_or_assign(parsed_name, input);
615 input_message_pairs_.insert_or_assign(
617 modulo_core::communication::make_shared_message_pair(std::make_shared<T>(), get_node()->get_clock()));
624 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>();
626 create_input(input, name, topic_name);
631 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>();
632 auto input = ControllerInput(buffer);
633 create_input(input, name, topic_name);
639 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>();
640 auto input = ControllerInput(buffer);
641 create_input(input, name, topic_name);
646 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>();
647 auto input = ControllerInput(buffer);
648 create_input(input, name, topic_name);
652inline void BaseControllerInterface::add_input<std::string>(
const std::string& name,
const std::string& topic_name) {
653 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>();
654 auto input = ControllerInput(buffer);
655 create_input(input, name, topic_name);
659inline std::shared_ptr<rclcpp::Subscription<T>>
660BaseControllerInterface::create_subscription(
const std::string& name,
const std::string& topic_name) {
661 return get_node()->create_subscription<T>(topic_name, qos_, [
this, name](
const std::shared_ptr<T> message) {
662 std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<T>>>(inputs_.at(name).buffer).writeFromNonRT(message);
663 inputs_.at(name).timestamp = std::chrono::steady_clock::now();
670 typedef std::pair<std::shared_ptr<rclcpp::Publisher<T>>, realtime_tools::RealtimePublisherSharedPtr<T>> PublisherT;
671 auto parsed_name = validate_and_declare_signal(name,
"output", topic_name);
672 if (!parsed_name.empty()) {
673 outputs_.insert_or_assign(parsed_name, PublisherT());
674 custom_output_configuration_callables_.insert_or_assign(
675 name, [
this](CustomPublishers& pub,
const std::string& topic) {
676 auto publisher = get_node()->create_publisher<T>(topic, qos_);
677 pub.first = publisher;
678 pub.second = std::make_shared<realtime_tools::RealtimePublisher<T>>(publisher);
682 std::shared_ptr<state_representation::State> state_ptr = std::make_shared<T>();
683 create_output(EncodedStatePublishers(state_ptr, {}, {}), name, topic_name);
689 create_output(BoolPublishers(), name, topic_name);
694 create_output(DoublePublishers(), name, topic_name);
700 create_output(DoubleVecPublishers(), name, topic_name);
705 create_output(IntPublishers(), name, topic_name);
709inline void BaseControllerInterface::add_output<std::string>(
const std::string& name,
const std::string& topic_name) {
710 create_output(StringPublishers(), name, topic_name);
715 if (!check_input_valid(name)) {
721 auto buffer_variant = std::get<std::any>(inputs_.at(name).buffer);
722 auto buffer = std::any_cast<std::shared_ptr<realtime_tools::RealtimeBuffer<std::shared_ptr<T>>>>(buffer_variant);
723 return **(buffer->readFromNonRT());
724 }
catch (
const std::bad_any_cast& ex) {
725 RCLCPP_ERROR(get_node()->get_logger(),
"Failed to read custom input: %s", ex.what());
730 **std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<modulo_core::EncodedState>>>(inputs_.at(name).buffer)
732 std::shared_ptr<state_representation::State> state;
734 auto message_pair = input_message_pairs_.at(name);
735 message_pair->read<modulo_core::EncodedState, state_representation::State>(message);
736 state = message_pair->get_message_pair<modulo_core::EncodedState, state_representation::State>()->get_data();
737 }
catch (
const std::exception& ex) {
738 RCLCPP_WARN_THROTTLE(
739 get_node()->get_logger(), *get_node()->get_clock(), 1000,
740 "Could not read EncodedState message on input '%s': %s", name.c_str(), ex.what());
743 if (state->is_empty()) {
746 auto cast_ptr = std::dynamic_pointer_cast<T>(state);
747 if (cast_ptr !=
nullptr) {
750 RCLCPP_WARN_THROTTLE(
751 get_node()->get_logger(), *get_node()->get_clock(), 1000,
752 "Dynamic cast of message on input '%s' from type '%s' to type '%s' failed.", name.c_str(),
753 get_state_type_name(state->get_type()).c_str(), get_state_type_name(T().get_type()).c_str());
761 if (!check_input_valid(name)) {
766 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>>(inputs_.at(name).buffer)
773 if (!check_input_valid(name)) {
776 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>>(inputs_.at(name).buffer)
782inline std::optional<std::vector<double>>
784 if (!check_input_valid(name)) {
787 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>>(
788 inputs_.at(name).buffer)
795 if (!check_input_valid(name)) {
798 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>>(inputs_.at(name).buffer)
804inline std::optional<std::string> BaseControllerInterface::read_input<std::string>(
const std::string& name) {
805 if (!check_input_valid(name)) {
808 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>>(inputs_.at(name).buffer)
815 if (outputs_.find(name) == outputs_.end()) {
816 RCLCPP_WARN_THROTTLE(
817 get_node()->get_logger(), *get_node()->get_clock(), 1000,
"Could not find output '%s'", name.c_str());
822 CustomPublishers publishers;
824 publishers = std::get<CustomPublishers>(outputs_.at(name));
825 }
catch (
const std::bad_variant_access&) {
826 RCLCPP_WARN_THROTTLE(
827 get_node()->get_logger(), *get_node()->get_clock(), 1000,
828 "Could not retrieve publisher for output '%s': Invalid output type", name.c_str());
832 std::shared_ptr<realtime_tools::RealtimePublisher<T>> rt_pub;
834 rt_pub = std::any_cast<std::shared_ptr<realtime_tools::RealtimePublisher<T>>>(publishers.second);
835 }
catch (
const std::bad_any_cast& ex) {
836 RCLCPP_ERROR_THROTTLE(
837 get_node()->get_logger(), *get_node()->get_clock(), 1000,
838 "Skipping publication of output '%s' due to wrong data type: %s", name.c_str(), ex.what());
841 if (rt_pub && rt_pub->trylock()) {
843 rt_pub->unlockAndPublish();
846 if (data.is_empty()) {
847 RCLCPP_DEBUG_THROTTLE(
848 get_node()->get_logger(), *get_node()->get_clock(), 1000,
849 "Skipping publication of output '%s' due to emptiness of state", name.c_str());
852 EncodedStatePublishers publishers;
854 publishers = std::get<EncodedStatePublishers>(outputs_.at(name));
855 }
catch (
const std::bad_variant_access&) {
856 RCLCPP_WARN_THROTTLE(
857 get_node()->get_logger(), *get_node()->get_clock(), 1000,
858 "Could not retrieve publisher for output '%s': Invalid output type", name.c_str());
861 if (
const auto output_type = std::get<0>(publishers)->get_type(); output_type != data.get_type()) {
862 RCLCPP_WARN_THROTTLE(
863 get_node()->get_logger(), *get_node()->get_clock(), 1000,
864 "Skipping publication of output '%s' due to wrong data type (expected '%s', got '%s')",
865 state_representation::get_state_type_name(output_type).c_str(),
866 state_representation::get_state_type_name(data.get_type()).c_str(), name.c_str());
869 auto rt_pub = std::get<2>(publishers);
870 if (rt_pub && rt_pub->trylock()) {
874 RCLCPP_ERROR_THROTTLE(
875 get_node()->get_logger(), *get_node()->get_clock(), 1000,
"Failed to publish output '%s': %s", name.c_str(),
878 rt_pub->unlockAndPublish();
883template<
typename PublisherT,
typename MsgT,
typename T>
884void BaseControllerInterface::write_std_output(
const std::string& name,
const T& data) {
885 if (outputs_.find(name) == outputs_.end()) {
886 RCLCPP_WARN_THROTTLE(
887 get_node()->get_logger(), *get_node()->get_clock(), 1000,
"Could not find output '%s'", name.c_str());
890 PublisherT publishers;
892 publishers = std::get<PublisherT>(outputs_.at(name));
893 }
catch (
const std::bad_variant_access&) {
894 RCLCPP_WARN_THROTTLE(
895 get_node()->get_logger(), *get_node()->get_clock(), 1000,
896 "Could not retrieve publisher for output '%s': Invalid output type", name.c_str());
899 auto rt_pub = publishers.second;
900 if (rt_pub && rt_pub->trylock()) {
901 rt_pub->msg_.data = data;
902 rt_pub->unlockAndPublish();
908 write_std_output<BoolPublishers, std_msgs::msg::Bool, bool>(name, data);
913 write_std_output<DoublePublishers, std_msgs::msg::Float64, double>(name, data);
918 write_std_output<DoubleVecPublishers, std_msgs::msg::Float64MultiArray, std::vector<double>>(name, data);
923 write_std_output<IntPublishers, std_msgs::msg::Int32, int>(name, data);
928 write_std_output<StringPublishers, std_msgs::msg::String, std::string>(name, data);
931template<
bool acquire_lock,
typename CallbackT>
933BaseControllerInterface::create_service(
const std::string& service_name,
const std::function<CallbackT>& callback)
935 std::is_same_v<CallbackT, ControllerServiceResponse(
const std::string&)>
936 || std::is_same_v<CallbackT, ControllerServiceResponse(
void)>)
938 constexpr bool is_empty = std::is_same_v<CallbackT, ControllerServiceResponse(
void)>;
940 std::conditional_t<is_empty, modulo_interfaces::srv::EmptyTrigger, modulo_interfaces::srv::StringTrigger>;
942 auto parsed_service_name = validate_service_name(service_name, is_empty ?
"empty" :
"string");
943 if (parsed_service_name.empty()) {
948 auto service = get_node()->create_service<ServiceT>(
949 "~/" + parsed_service_name,
951 const std::shared_ptr<typename ServiceT::Request> request,
952 std::shared_ptr<typename ServiceT::Response> response) {
954 auto run_callback = [&]() {
955 ControllerServiceResponse callback_response;
956 if constexpr (is_empty) {
957 callback_response = callback();
959 callback_response = callback(request->payload);
961 response->success = callback_response.success;
962 response->message = callback_response.message;
965 if constexpr (!acquire_lock) {
968 std::unique_lock<std::timed_mutex> lock(this->command_mutex_, std::defer_lock);
969 if (lock.try_lock_for(std::chrono::milliseconds{100})) {
972 response->success =
false;
973 response->message =
"Unable to acquire lock for command interface within 100ms";
976 }
catch (
const std::exception& ex) {
977 response->success =
false;
978 response->message = ex.what();
982 if constexpr (is_empty) {
983 empty_services_.insert_or_assign(parsed_service_name, service);
985 string_services_.insert_or_assign(parsed_service_name, service);
987 }
catch (
const std::exception& ex) {
988 RCLCPP_ERROR(get_node()->get_logger(),
"Failed to add service '%s': %s", parsed_service_name.c_str(), ex.what());
994 std::string parsed_name = modulo_utils::parsing::parse_topic_name(assignment_name);
995 if (parsed_name.empty()) {
997 get_node()->get_logger(),
998 "The parsed name for assignment '" + assignment_name
999 +
"' is empty. Provide a string with valid characters for the assignment name ([a-z0-9_]).");
1002 if (assignment_name != parsed_name) {
1004 get_node()->get_logger(),
1005 "The parsed name for assignment '" + assignment_name +
"' is '" + parsed_name
1006 +
"'. Use the parsed name to refer to this assignment.");
1009 this->assignments_map_.get_parameter(parsed_name);
1011 get_node()->get_logger(),
"Assignment with name '" + parsed_name +
"' already exists, overwriting.");
1012 }
catch (
const state_representation::exceptions::InvalidParameterException& ex) {
1013 RCLCPP_DEBUG_STREAM(get_node()->get_logger(),
"Adding assignment '" << parsed_name <<
"'.");
1016 assignments_map_.set_parameter(state_representation::make_shared_parameter<T>(parsed_name));
1017 }
catch (
const std::exception& ex) {
1018 RCLCPP_ERROR_STREAM_THROTTLE(
1019 get_node()->get_logger(), *get_node()->get_clock(), 1000,
1020 "Failed to add assignment '" << parsed_name <<
"': " << ex.what());
1026 modulo_interfaces::msg::Assignment message;
1027 std::shared_ptr<state_representation::ParameterInterface> assignment;
1029 assignment = assignments_map_.get_parameter(assignment_name);
1030 }
catch (
const state_representation::exceptions::InvalidParameterException&) {
1031 RCLCPP_ERROR_STREAM_THROTTLE(
1032 get_node()->get_logger(), *get_node()->get_clock(), 1000,
1033 "Failed to set assignment '" << assignment_name <<
"': Assignment does not exist.");
1037 assignment->set_parameter_value<T>(assignment_value);
1038 }
catch (
const state_representation::exceptions::InvalidParameterCastException&) {
1039 RCLCPP_ERROR_STREAM_THROTTLE(
1040 get_node()->get_logger(), *get_node()->get_clock(), 1000,
1041 "Failed to set assignment '" << assignment_name <<
"': Incompatible value type.");
1044 if (assignment_publisher_ ==
nullptr) {
1045 RCLCPP_ERROR_STREAM_THROTTLE(
1046 get_node()->get_logger(), *get_node()->get_clock(), 1000,
1047 "No assignment publisher configured. Make sure to add assignments `on_init` of the controller.");
1050 message.node = get_node()->get_fully_qualified_name();
1052 assignment_publisher_->publish(message);
1057 std::shared_ptr<state_representation::ParameterInterface> assignment;
1059 assignment = assignments_map_.get_parameter(assignment_name);
1060 }
catch (
const state_representation::exceptions::InvalidParameterException&) {
1062 "Failed to get value of assignment '" + assignment_name +
"': Assignment does not exist.");
1065 return assignment->get_parameter_value<T>();
1066 }
catch (
const state_representation::exceptions::InvalidParameterCastException&) {
1067 auto expected_type = state_representation::get_parameter_type_name(assignment->get_parameter_type());
1069 "Incompatible type for assignment '" + assignment_name +
"' defined with type '" + expected_type +
"'.");
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 add_assignment(const std::string &assignment_name)
Add an assignment to the map of assignments.
void set_input_validity_period(double input_validity_period)
Set the input validity period of input signals.
void set_assignment(const std::string &assignment_name, const T &assignment_value)
Set an assignment.
CallbackReturn on_init() override
Declare parameters and register the on_set_parameters callback.
T get_assignment(const std::string &assignment_name) const
Get the value of an assignment.
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 > ¶meter, 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 > ¶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 when getting the value of an assignment.
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 > ¶meter)
Write a ROS Parameter from a ParameterInterface pointer.
Response structure to be returned by controller services.