00001 /* 00002 * Copyright (c) 2010, Daniel Hewlett, Antons Rebguns 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * * Redistributions of source code must retain the above copyright 00008 * notice, this list of conditions and the following disclaimer. 00009 * * Redistributions in binary form must reproduce the above copyright 00010 * notice, this list of conditions and the following disclaimer in the 00011 * documentation and/or other materials provided with the distribution. 00012 * * Neither the name of the <organization> nor the 00013 * names of its contributors may be used to endorse or promote products 00014 * derived from this software without specific prior written permission. 00015 * 00016 * THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY 00017 * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00018 * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00019 * DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY 00020 * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00021 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00022 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00023 * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00024 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00025 * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 * 00027 **/ 00028 00029 /* 00030 * \file gazebo_ros_diff_drive.h 00031 * 00032 * \brief A differential drive plugin for gazebo. Based on the diffdrive plugin 00033 * developed for the erratic robot (see copyright notice above). The original 00034 * plugin can be found in the ROS package gazebo_erratic_plugins. 00035 * 00036 * \author Piyush Khandelwal (piyushk@gmail.com) 00037 * 00038 * $ Id: 06/21/2013 11:23:40 AM piyushk $ 00039 */ 00040 00041 #ifndef DIFFDRIVE_PLUGIN_HH 00042 #define DIFFDRIVE_PLUGIN_HH 00043 00044 #include <map> 00045 00046 // Gazebo 00047 #include <gazebo/common/common.hh> 00048 #include <gazebo/physics/physics.hh> 00049 #include <gazebo_plugins/gazebo_ros_utils.h> 00050 00051 // ROS 00052 #include <ros/ros.h> 00053 #include <tf/transform_broadcaster.h> 00054 #include <tf/transform_listener.h> 00055 #include <geometry_msgs/Twist.h> 00056 #include <geometry_msgs/Pose2D.h> 00057 #include <nav_msgs/Odometry.h> 00058 #include <sensor_msgs/JointState.h> 00059 00060 // Custom Callback Queue 00061 #include <ros/callback_queue.h> 00062 #include <ros/advertise_options.h> 00063 00064 // Boost 00065 #include <boost/thread.hpp> 00066 #include <boost/bind.hpp> 00067 00068 namespace gazebo { 00069 00070 class Joint; 00071 class Entity; 00072 00073 class GazeboRosDiffDrive : public ModelPlugin { 00074 00075 enum OdomSource 00076 { 00077 ENCODER = 0, 00078 WORLD = 1, 00079 }; 00080 public: 00081 GazeboRosDiffDrive(); 00082 ~GazeboRosDiffDrive(); 00083 void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf); 00084 00085 protected: 00086 virtual void UpdateChild(); 00087 virtual void FiniChild(); 00088 00089 private: 00090 void publishOdometry(double step_time); 00091 void getWheelVelocities(); 00092 void publishWheelTF(); 00093 void publishWheelJointState(); 00094 void UpdateOdometryEncoder(); 00095 00096 00097 GazeboRosPtr gazebo_ros_; 00098 physics::ModelPtr parent; 00099 event::ConnectionPtr update_connection_; 00100 00101 double wheel_separation_; 00102 double wheel_diameter_; 00103 double wheel_torque; 00104 double wheel_speed_[2]; 00105 double wheel_accel; 00106 double wheel_speed_instr_[2]; 00107 00108 std::vector<physics::JointPtr> joints_; 00109 00110 // ROS STUFF 00111 ros::Publisher odometry_publisher_; 00112 ros::Subscriber cmd_vel_subscriber_; 00113 boost::shared_ptr<tf::TransformBroadcaster> transform_broadcaster_; 00114 sensor_msgs::JointState joint_state_; 00115 ros::Publisher joint_state_publisher_; 00116 nav_msgs::Odometry odom_; 00117 std::string tf_prefix_; 00118 00119 boost::mutex lock; 00120 00121 std::string robot_namespace_; 00122 std::string command_topic_; 00123 std::string odometry_topic_; 00124 std::string odometry_frame_; 00125 std::string robot_base_frame_; 00126 bool publish_tf_; 00127 // Custom Callback Queue 00128 ros::CallbackQueue queue_; 00129 boost::thread callback_queue_thread_; 00130 void QueueThread(); 00131 00132 // DiffDrive stuff 00133 void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg); 00134 00135 double x_; 00136 double rot_; 00137 bool alive_; 00138 00139 // Update Rate 00140 double update_rate_; 00141 double update_period_; 00142 common::Time last_update_time_; 00143 00144 OdomSource odom_source_; 00145 geometry_msgs::Pose2D pose_encoder_; 00146 common::Time last_odom_update_; 00147 00148 // Flags 00149 bool publishWheelTF_; 00150 bool publishWheelJointState_; 00151 00152 }; 00153 00154 } 00155 00156 #endif 00157