16 #ifndef GZ_ROS2_CONTROL__GZ_SYSTEM_INTERFACE_HPP_
17 #define GZ_ROS2_CONTROL__GZ_SYSTEM_INTERFACE_HPP_
24 #include <gz/sim/System.hh>
25 namespace sim = gz::sim;
27 #include <hardware_interface/system_interface.hpp>
28 #include <hardware_interface/types/hardware_interface_type_values.hpp>
30 #include <rclcpp/rclcpp.hpp>
32 namespace gz_ros2_control
52 template<class ENUM, class UNDERLYING = typename std::underlying_type<ENUM>::type>
59 : mFlags(singleFlag) {}
61 : mFlags(original.mFlags) {}
63 SafeEnum & operator|=(ENUM addValue) {mFlags |= addValue;
return *
this;}
64 SafeEnum operator|(ENUM addValue) {
SafeEnum result(*
this); result |= addValue;
return result;}
65 SafeEnum & operator&=(ENUM maskValue) {mFlags &= maskValue;
return *
this;}
66 SafeEnum operator&(ENUM maskValue) {
SafeEnum result(*
this); result &= maskValue;
return result;}
67 SafeEnum operator~() {
SafeEnum result(*
this); result.mFlags = ~result.mFlags;
return result;}
68 explicit operator bool() {
return mFlags != 0;}
87 rclcpp::Node::SharedPtr & model_nh,
88 std::map<std::string, sim::Entity> & joints,
90 sim::EntityComponentManager & _ecm,
91 unsigned int update_rate) = 0;
105 rclcpp::Node::SharedPtr nh_;
Definition: gz_system_interface.hpp:77
virtual bool initSim(rclcpp::Node::SharedPtr &model_nh, std::map< std::string, sim::Entity > &joints, const hardware_interface::HardwareInfo &hardware_info, sim::EntityComponentManager &_ecm, unsigned 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: gz_system_interface.hpp:54
Definition: system_interface.hpp:83
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:170