husky_plugin.h
Go to the documentation of this file.
00001 #ifndef GAZEBO_ROS_CREATE_H
00002 #define GAZEBO_ROS_CREATE_H
00003 
00004 #include "physics/physics.h"
00005 #include "physics/PhysicsTypes.hh"
00006 #include "sensors/SensorTypes.hh"
00007 #include "transport/TransportTypes.hh"
00008 #include "common/Time.hh"
00009 #include "common/Plugin.hh"
00010 #include "common/Events.hh"
00011 
00012 #include <nav_msgs/Odometry.h>
00013 #include <geometry_msgs/TwistWithCovariance.h>
00014 #include <geometry_msgs/PoseWithCovariance.h>
00015 
00016 #include <tf/transform_broadcaster.h>
00017 #include <ros/ros.h>
00018 
00019 
00020 /*
00021  * Desc: Gazebo 1.x plugin for a Clearpath Robotics Husky A200
00022  * Adapted from the TurtleBot plugin
00023  * Author: Ryan Gariepy
00024  */ 
00025 
00026 namespace gazebo
00027 {
00028   class HuskyPlugin : public ModelPlugin
00029   {
00030     public: 
00031       HuskyPlugin();
00032       virtual ~HuskyPlugin();
00033           
00034       virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf );
00035 
00036       virtual void UpdateChild();
00037   
00038     private:
00039 
00040       void OnContact(const std::string &name, const physics::Contact &contact);
00041       void OnCmdVel( const geometry_msgs::TwistConstPtr &msg);
00042 
00043 
00045       std::string node_namespace_;
00046       std::string bl_joint_name_;
00047       std::string br_joint_name_;
00048       std::string fl_joint_name_;
00049       std::string fr_joint_name_;
00050       std::string base_geom_name_;
00051 
00053       float wheel_sep_;
00054 
00056       float wheel_diam_;
00057 
00059       float torque_;
00060 
00061       ros::NodeHandle *rosnode_;
00062   
00063       ros::Publisher sensor_state_pub_;
00064       ros::Publisher odom_pub_;
00065       ros::Publisher joint_state_pub_;
00066   
00067       ros::Subscriber cmd_vel_sub_;
00068 
00069       physics::WorldPtr world_;
00070       physics::ModelPtr model_;
00071       sensors::SensorPtr parent_sensor_;
00072 
00074       float *wheel_speed_;
00075 
00076       // Simulation time of the last update
00077       common::Time prev_update_time_;
00078       common::Time last_cmd_vel_time_;
00079 
00080       float odom_pose_[3];
00081       float odom_vel_[3];
00082 
00083       bool set_joints_[4];
00084       physics::JointPtr joints_[4];
00085       physics::CollisionPtr base_geom_;
00086 
00087       tf::TransformBroadcaster transform_broadcaster_;
00088       sensor_msgs::JointState js_;
00089 
00090       void spin();
00091       boost::thread *spinner_thread_;
00092 
00093       // Pointer to the update event connection
00094       event::ConnectionPtr updateConnection;
00095 
00096       bool kill_sim;
00097   };
00098 }
00099 #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