diffdrive_plugin_6w.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  * Desc: ROS interface to a Position2d controller for a Differential drive.
23  * Author: Daniel Hewlett (adapted from Nathan Koenig)
24  */
25 #ifndef DIFFDRIVE_PLUGIN_HH
26 #define DIFFDRIVE_PLUGIN_HH
27 
28 #include <map>
29 
30 #include <gazebo/common/Plugin.hh>
31 #include <gazebo/common/Time.hh>
32 
33 // ROS
34 #include <ros/ros.h>
36 #include <tf/transform_listener.h>
37 #include <geometry_msgs/Twist.h>
38 #include <nav_msgs/Odometry.h>
39 
40 // Custom Callback Queue
41 #include <ros/callback_queue.h>
42 #include <ros/advertise_options.h>
43 
44 // Boost
45 #include <boost/thread.hpp>
46 #include <boost/bind.hpp>
47 
48 namespace gazebo
49 {
50 
51 class DiffDrivePlugin6W : public ModelPlugin
52 {
53 
54 public:
56  virtual ~DiffDrivePlugin6W();
57 
58 protected:
59  virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
60  virtual void Reset();
61  virtual void Update();
62 
63 private:
64  void publish_odometry();
65  void GetPositionCmd();
66 
67  physics::LinkPtr link;
68  physics::WorldPtr world;
69  physics::JointPtr joints[6];
70 
71  float wheelSep;
72  float wheelDiam;
73  float torque;
74  float wheelSpeed[2];
75 
76  // Simulation time of the last update
77  common::Time prevUpdateTime;
78 
80  float odomPose[3];
81  float odomVel[3];
82 
83  // ROS STUFF
88  nav_msgs::Odometry odom_;
89  std::string tf_prefix_;
90 
91  boost::mutex lock;
92 
93  std::string namespace_;
94  std::string topic_;
95  std::string link_name_;
96 
97  // Custom Callback Queue
99  boost::thread callback_queue_thread_;
100  void QueueThread();
101 
102  // DiffDrive stuff
103  void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg);
104 
105  float x_;
106  float rot_;
107  bool alive_;
108 
109  // Pointer to the update event connection
110  event::ConnectionPtr updateConnection;
111 };
112 
113 }
114 
115 #endif
116 
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
physics::JointPtr joints[6]
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
tf::TransformBroadcaster * transform_broadcaster_
event::ConnectionPtr updateConnection


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