husky_controller.h
Go to the documentation of this file.
00001 /*
00002  *  Gazebo - Outdoor Multi-Robot Simulator
00003  *  Copyright (C) 2003
00004  *     Nate Koenig & Andrew Howard
00005  *
00006  *  This program is free software; you can redistribute it and/or modify
00007  *  it under the terms of the GNU General Public License as published by
00008  *  the Free Software Foundation; either version 2 of the License, or
00009  *  (at your option) any later version.
00010  *
00011  *  This program is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014  *  GNU General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU General Public License
00017  *  along with this program; if not, write to the Free Software
00018  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  *
00020  */
00021 /*
00022  * Desc: ROS interface to a Position controller for a Differential drive Husky Robot
00023  * Author: Siddhant Ahuja (adapted from Daniel Hewlett)
00024  */
00025 
00026 #ifndef DIFFDRIVE_PLUGIN_HH
00027 #define DIFFDRIVE_PLUGIN_HH
00028 
00029 #include <map>
00030 
00031 #include <gazebo/Param.hh>
00032 #include <gazebo/Controller.hh>
00033 #include <gazebo/Model.hh>
00034 
00035 // ROS 
00036 #include <ros/ros.h>
00037 #include <tf/transform_broadcaster.h>
00038 #include <tf/transform_listener.h>
00039 #include <geometry_msgs/Twist.h>
00040 #include <nav_msgs/Odometry.h>
00041 
00042 // Custom Callback Queue
00043 #include <ros/callback_queue.h>
00044 #include <ros/advertise_options.h>
00045 
00046 // Boost
00047 #include <boost/thread.hpp>
00048 #include <boost/bind.hpp>
00049 
00050 namespace gazebo
00051 {
00052         class Joint;
00053         class Entity;
00054 
00055         class DiffDrivePlugin : public Controller
00056         {
00057                 public:
00058                         DiffDrivePlugin(Entity *parent);
00059                         virtual ~DiffDrivePlugin();     
00060 
00061                 protected:
00062                         virtual void LoadChild(XMLConfigNode *node);
00063                         void SaveChild(std::string &prefix, std::ostream &stream);
00064                         virtual void InitChild();
00065                         void ResetChild();
00066                         virtual void UpdateChild();
00067                         virtual void FiniChild();
00068 
00069                 private:
00070                         void write_position_data();
00071                         void publish_odometry();
00072                         void GetPositionCmd();
00073 
00074                         libgazebo::PositionIface *pos_iface_;
00075                         Model *parent_;
00076                         ParamT<float> *wheelSepP;
00077                         ParamT<float> *wheelDiamP;
00078                         ParamT<float> *torqueP;
00079                         float wheelSpeed[2];
00080 
00081                         // Simulation time of the last update
00082                         Time prevUpdateTime;
00083 
00084                         bool enableMotors;
00085                         float odomPose[3];
00086                         float odomVel[3];
00087 
00088                         Joint *joints[4];
00089                         PhysicsEngine *physicsEngine;
00090                         ParamT<std::string> *backLeftJointNameP;
00091                         ParamT<std::string> *backRightJointNameP;
00092                         ParamT<std::string> *frontLeftJointNameP;
00093                         ParamT<std::string> *frontRightJointNameP;
00094 
00095                         // ROS STUFF
00096                         ros::NodeHandle* rosnode_;
00097                         ros::Publisher pub_;
00098                         ros::Subscriber sub_;
00099                         tf::TransformBroadcaster *transform_broadcaster_;
00100                         nav_msgs::Odometry odom_;
00101                         std::string tf_prefix_;
00102 
00103                         boost::mutex lock;
00104 
00105                         ParamT<std::string> *robotNamespaceP;
00106                         std::string robotNamespace;
00107 
00108                         ParamT<std::string> *topicNameP;
00109                         std::string topicName;
00110 
00111                         // Custom Callback Queue
00112                         ros::CallbackQueue queue_;
00113                         boost::thread* callback_queue_thread_;
00114                         void QueueThread();
00115 
00116                         // DiffDrive stuff
00117                         void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg);
00118 
00119                         float x_;
00120                         float rot_;
00121                         bool alive_;
00122         };
00123 }
00124 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


husky_gazebo_plugins
Author(s): Ryan Gariepy/Clearpath Robotics
autogenerated on Tue Sep 3 2013 10:23:58