gazebo_ros_diff_drive.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, Daniel Hewlett, Antons Rebguns
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * * Redistributions of source code must retain the above copyright
8  * notice, this list of conditions and the following disclaimer.
9  * * Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * * Neither the name of the <organization> nor the
13  * names of its contributors may be used to endorse or promote products
14  * derived from this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY
17  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19  * DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY
20  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26  *
27  **/
28 
29 /*
30  * \file gazebo_ros_diff_drive.h
31  *
32  * \brief A differential drive plugin for gazebo. Based on the diffdrive plugin
33  * developed for the erratic robot (see copyright notice above). The original
34  * plugin can be found in the ROS package gazebo_erratic_plugins.
35  *
36  * \author Piyush Khandelwal (piyushk@gmail.com)
37  *
38  * $ Id: 06/21/2013 11:23:40 AM piyushk $
39  */
40 
41 #ifndef DIFFDRIVE_PLUGIN_HH
42 #define DIFFDRIVE_PLUGIN_HH
43 
44 #include <map>
45 
46 // Gazebo
47 #include <gazebo/common/common.hh>
48 #include <gazebo/physics/physics.hh>
50 
51 // ROS
52 #include <ros/ros.h>
54 #include <tf/transform_listener.h>
55 #include <geometry_msgs/Twist.h>
56 #include <geometry_msgs/Pose2D.h>
57 #include <nav_msgs/Odometry.h>
58 #include <sensor_msgs/JointState.h>
59 
60 // Custom Callback Queue
61 #include <ros/callback_queue.h>
62 #include <ros/advertise_options.h>
63 
64 // Boost
65 #include <boost/thread.hpp>
66 #include <boost/bind.hpp>
67 
68 namespace gazebo {
69 
70  class Joint;
71  class Entity;
72 
73  class GazeboRosDiffDrive : public ModelPlugin {
74 
76  {
77  ENCODER = 0,
78  WORLD = 1,
79  };
80  public:
83  void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
84  void Reset();
85 
86  protected:
87  virtual void UpdateChild();
88  virtual void FiniChild();
89 
90  private:
91  void publishOdometry(double step_time);
92  void getWheelVelocities();
93  void publishWheelTF();
95  void UpdateOdometryEncoder();
96 
97 
99  physics::ModelPtr parent;
100  event::ConnectionPtr update_connection_;
101 
104  double wheel_torque;
105  double wheel_speed_[2];
106  double wheel_accel;
108 
109  std::vector<physics::JointPtr> joints_;
110 
111  // ROS STUFF
115  sensor_msgs::JointState joint_state_;
117  nav_msgs::Odometry odom_;
118  std::string tf_prefix_;
119 
120  boost::mutex lock;
121 
122  std::string robot_namespace_;
123  std::string command_topic_;
124  std::string odometry_topic_;
125  std::string odometry_frame_;
126  std::string robot_base_frame_;
129  // Custom Callback Queue
131  boost::thread callback_queue_thread_;
132  void QueueThread();
133 
134  // DiffDrive stuff
135  void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg);
136 
137  double x_;
138  double rot_;
139  bool alive_;
140 
141  // Update Rate
142  double update_rate_;
144  common::Time last_update_time_;
145 
147  geometry_msgs::Pose2D pose_encoder_;
148  common::Time last_odom_update_;
149 
150  // Flags
153 
154  };
155 
156 }
157 
158 #endif
159 
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
event::ConnectionPtr update_connection_
sensor_msgs::JointState joint_state_
void publishOdometry(double step_time)
void publishWheelJointState()
publishes the wheel tf&#39;s
geometry_msgs::Pose2D pose_encoder_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
std::vector< physics::JointPtr > joints_


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Mar 26 2019 02:31:27