gazebo_ros_katana_gripper.h
Go to the documentation of this file.
1 /*
2  * UOS-ROS packages - Robot Operating System code by the University of Osnabrück
3  * Copyright (C) 2011 University of Osnabrück
4  *
5  * This program is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * as published by the Free Software Foundation; either version 2
8  * of the License, or (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program; if not, write to the Free Software
17  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
18  *
19  * gazebo_ros_katana_gripper.cpp
20  *
21  * Created on: 29.08.2011
22  * Author: Martin Günther <mguenthe@uos.de>
23  */
24 #ifndef GAZEBO_ROS_KATANA_H
25 #define GAZEBO_ROS_KATANA_H
26 
27 #include <vector>
28 
32 
33 #include <gazebo/common/Plugin.hh>
34 #include <gazebo/common/Time.hh>
35 #include <gazebo/common/Events.hh>
36 #include <gazebo/physics/physics.hh>
37 
38 #include <katana_msgs/GripperControllerState.h>
39 #include <control_toolbox/pid.h>
40 #include <ros/ros.h>
41 
42 #include <boost/thread.hpp>
43 
44 namespace gazebo
45 {
46 class GazeboRosKatanaGripper : public ModelPlugin
47 {
48 public:
50  virtual ~GazeboRosKatanaGripper();
51 
52  virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
53  virtual void InitChild();
54  virtual void FiniChild();
55  virtual void UpdateChild();
56 
57 private:
59  void updateGains();
60 
61  static const size_t NUM_JOINTS = 2;
62 
64 
65  // ros::Publisher joint_state_pub_;
67 
68  std::string node_namespace_;
69  std::vector<std::string> joint_names_;
70 
72  float torque_;
73 
74  physics::WorldPtr my_world_;
75  physics::ModelPtr my_parent_;
76 
78 
79  physics::JointPtr joints_[NUM_JOINTS];
80 
81  // sensor_msgs::JointState js_;
82 
83  // Simulation time of the last update
84  common::Time prev_update_time_;
85 
86  // Pointer to the update event connection
87  event::ConnectionPtr updateConnection;
88 
90  std::vector<katana_gazebo_plugins::IGazeboRosKatanaGripperAction*> gripper_action_list_;
91 
93 
94  void spin();
95  boost::thread *spinner_thread_;
96 };
97 }
98 #endif
katana_gazebo_plugins::IGazeboRosKatanaGripperAction * active_gripper_action_
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
std::vector< std::string > joint_names_
std::vector< katana_gazebo_plugins::IGazeboRosKatanaGripperAction * > gripper_action_list_
physics::JointPtr joints_[NUM_JOINTS]
float torque_
Torque applied to the joints.


katana_gazebo_plugins
Author(s): Martin Günther
autogenerated on Fri Jan 3 2020 04:01:10