ign_system.hpp
Go to the documentation of this file.
1 // Copyright 2022 ros_control team.
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 #ifndef IGN_ROS_CONTROL__IGN_SYSTEM_HPP_
16 #define IGN_ROS_CONTROL__IGN_SYSTEM_HPP_
17 
18 #include <map>
19 #include <memory>
20 #include <string>
21 #include <vector>
22 
24 
25 namespace ign_ros_control
26 {
27 // Forward declaration
28 class IgnitionSystemPrivate;
29 
30 // These class must inherit `ign_ros_control::IgnitionSystemInterface` which implements a
31 // simulated `ros_control` `hardware_interface::SystemInterface`.
32 
34 {
35 public:
36 
38 
39  virtual ~IgnitionSystem() override;
40 
42  virtual void read() override;
43  //
45  virtual void write() override;
46 
47  // Documentation Inherited
48  bool initSim(
49  ros::NodeHandle model_nh,
50  std::map<std::string, ignition::gazebo::Entity> & joints,
51  ignition::gazebo::EntityComponentManager & ecm,
52  std::vector<transmission_interface::TransmissionInfo> transmissions,
53  int & update_rate) override;
54 
55 private:
56 
58  std::unique_ptr<IgnitionSystemPrivate> dataPtr;
59 
64 };
65 
66 } // namespace ign_ros_control
67 
68 #endif // IGN_ROS_CONTROL__IGN_SYSTEM_HPP_
ign_ros_control::IgnitionSystem::pj_interface_
hardware_interface::PositionJointInterface pj_interface_
Definition: ign_system.hpp:62
ign_ros_control::IgnitionSystem::~IgnitionSystem
virtual ~IgnitionSystem() override
ign_ros_control
Definition: ign_ros_control_plugin.hpp:22
hardware_interface::JointStateInterface
ign_ros_control::IgnitionSystem::IgnitionSystem
IgnitionSystem()
Definition: ign_system.cpp:94
hardware_interface::VelocityJointInterface
ign_ros_control::IgnitionSystem::read
virtual void read() override
Definition: ign_system.cpp:248
ign_ros_control::IgnitionSystem::ej_interface_
hardware_interface::EffortJointInterface ej_interface_
Definition: ign_system.hpp:61
ign_ros_control::IgnitionSystem::js_interface_
hardware_interface::JointStateInterface js_interface_
Definition: ign_system.hpp:60
hardware_interface::EffortJointInterface
ign_ros_control::IgnitionSystem
Definition: ign_system.hpp:33
ign_ros_control::IgnitionSystem::write
virtual void write() override
Definition: ign_system.cpp:273
ign_ros_control::IgnitionSystem::vj_interface_
hardware_interface::VelocityJointInterface vj_interface_
Definition: ign_system.hpp:63
ign_ros_control::IgnitionSystemInterface
Definition: ign_system_interface.hpp:37
ign_ros_control::IgnitionSystem::initSim
bool initSim(ros::NodeHandle model_nh, std::map< std::string, ignition::gazebo::Entity > &joints, ignition::gazebo::EntityComponentManager &ecm, std::vector< transmission_interface::TransmissionInfo > transmissions, int &update_rate) override
Initialize the system interface param[in] model_nh Pointer to the ros node param[in] joints Map with ...
Definition: ign_system.cpp:102
ign_system_interface.hpp
ign_ros_control::IgnitionSystem::dataPtr
std::unique_ptr< IgnitionSystemPrivate > dataPtr
Private data class.
Definition: ign_system.hpp:58
hardware_interface::PositionJointInterface
ros::NodeHandle


ign_ros_control
Author(s): Gennaro Raiola
autogenerated on Sun Aug 14 2022 02:23:53