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_;
128  // Custom Callback Queue
130  boost::thread callback_queue_thread_;
131  void QueueThread();
132 
133  // DiffDrive stuff
134  void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg);
135 
136  double x_;
137  double rot_;
138  bool alive_;
139 
140  // Update Rate
141  double update_rate_;
143  common::Time last_update_time_;
144 
146  geometry_msgs::Pose2D pose_encoder_;
147  common::Time last_odom_update_;
148 
149  // Flags
153 
154  };
155 
156 }
157 
158 #endif
gazebo::GazeboRosDiffDrive::odom_source_
OdomSource odom_source_
Definition: gazebo_ros_diff_drive.h:145
gazebo::GazeboRosDiffDrive::wheel_torque
double wheel_torque
Definition: gazebo_ros_diff_drive.h:104
ros::Publisher
gazebo::GazeboRosDiffDrive::odometry_publisher_
ros::Publisher odometry_publisher_
Definition: gazebo_ros_diff_drive.h:112
gazebo::GazeboRosDiffDrive::parent
physics::ModelPtr parent
Definition: gazebo_ros_diff_drive.h:99
gazebo::GazeboRosDiffDrive::wheel_accel
double wheel_accel
Definition: gazebo_ros_diff_drive.h:106
gazebo::GazeboRosDiffDrive::transform_broadcaster_
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
Definition: gazebo_ros_diff_drive.h:114
boost::shared_ptr< GazeboRos >
gazebo
gazebo::GazeboRosDiffDrive::robot_namespace_
std::string robot_namespace_
Definition: gazebo_ros_diff_drive.h:122
gazebo::GazeboRosDiffDrive::publishWheelTF_
bool publishWheelTF_
Definition: gazebo_ros_diff_drive.h:150
gazebo::GazeboRosDiffDrive::QueueThread
void QueueThread()
Definition: gazebo_ros_diff_drive.cpp:342
gazebo::GazeboRosDiffDrive::tf_prefix_
std::string tf_prefix_
Definition: gazebo_ros_diff_drive.h:118
gazebo::GazeboRosDiffDrive::alive_
bool alive_
Definition: gazebo_ros_diff_drive.h:138
gazebo::GazeboRosDiffDrive::publishOdometry
void publishOdometry(double step_time)
Definition: gazebo_ros_diff_drive.cpp:402
gazebo::GazeboRosDiffDrive::publishWheelJointState_
bool publishWheelJointState_
Definition: gazebo_ros_diff_drive.h:152
ros.h
gazebo::GazeboRosDiffDrive::UpdateOdometryEncoder
void UpdateOdometryEncoder()
Definition: gazebo_ros_diff_drive.cpp:351
gazebo::GazeboRosDiffDrive::cmd_vel_subscriber_
ros::Subscriber cmd_vel_subscriber_
Definition: gazebo_ros_diff_drive.h:113
gazebo::GazeboRosDiffDrive::Reset
void Reset()
Definition: gazebo_ros_diff_drive.cpp:183
gazebo::GazeboRosDiffDrive::odometry_frame_
std::string odometry_frame_
Definition: gazebo_ros_diff_drive.h:125
gazebo::GazeboRosDiffDrive::odom_
nav_msgs::Odometry odom_
Definition: gazebo_ros_diff_drive.h:117
gazebo::GazeboRosDiffDrive::wheel_diameter_
double wheel_diameter_
Definition: gazebo_ros_diff_drive.h:103
gazebo::GazeboRosDiffDrive::wheel_separation_
double wheel_separation_
Definition: gazebo_ros_diff_drive.h:102
gazebo::GazeboRosDiffDrive::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Definition: gazebo_ros_diff_drive.cpp:84
gazebo::GazeboRosDiffDrive::getWheelVelocities
void getWheelVelocities()
Definition: gazebo_ros_diff_drive.cpp:324
gazebo::GazeboRosDiffDrive::WORLD
@ WORLD
Definition: gazebo_ros_diff_drive.h:78
transform_broadcaster.h
gazebo::GazeboRosDiffDrive::x_
double x_
Definition: gazebo_ros_diff_drive.h:136
gazebo::GazeboRosDiffDrive::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_diff_drive.h:129
gazebo::GazeboRosDiffDrive::rot_
double rot_
Definition: gazebo_ros_diff_drive.h:137
gazebo::GazeboRosDiffDrive::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_diff_drive.h:130
gazebo::GazeboRosDiffDrive::last_update_time_
common::Time last_update_time_
Definition: gazebo_ros_diff_drive.h:143
gazebo::GazeboRosDiffDrive::OdomSource
OdomSource
Definition: gazebo_ros_diff_drive.h:75
ros::CallbackQueue
gazebo::GazeboRosDiffDrive::pose_encoder_
geometry_msgs::Pose2D pose_encoder_
Definition: gazebo_ros_diff_drive.h:146
gazebo::GazeboRosDiffDrive::publishWheelTF
void publishWheelTF()
Definition: gazebo_ros_diff_drive.cpp:220
gazebo::GazeboRosDiffDrive::ENCODER
@ ENCODER
Definition: gazebo_ros_diff_drive.h:77
gazebo::GazeboRosDiffDrive::joint_state_
sensor_msgs::JointState joint_state_
Definition: gazebo_ros_diff_drive.h:115
gazebo::GazeboRosDiffDrive::FiniChild
virtual void FiniChild()
Definition: gazebo_ros_diff_drive.cpp:315
gazebo::GazeboRosDiffDrive::lock
boost::mutex lock
Definition: gazebo_ros_diff_drive.h:120
gazebo::GazeboRosDiffDrive::last_odom_update_
common::Time last_odom_update_
Definition: gazebo_ros_diff_drive.h:147
gazebo::GazeboRosDiffDrive::~GazeboRosDiffDrive
~GazeboRosDiffDrive()
Definition: gazebo_ros_diff_drive.cpp:78
gazebo::GazeboRosDiffDrive::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
Definition: gazebo_ros_diff_drive.cpp:335
callback_queue.h
gazebo::GazeboRosDiffDrive::UpdateChild
virtual void UpdateChild()
Definition: gazebo_ros_diff_drive.cpp:244
gazebo::GazeboRosDiffDrive::joint_state_publisher_
ros::Publisher joint_state_publisher_
Definition: gazebo_ros_diff_drive.h:116
gazebo::GazeboRosDiffDrive::update_rate_
double update_rate_
Definition: gazebo_ros_diff_drive.h:141
transform_listener.h
advertise_options.h
gazebo::GazeboRosDiffDrive::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_diff_drive.h:100
gazebo::GazeboRosDiffDrive
Definition: gazebo_ros_diff_drive.h:73
gazebo::GazeboRosDiffDrive::wheel_speed_instr_
double wheel_speed_instr_[2]
Definition: gazebo_ros_diff_drive.h:107
gazebo::GazeboRosDiffDrive::publishWheelJointState
void publishWheelJointState()
publishes the wheel tf's
Definition: gazebo_ros_diff_drive.cpp:199
gazebo::GazeboRosDiffDrive::robot_base_frame_
std::string robot_base_frame_
Definition: gazebo_ros_diff_drive.h:126
gazebo::GazeboRosDiffDrive::publish_tf_
bool publish_tf_
Definition: gazebo_ros_diff_drive.h:127
gazebo::GazeboRosDiffDrive::wheel_speed_
double wheel_speed_[2]
Definition: gazebo_ros_diff_drive.h:105
gazebo::GazeboRosDiffDrive::joints_
std::vector< physics::JointPtr > joints_
Definition: gazebo_ros_diff_drive.h:109
gazebo_ros_utils.h
gazebo::GazeboRosDiffDrive::gazebo_ros_
GazeboRosPtr gazebo_ros_
Definition: gazebo_ros_diff_drive.h:98
gazebo::GazeboRosDiffDrive::command_topic_
std::string command_topic_
Definition: gazebo_ros_diff_drive.h:123
gazebo::GazeboRosDiffDrive::GazeboRosDiffDrive
GazeboRosDiffDrive()
Definition: gazebo_ros_diff_drive.cpp:75
gazebo::GazeboRosDiffDrive::publishOdomTF_
bool publishOdomTF_
Definition: gazebo_ros_diff_drive.h:151
ros::Subscriber
gazebo::GazeboRosDiffDrive::update_period_
double update_period_
Definition: gazebo_ros_diff_drive.h:142
gazebo::GazeboRosDiffDrive::odometry_topic_
std::string odometry_topic_
Definition: gazebo_ros_diff_drive.h:124


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28