gazebo_ros_kurt.h
Go to the documentation of this file.
00001 #ifndef GAZEBO_ROS_KURT_H
00002 #define GAZEBO_ROS_KURT_H
00003 
00004 #include <ros/ros.h>
00005 #include <common/Plugin.hh>
00006 #include <common/Time.hh>
00007 #include <common/Events.hh>
00008 #include <physics/physics.hh>
00009 
00010 #include <geometry_msgs/TwistWithCovariance.h>
00011 #include <sensor_msgs/JointState.h>
00012 
00013 #include <boost/thread.hpp>
00014 
00015 namespace gazebo
00016 {
00017 class GazeboRosKurt : public ModelPlugin
00018 {
00019 public:
00020   GazeboRosKurt();
00021   virtual ~GazeboRosKurt();
00022 
00023   virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
00024   virtual void UpdateChild();
00025 
00026 private:
00027   static const size_t NUM_JOINTS = 6;
00028   static const double CMD_VEL_TIMEOUT = 0.6;
00029 
00030   void OnCmdVel(const geometry_msgs::TwistConstPtr &msg);
00031 
00032   ros::NodeHandle *rosnode_;
00033 
00034   ros::Publisher odom_pub_;
00035   ros::Publisher joint_state_pub_;
00036 
00037   ros::Subscriber cmd_vel_sub_;
00038 
00039   std::string node_namespace_;
00040 
00041   std::string cmd_vel_topic_name_;
00042   std::string odom_topic_name_;
00043   std::string joint_states_topic_name_;
00044 
00046   float wheel_sep_;
00047 
00049   float wheel_diam_;
00050 
00052   float turning_adaptation_;
00053 
00055   float torque_;
00056 
00058   float max_velocity_;
00059 
00060   physics::WorldPtr my_world_;
00061   physics::ModelPtr my_parent_;
00062 
00064   float wheel_speed_right_;
00065   float wheel_speed_left_;
00066 
00067   physics::JointPtr joints_[NUM_JOINTS];
00068 
00069   // Simulation time of the last update
00070   common::Time prev_update_time_;
00071 
00072   // Simulation time when the last cmd_vel command was received (for timeout)
00073   common::Time last_cmd_vel_time_;
00074 
00075   // Pointer to the update event connection
00076   event::ConnectionPtr updateConnection;
00077 
00078   float odom_pose_[3];
00079   float odom_vel_[3];
00080 
00081   sensor_msgs::JointState js_;
00082 
00083   void spin();
00084   boost::thread *spinner_thread_;
00085 
00086 };
00087 }
00088 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


kurt_gazebo_plugins
Author(s): Martin Günther
autogenerated on Tue May 28 2013 17:23:20