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/predicate_collection.hpp>
22#include <modulo_interfaces/srv/empty_trigger.hpp>
23#include <modulo_interfaces/srv/string_trigger.hpp>
25#include <modulo_utils/parsing.hpp>
27#include <modulo_core/concepts.hpp>
29namespace modulo_controllers {
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>
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>
50 std::shared_ptr<state_representation::State>, std::shared_ptr<rclcpp::Publisher<modulo_core::EncodedState>>,
51 realtime_tools::RealtimePublisherSharedPtr<modulo_core::EncodedState>>
52 EncodedStatePublishers;
54 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Bool>>,
55 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Bool>>
58 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Float64>>,
59 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Float64>>
62 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Float64MultiArray>>,
63 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Float64MultiArray>>
66 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Int32>>,
67 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::Int32>>
70 std::shared_ptr<rclcpp::Publisher<std_msgs::msg::String>>,
71 realtime_tools::RealtimePublisherSharedPtr<std_msgs::msg::String>>
73typedef std::pair<std::any, std::any> CustomPublishers;
76 EncodedStatePublishers, BoolPublishers, DoublePublishers, DoubleVecPublishers, IntPublishers, StringPublishers,
86 ControllerInput(BufferVariant buffer_variant) : buffer(std::move(buffer_variant)) {}
88 std::chrono::time_point<std::chrono::steady_clock> timestamp;
117 CallbackReturn
on_init()
override;
124 CallbackReturn
on_configure(
const rclcpp_lifecycle::State& previous_state)
override;
136 const std::shared_ptr<state_representation::ParameterInterface>& parameter,
const std::string& description,
137 bool read_only =
false);
150 void add_parameter(
const std::string& name,
const T& value,
const std::string& description,
bool read_only =
false);
170 [[nodiscard]] std::shared_ptr<state_representation::ParameterInterface>
get_parameter(
const std::string& name)
const;
197 void add_predicate(
const std::string& predicate_name,
bool predicate_value);
204 void add_predicate(
const std::string& predicate_name,
const std::function<
bool(
void)>& predicate_function);
212 [[nodiscard]]
bool get_predicate(
const std::string& predicate_name)
const;
221 void set_predicate(
const std::string& predicate_name,
bool predicate_value);
230 void set_predicate(
const std::string& predicate_name,
const std::function<
bool(
void)>& predicate_function);
244 void trigger(
const std::string& trigger_name);
255 void add_input(
const std::string& name,
const std::string& topic_name =
"");
266 void add_output(
const std::string& name,
const std::string& topic_name =
"");
282 std::optional<T>
read_input(
const std::string& name);
293 void write_output(
const std::string& name,
const T& data);
311 const std::string& service_name,
326 const std::string& service_name,
333 [[nodiscard]] rclcpp::QoS
get_qos()
const;
339 void set_qos(
const rclcpp::QoS& qos);
361 bool validate_parameter(
const std::shared_ptr<state_representation::ParameterInterface>& parameter);
367 void pre_set_parameters_callback(std::vector<rclcpp::Parameter>& parameters);
375 rcl_interfaces::msg::SetParametersResult on_set_parameters_callback(
const std::vector<rclcpp::Parameter>& parameters);
382 modulo_interfaces::msg::Predicate get_predicate_message(
const std::string& name,
bool value)
const;
389 void publish_predicate(
const std::string& predicate_name,
bool value)
const;
394 void publish_predicates();
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);
415 void create_input(
const ControllerInput& input,
const std::string& name,
const std::string& topic_name);
425 void create_output(
const PublisherVariant& publishers,
const std::string& name,
const std::string& topic_name);
434 std::shared_ptr<rclcpp::Subscription<T>> create_subscription(
const std::string& name,
const std::string& topic_name);
440 bool check_input_valid(
const std::string& name)
const;
445 template<
typename PublisherT,
typename MsgT,
typename T>
446 void write_std_output(
const std::string& name,
const T& data);
465 template<
bool acquire_lock,
typename CallbackT>
466 void create_service(
const std::string& service_name,
const std::function<CallbackT>& callback)
477 std::string validate_service_name(
const std::string& service_name,
const std::string& type)
const;
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;
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);
496 std::map<std::string, std::shared_ptr<rclcpp::Service<modulo_interfaces::srv::EmptyTrigger>>>
498 std::map<std::string, std::shared_ptr<rclcpp::Service<modulo_interfaces::srv::StringTrigger>>>
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_;
508 std::timed_mutex command_mutex_;
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_;
518 const std::string& name,
const T& value,
const std::string& description,
bool read_only) {
520 RCLCPP_ERROR(get_node()->get_logger(),
"Failed to add parameter: Provide a non empty string as a name.");
523 add_parameter(state_representation::make_shared_parameter(name, value), description, read_only);
530 }
catch (
const state_representation::exceptions::InvalidParameterException& ex) {
532 "Failed to get parameter value of parameter '" + name +
"': " + ex.what());
539 std::vector<rclcpp::Parameter> parameters{
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());
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());
559 auto buffer = std::make_shared<realtime_tools::RealtimeBuffer<std::shared_ptr<T>>>();
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) {
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>>>>(
571 buffer->writeFromNonRT(message);
572 inputs_.at(name).timestamp = std::chrono::steady_clock::now();
574 subscriptions_.push_back(subscription);
578 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<modulo_core::EncodedState>>();
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(
585 modulo_core::communication::make_shared_message_pair(std::make_shared<T>(), get_node()->get_clock()));
592 auto buffer = realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>();
594 create_input(input, name, 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);
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);
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);
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);
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();
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);
650 std::shared_ptr<state_representation::State> state_ptr = std::make_shared<T>();
651 create_output(EncodedStatePublishers(state_ptr, {}, {}), name, topic_name);
657 create_output(BoolPublishers(), name, topic_name);
662 create_output(DoublePublishers(), name, topic_name);
668 create_output(DoubleVecPublishers(), name, topic_name);
673 create_output(IntPublishers(), name, topic_name);
677inline void BaseControllerInterface::add_output<std::string>(
const std::string& name,
const std::string& topic_name) {
678 create_output(StringPublishers(), name, topic_name);
683 if (!check_input_valid(name)) {
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());
698 **std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<modulo_core::EncodedState>>>(inputs_.at(name).buffer)
700 std::shared_ptr<state_representation::State> state;
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());
711 if (state->is_empty()) {
714 auto cast_ptr = std::dynamic_pointer_cast<T>(state);
715 if (cast_ptr !=
nullptr) {
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());
729 if (!check_input_valid(name)) {
734 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>>(inputs_.at(name).buffer)
741 if (!check_input_valid(name)) {
744 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>>(inputs_.at(name).buffer)
750inline std::optional<std::vector<double>>
752 if (!check_input_valid(name)) {
755 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>>(
756 inputs_.at(name).buffer)
763 if (!check_input_valid(name)) {
766 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>>(inputs_.at(name).buffer)
772inline std::optional<std::string> BaseControllerInterface::read_input<std::string>(
const std::string& name) {
773 if (!check_input_valid(name)) {
776 return (*std::get<realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>>(inputs_.at(name).buffer)
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());
790 CustomPublishers publishers;
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());
800 std::shared_ptr<realtime_tools::RealtimePublisher<T>> rt_pub;
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());
809 if (rt_pub && rt_pub->trylock()) {
811 rt_pub->unlockAndPublish();
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());
820 EncodedStatePublishers publishers;
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());
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());
837 auto rt_pub = std::get<2>(publishers);
838 if (rt_pub && rt_pub->trylock()) {
842 RCLCPP_ERROR_THROTTLE(
843 get_node()->get_logger(), *get_node()->get_clock(), 1000,
"Failed to publish output '%s': %s", name.c_str(),
846 rt_pub->unlockAndPublish();
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());
858 PublisherT publishers;
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());
867 auto rt_pub = publishers.second;
868 if (rt_pub && rt_pub->trylock()) {
869 rt_pub->msg_.data = data;
870 rt_pub->unlockAndPublish();
876 write_std_output<BoolPublishers, std_msgs::msg::Bool, bool>(name, data);
881 write_std_output<DoublePublishers, std_msgs::msg::Float64, double>(name, data);
886 write_std_output<DoubleVecPublishers, std_msgs::msg::Float64MultiArray, std::vector<double>>(name, data);
891 write_std_output<IntPublishers, std_msgs::msg::Int32, int>(name, data);
896 write_std_output<StringPublishers, std_msgs::msg::String, std::string>(name, data);
899template<
bool acquire_lock,
typename CallbackT>
901BaseControllerInterface::create_service(
const std::string& service_name,
const std::function<CallbackT>& callback)
903 std::is_same_v<CallbackT, ControllerServiceResponse(
const std::string&)>
904 || std::is_same_v<CallbackT, ControllerServiceResponse(
void)>)
906 constexpr bool is_empty = std::is_same_v<CallbackT, ControllerServiceResponse(
void)>;
908 std::conditional_t<is_empty, modulo_interfaces::srv::EmptyTrigger, modulo_interfaces::srv::StringTrigger>;
910 auto parsed_service_name = validate_service_name(service_name, is_empty ?
"empty" :
"string");
911 if (parsed_service_name.empty()) {
916 auto service = get_node()->create_service<ServiceT>(
917 "~/" + parsed_service_name,
919 const std::shared_ptr<typename ServiceT::Request> request,
920 std::shared_ptr<typename ServiceT::Response> response) {
922 auto run_callback = [&]() {
923 ControllerServiceResponse callback_response;
924 if constexpr (is_empty) {
925 callback_response = callback();
927 callback_response = callback(request->payload);
929 response->success = callback_response.success;
930 response->message = callback_response.message;
933 if constexpr (!acquire_lock) {
936 std::unique_lock<std::timed_mutex> lock(this->command_mutex_, std::defer_lock);
937 if (lock.try_lock_for(std::chrono::milliseconds{100})) {
940 response->success =
false;
941 response->message =
"Unable to acquire lock for command interface within 100ms";
944 }
catch (
const std::exception& ex) {
945 response->success =
false;
946 response->message = ex.what();
950 if constexpr (is_empty) {
951 empty_services_.insert_or_assign(parsed_service_name, service);
953 string_services_.insert_or_assign(parsed_service_name, service);
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());
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 > ¶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 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.