$search
00001 #ifndef GAZEBO_ROS_KURT_H 00002 #define GAZEBO_ROS_KURT_H 00003 00004 #include <ros/ros.h> 00005 #include <gazebo/Controller.hh> 00006 #include <gazebo/Model.hh> 00007 00008 #include <nav_msgs/Odometry.h> 00009 #include <geometry_msgs/TwistWithCovariance.h> 00010 #include <geometry_msgs/PoseWithCovariance.h> 00011 #include <sensor_msgs/JointState.h> 00012 00013 #include <tf/transform_broadcaster.h> 00014 00015 namespace gazebo 00016 { 00017 class GazeboRosKurt : public Controller 00018 { 00019 public: 00020 GazeboRosKurt(gazebo::Entity *parent); 00021 virtual ~GazeboRosKurt(); 00022 00023 virtual void LoadChild(XMLConfigNode *node); 00024 virtual void InitChild(); 00025 virtual void FiniChild(); 00026 virtual void UpdateChild(); 00027 00028 private: 00029 static const size_t NUM_JOINTS = 6; 00030 static const double CMD_VEL_TIMEOUT = 0.6; 00031 00032 void OnCmdVel(const geometry_msgs::TwistConstPtr &msg); 00033 00034 ros::NodeHandle *rosnode_; 00035 00036 ros::Publisher odom_pub_; 00037 ros::Publisher joint_state_pub_; 00038 00039 ros::Subscriber cmd_vel_sub_; 00040 00041 ParamT<std::string> *robotNamespaceP_; 00042 00043 ParamT<std::string> *cmd_vel_topic_nameP_; 00044 std::string cmd_vel_topic_name_; 00045 ParamT<std::string> *odom_topic_nameP_; 00046 std::string odom_topic_name_; 00047 ParamT<std::string> *joint_states_topic_nameP_; 00048 std::string joint_states_topic_name_; 00049 00050 std::vector<ParamT<std::string> *> joint_nameP_; 00051 00053 ParamT<float> *wheel_sepP_; 00054 00056 ParamT<float> *wheel_diamP_; 00057 00059 ParamT<float> *turning_adaptationP_; 00060 00062 ParamT<float> *torqueP_; 00063 00065 ParamT<float> *max_velocityP_; 00066 00067 Model *my_parent_; 00068 00070 float wheel_speed_right_; 00071 float wheel_speed_left_; 00072 00073 Joint *joints_[NUM_JOINTS]; 00074 00075 // Simulation time of the last update 00076 Time prev_update_time_; 00077 00078 // Simulation time when the last cmd_vel command was received (for timeout) 00079 Time last_cmd_vel_time_; 00080 00081 float odom_pose_[3]; 00082 float odom_vel_[3]; 00083 00084 tf::TransformBroadcaster transform_broadcaster_; 00085 sensor_msgs::JointState js_; 00086 }; 00087 } 00088 #endif