servo_plugin.h
Go to the documentation of this file.
1 /*
2  * Gazebo - Outdoor Multi-Robot Simulator
3  * Copyright (C) 2003
4  * Nate Koenig & Andrew Howard
5  *
6  * This program is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  *
11  * This program is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with this program; if not, write to the Free Software
18  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
19  *
20  */
21 
22 #ifndef SERVO_PLUGIN_H
23 #define SERVO_PLUGIN_H
24 
25 #include <gazebo/common/Plugin.hh>
26 #include <gazebo/common/Time.hh>
27 #if (GAZEBO_MAJOR_VERSION < 8)
28 #include <gazebo/math/Quaternion.hh>
29 #endif
30 
31 // ROS
32 #include <ros/ros.h>
34 #include <tf/transform_listener.h>
35 #include <geometry_msgs/QuaternionStamped.h>
36 #include <sensor_msgs/JointState.h>
37 
38 // Boost
39 #include <boost/thread.hpp>
40 #include <boost/bind.hpp>
41 
42 namespace gazebo
43 {
44 
45 class ServoPlugin : public ModelPlugin
46 {
47 
48 public:
49  ServoPlugin();
50  virtual ~ServoPlugin();
51 
52 protected:
53  virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
54  virtual void Init();
55  virtual void Reset();
56  virtual void Update();
57 
58 private:
59  void CalculateVelocities();
60  void publish_joint_states();
61 
62 private:
64  physics::WorldPtr world;
65 
66  // Simulation time of the last update
67  common::Time prevUpdateTime;
68 
70 
71  struct Servo {
72  std::string name;
73 #if (GAZEBO_MAJOR_VERSION >= 8)
74  ignition::math::Vector3d axis;
75 #else
76  math::Vector3 axis;
77 #endif
78  physics::JointPtr joint;
79  float velocity;
80  Servo() : velocity() {}
81  } servo[3];
82 
83  unsigned int countOfServos;
84  unsigned int orderOfAxes[3];
85  unsigned int rotationConv;
86  sensor_msgs::JointState joint_state;
87 
88  // parameters
89  std::string robotNamespace;
90  std::string topicName;
91  std::string jointStateName;
92  common::Time controlPeriod;
93 
98 
99  // ROS STUFF
104 
105  // Custom Callback Queue
107 // boost::thread* callback_queue_thread_;
108 // void QueueThread();
109 
110  // DiffDrive stuff
111  void cmdCallback(const geometry_msgs::QuaternionStamped::ConstPtr& cmd_msg);
112 
113  boost::mutex mutex;
114  geometry_msgs::QuaternionStamped::ConstPtr current_cmd;
115 #if (GAZEBO_MAJOR_VERSION >= 8)
116  ignition::math::Quaterniond rotation_;
117 #else
118  math::Quaternion rotation_;
119 #endif
120 
121  // Pointer to the update event connection
122  event::ConnectionPtr updateConnection;
123 };
124 
125 }
126 
127 #endif
std::string topicName
Definition: servo_plugin.h:90
common::Time prevUpdateTime
Definition: servo_plugin.h:67
unsigned int countOfServos
Definition: servo_plugin.h:83
event::ConnectionPtr updateConnection
Definition: servo_plugin.h:122
ros::Publisher jointStatePub_
Definition: servo_plugin.h:101
tf::TransformListener * transform_listener_
Definition: servo_plugin.h:103
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
math::Quaternion rotation_
Definition: servo_plugin.h:118
float proportionalControllerGain
Definition: servo_plugin.h:94
unsigned int orderOfAxes[3]
Definition: servo_plugin.h:84
ros::CallbackQueue queue_
Definition: servo_plugin.h:106
void cmdCallback(const geometry_msgs::QuaternionStamped::ConstPtr &cmd_msg)
ros::Subscriber sub_
Definition: servo_plugin.h:102
physics::WorldPtr world
The parent World.
Definition: servo_plugin.h:64
virtual void Reset()
unsigned int rotationConv
Definition: servo_plugin.h:85
common::Time controlPeriod
Definition: servo_plugin.h:92
std::string jointStateName
Definition: servo_plugin.h:91
geometry_msgs::QuaternionStamped::ConstPtr current_cmd
Definition: servo_plugin.h:114
std::string robotNamespace
Definition: servo_plugin.h:89
boost::mutex mutex
Definition: servo_plugin.h:113
physics::JointPtr joint
Definition: servo_plugin.h:78
float derivativeControllerGain
Definition: servo_plugin.h:95
ros::NodeHandle * rosnode_
Definition: servo_plugin.h:100
struct gazebo::ServoPlugin::Servo servo[3]
virtual void Update()
virtual void Init()
sensor_msgs::JointState joint_state
Definition: servo_plugin.h:86


hector_gazebo_plugins
Author(s): Stefan Kohlbrecher , Johannes Meyer
autogenerated on Wed Jun 5 2019 22:40:23