ign_system_interface.hpp
Go to the documentation of this file.
1 // Copyright 2022 The 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_INTERFACE_HPP_
16 #define IGN_ROS_CONTROL__IGN_SYSTEM_INTERFACE_HPP_
17 
18 #include <ignition/gazebo/System.hh>
19 
20 #include <map>
21 #include <memory>
22 #include <string>
23 #include <vector>
24 
25 #include <ros/ros.h>
28 
29 // ros_control
32 
33 namespace ign_ros_control
34 {
35 
36 // SystemInterface provides API-level access to read and command joint properties.
39 {
40 public:
41 
49  virtual bool initSim(
50  ros::NodeHandle model_nh,
51  std::map<std::string, ignition::gazebo::Entity> & joints,
52  ignition::gazebo::EntityComponentManager & _ecm,
53  std::vector<transmission_interface::TransmissionInfo> transmissions,
54  int & update_rate) = 0;
55 
56  // Methods used to control a joint.
58 
60  virtual void read() = 0;
61  //
63  virtual void write() = 0;
64 
65 protected:
66 
68 };
69 
70 } // namespace ign_ros_control
71 
72 #endif // IGN_ROS_CONTROL__IGN_SYSTEM_INTERFACE_HPP_
ign_ros_control::IgnitionSystemInterface::initSim
virtual 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)=0
Initialize the system interface param[in] model_nh Pointer to the ros node param[in] joints Map with ...
ign_ros_control::IgnitionSystemInterface::read
virtual void read()=0
transmission_info.h
ign_ros_control
Definition: ign_ros_control_plugin.hpp:22
ros.h
ign_ros_control::IgnitionSystemInterface::VELOCITY_PID
@ VELOCITY_PID
Definition: ign_system_interface.hpp:57
ign_ros_control::IgnitionSystemInterface::POSITION
@ POSITION
Definition: ign_system_interface.hpp:57
ign_ros_control::IgnitionSystemInterface::POSITION_PID
@ POSITION_PID
Definition: ign_system_interface.hpp:57
ign_ros_control::IgnitionSystemInterface::nh_
ros::NodeHandle nh_
Definition: ign_system_interface.hpp:67
ign_ros_control::IgnitionSystemInterface::write
virtual void write()=0
joint_command_interface.h
hardware_interface::RobotHW
ign_ros_control::IgnitionSystemInterface::EFFORT
@ EFFORT
Definition: ign_system_interface.hpp:57
ign_ros_control::IgnitionSystemInterface
Definition: ign_system_interface.hpp:37
ign_ros_control::IgnitionSystemInterface::ControlMethod
ControlMethod
Definition: ign_system_interface.hpp:57
robot_hw.h
ign_ros_control::IgnitionSystemInterface::VELOCITY
@ VELOCITY
Definition: ign_system_interface.hpp:57
ros::NodeHandle


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