2525#include " hardware_interface/component_parser.hpp"
2626#include " hardware_interface/handle.hpp"
2727#include " hardware_interface/hardware_info.hpp"
28+ #include " hardware_interface/types/hardware_interface_emergency_stop_signal.hpp"
29+ #include " hardware_interface/types/hardware_interface_error_signals.hpp"
2830#include " hardware_interface/types/hardware_interface_return_values.hpp"
31+ #include " hardware_interface/types/hardware_interface_warning_signals.hpp"
2932#include " hardware_interface/types/lifecycle_state_names.hpp"
3033#include " lifecycle_msgs/msg/state.hpp"
3134#include " rclcpp/duration.hpp"
@@ -125,6 +128,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
125128 info_ = hardware_info;
126129 import_state_interface_descriptions (info_);
127130 import_command_interface_descriptions (info_);
131+ create_report_interfaces ();
128132 return CallbackReturn::SUCCESS;
129133 };
130134
@@ -156,6 +160,52 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
156160 }
157161 }
158162
163+ /* *
164+ * Creates all interfaces used for reporting emergency stop, warning and error messages.
165+ * The available report interfaces are: EMERGENCY_STOP_SIGNAL, ERROR_SIGNAL, ERROR_SIGNAL_MESSAGE,
166+ * WARNING_SIGNAL and WARNING_SIGNAL_MESSAGE. Where the <report_type>_MESSAGE hold the message for
167+ * the corresponding report signal.
168+ * The interfaces are named like <hardware_name>/<report_interface_type>. E.g. if hardware is
169+ * called joint_1 -> interface for WARNING_SIGNAL is called: joint_1/WARNING_SIGNAL
170+ */
171+ void create_report_interfaces ()
172+ {
173+ // EMERGENCY STOP
174+ InterfaceInfo emergency_interface_info;
175+ emergency_interface_info.name = hardware_interface::EMERGENCY_STOP_SIGNAL;
176+ emergency_interface_info.data_type = " bool" ;
177+ InterfaceDescription emergency_interface_descr (info_.name , emergency_interface_info);
178+ emergency_stop_ = std::make_shared<StateInterface>(emergency_interface_descr);
179+
180+ // ERROR
181+ // create error signal interface
182+ InterfaceInfo error_interface_info;
183+ error_interface_info.name = hardware_interface::ERROR_SIGNAL_INTERFACE_NAME;
184+ error_interface_info.data_type = " array<uint8_t>[32]" ;
185+ InterfaceDescription error_interface_descr (info_.name , error_interface_info);
186+ error_signal_ = std::make_shared<StateInterface>(error_interface_descr);
187+ // create error signal report message interface
188+ InterfaceInfo error_msg_interface_info;
189+ error_msg_interface_info.name = hardware_interface::ERROR_SIGNAL_MESSAGE_INTERFACE_NAME;
190+ error_msg_interface_info.data_type = " array<string>[32]" ;
191+ InterfaceDescription error_msg_interface_descr (info_.name , error_msg_interface_info);
192+ error_signal_message_ = std::make_shared<StateInterface>(error_msg_interface_descr);
193+
194+ // WARNING
195+ // create warning signal interface
196+ InterfaceInfo warning_interface_info;
197+ warning_interface_info.name = hardware_interface::WARNING_SIGNAL_INTERFACE_NAME;
198+ warning_interface_info.data_type = " array<int8_t>[32]" ;
199+ InterfaceDescription warning_interface_descr (info_.name , warning_interface_info);
200+ warning_signal_ = std::make_shared<StateInterface>(warning_interface_descr);
201+ // create warning signal report message interface
202+ InterfaceInfo warning_msg_interface_info;
203+ warning_msg_interface_info.name = hardware_interface::WARNING_SIGNAL_MESSAGE_INTERFACE_NAME;
204+ warning_msg_interface_info.data_type = " array<string>[32]" ;
205+ InterfaceDescription warning_msg_interface_descr (info_.name , warning_msg_interface_info);
206+ warning_signal_message_ = std::make_shared<StateInterface>(warning_msg_interface_descr);
207+ }
208+
159209 // / Exports all state interfaces for this hardware interface.
160210 /* *
161211 * Old way of exporting the StateInterfaces. If a empty vector is returned then
@@ -230,6 +280,14 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
230280 actuator_states_.insert (std::make_pair (name, state_interface));
231281 state_interfaces.push_back (state_interface);
232282 }
283+
284+ // export warning signal interfaces
285+ state_interfaces.push_back (emergency_stop_);
286+ state_interfaces.push_back (error_signal_);
287+ state_interfaces.push_back (error_signal_message_);
288+ state_interfaces.push_back (warning_signal_);
289+ state_interfaces.push_back (warning_signal_message_);
290+
233291 return state_interfaces;
234292 }
235293
@@ -416,6 +474,35 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
416474 return actuator_commands_.at (interface_name)->get_value ();
417475 }
418476
477+ void set_emergency_stop (const double & emergency_stop)
478+ {
479+ emergency_stop_->set_value (emergency_stop);
480+ }
481+
482+ double get_emergency_stop () const { return emergency_stop_->get_value (); }
483+
484+ void set_error_code (const double & error_code) { error_signal_->set_value (error_code); }
485+
486+ double get_error_code () const { return error_signal_->get_value (); }
487+
488+ void set_error_message (const double & error_message)
489+ {
490+ error_signal_message_->set_value (error_message);
491+ }
492+
493+ double get_error_message () const { return error_signal_message_->get_value (); }
494+
495+ void set_warning_code (const double & warning_codes) { warning_signal_->set_value (warning_codes); }
496+
497+ double get_warning_code () const { return warning_signal_->get_value (); }
498+
499+ void set_warning_message (const double & error_message)
500+ {
501+ warning_signal_message_->set_value (error_message);
502+ }
503+
504+ double get_warning_message () const { return warning_signal_message_->get_value (); }
505+
419506protected:
420507 // / Get the logger of the ActuatorInterface.
421508 /* *
@@ -436,13 +523,19 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
436523 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
437524 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
438525
439- rclcpp_lifecycle::State lifecycle_state_;
440-
441526private:
442527 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
443528 rclcpp::Logger actuator_logger_;
444529 std::unordered_map<std::string, std::shared_ptr<StateInterface>> actuator_states_;
445530 std::unordered_map<std::string, std::shared_ptr<CommandInterface>> actuator_commands_;
531+
532+ std::shared_ptr<StateInterface> emergency_stop_;
533+ std::shared_ptr<StateInterface> error_signal_;
534+ std::shared_ptr<StateInterface> error_signal_message_;
535+ std::shared_ptr<StateInterface> warning_signal_;
536+ std::shared_ptr<StateInterface> warning_signal_message_;
537+
538+ rclcpp_lifecycle::State lifecycle_state_;
446539};
447540
448541} // namespace hardware_interface
0 commit comments