ros2_control - rolling
gz_system_interface.hpp
1 // Copyright 2021 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 
16 #ifndef GZ_ROS2_CONTROL__GZ_SYSTEM_INTERFACE_HPP_
17 #define GZ_ROS2_CONTROL__GZ_SYSTEM_INTERFACE_HPP_
18 
19 #include <map>
20 #include <memory>
21 #include <string>
22 #include <vector>
23 
24 #include <gz/sim/System.hh>
25 namespace sim = gz::sim;
26 
27 #include <hardware_interface/system_interface.hpp>
28 #include <hardware_interface/types/hardware_interface_type_values.hpp>
29 
30 #include <rclcpp/rclcpp.hpp>
31 
32 namespace gz_ros2_control
33 {
34 
51 
52 template<class ENUM, class UNDERLYING = typename std::underlying_type<ENUM>::type>
53 class SafeEnum
54 {
55 public:
56  SafeEnum()
57  : mFlags(0) {}
58  explicit SafeEnum(ENUM singleFlag)
59  : mFlags(singleFlag) {}
60  SafeEnum(const SafeEnum & original)
61  : mFlags(original.mFlags) {}
62 
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;}
69 
70 protected:
71  UNDERLYING mFlags;
72 };
73 
74 // SystemInterface provides API-level access to read and command joint properties.
77 {
78 public:
86  virtual bool initSim(
87  rclcpp::Node::SharedPtr & model_nh,
88  std::map<std::string, sim::Entity> & joints,
89  const hardware_interface::HardwareInfo & hardware_info,
90  sim::EntityComponentManager & _ecm,
91  unsigned int update_rate) = 0;
92 
93  // Methods used to control a joint.
94  enum ControlMethod_
95  {
96  NONE = 0,
97  POSITION = (1 << 0),
98  VELOCITY = (1 << 1),
99  EFFORT = (1 << 2),
100  };
101 
102  typedef SafeEnum<enum ControlMethod_> ControlMethod;
103 
104 protected:
105  rclcpp::Node::SharedPtr nh_;
106 };
107 
108 } // namespace gz_ros2_control
109 
110 #endif // GZ_ROS2_CONTROL__GZ_SYSTEM_INTERFACE_HPP_
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