gazebo_ros_diffdrive_uos.h
Go to the documentation of this file.
00001 #ifndef GAZEBO_ROS_DIFFDRIVE_UOS
00002 #define GAZEBO_ROS_DIFFDRIVE_UOS
00003 
00004 #include <ros/ros.h>
00005 #include <gazebo/common/Plugin.hh>
00006 #include <gazebo/common/Time.hh>
00007 #include <gazebo/common/Events.hh>
00008 #include <gazebo/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 GazeboRosDiffdrive : public ModelPlugin
00018 {
00019 public:
00020   GazeboRosDiffdrive();
00021   virtual ~GazeboRosDiffdrive();
00022 
00023   virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
00024   virtual void UpdateChild();
00025 
00026 private:
00027   static const double CMD_VEL_TIMEOUT;
00028 
00029   void OnCmdVel(const geometry_msgs::TwistConstPtr &msg);
00030 
00031   ros::NodeHandle *rosnode_;
00032 
00033   ros::Publisher odom_pub_;
00034   ros::Publisher joint_state_pub_;
00035 
00036   ros::Subscriber cmd_vel_sub_;
00037 
00038   std::string node_namespace_;
00039 
00040   std::string cmd_vel_topic_name_;
00041   std::string odom_topic_name_;
00042   std::string joint_states_topic_name_;
00043 
00044   size_t num_joints_;
00045   size_t left, right;
00046 
00048   float wheel_sep_;
00049 
00051   float wheel_diam_;
00052 
00054   float turning_adaptation_;
00055 
00057   float torque_;
00058 
00060   float max_velocity_;
00061 
00062   physics::WorldPtr my_world_;
00063   physics::ModelPtr my_parent_;
00064 
00066   float wheel_speed_right_;
00067   float wheel_speed_left_;
00068 
00069   std::vector<physics::JointPtr> joints_;
00070 
00071   // Simulation time of the last update
00072   common::Time prev_update_time_;
00073 
00074   // Simulation time when the last cmd_vel command was received (for timeout)
00075   common::Time last_cmd_vel_time_;
00076 
00077   // Pointer to the update event connection
00078   event::ConnectionPtr updateConnection;
00079 
00080   float odom_pose_[3];
00081   float odom_vel_[3];
00082 
00083   sensor_msgs::JointState js_;
00084 
00085   void spin();
00086   boost::thread *spinner_thread_;
00087 
00088 };
00089 }
00090 #endif


diffdrive_gazebo_plugin
Author(s): Martin Guenther
autogenerated on Thu Jun 6 2019 18:32:09