16 #ifndef IGN_ROS2_CONTROL__IGN_SYSTEM_INTERFACE_HPP_
17 #define IGN_ROS2_CONTROL__IGN_SYSTEM_INTERFACE_HPP_
24 #include <ignition/gazebo/System.hh>
26 #include <hardware_interface/system_interface.hpp>
27 #include <hardware_interface/types/hardware_interface_type_values.hpp>
29 #include <rclcpp/rclcpp.hpp>
31 namespace ign_ros2_control
51 template<class ENUM, class UNDERLYING = typename std::underlying_type<ENUM>::type>
58 : mFlags(singleFlag) {}
60 : mFlags(original.mFlags) {}
62 SafeEnum & operator|=(ENUM addValue) {mFlags |= addValue;
return *
this;}
63 SafeEnum operator|(ENUM addValue) {
SafeEnum result(*
this); result |= addValue;
return result;}
64 SafeEnum & operator&=(ENUM maskValue) {mFlags &= maskValue;
return *
this;}
65 SafeEnum operator&(ENUM maskValue) {
SafeEnum result(*
this); result &= maskValue;
return result;}
66 SafeEnum operator~() {
SafeEnum result(*
this); result.mFlags = ~result.mFlags;
return result;}
67 explicit operator bool() {
return mFlags != 0;}
86 rclcpp::Node::SharedPtr & model_nh,
87 std::map<std::string, ignition::gazebo::Entity> & joints,
89 ignition::gazebo::EntityComponentManager & _ecm,
90 int & update_rate) = 0;
104 rclcpp::Node::SharedPtr nh_;
Definition: system_interface.hpp:73
Definition: ign_system_interface.hpp:76
virtual bool initSim(rclcpp::Node::SharedPtr &model_nh, std::map< std::string, ignition::gazebo::Entity > &joints, const hardware_interface::HardwareInfo &hardware_info, ignition::gazebo::EntityComponentManager &_ecm, int &update_rate)=0
Initialize the system interface param[in] model_nh Pointer to the ros2 node param[in] joints Map with...
This class allows us to handle flags easily, instead of using strings.
Definition: ign_system_interface.hpp:53
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:106