00001 #ifndef GAZEBO_ROS_CREATE_H 00002 #define GAZEBO_ROS_CREATE_H 00003 00004 #include <gazebo/physics/physics.hh> 00005 #include <gazebo/physics/PhysicsTypes.hh> 00006 #include <gazebo/sensors/SensorTypes.hh> 00007 #include <gazebo/transport/TransportTypes.hh> 00008 #include <gazebo/common/Time.hh> 00009 #include <gazebo/common/Plugin.hh> 00010 #include <gazebo/common/Events.hh> 00011 00012 #include <nav_msgs/Odometry.h> 00013 #include <geometry_msgs/TwistWithCovariance.h> 00014 #include <geometry_msgs/PoseWithCovariance.h> 00015 #include <tf/transform_broadcaster.h> 00016 #include <ros/ros.h> 00017 00018 namespace gazebo 00019 { 00020 class GazeboRosCreate : public ModelPlugin 00021 { 00022 public: 00023 GazeboRosCreate(); 00024 virtual ~GazeboRosCreate(); 00025 00026 virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf ); 00027 00028 virtual void UpdateChild(); 00029 00030 private: 00031 00032 void UpdateSensors(); 00033 void OnContact(const std::string &name, const physics::Contact &contact); 00034 void OnCmdVel( const geometry_msgs::TwistConstPtr &msg); 00035 00036 00038 std::string node_namespace_; 00039 std::string left_wheel_joint_name_; 00040 std::string right_wheel_joint_name_; 00041 std::string front_castor_joint_name_; 00042 std::string rear_castor_joint_name_; 00043 std::string base_geom_name_; 00044 00046 float wheel_sep_; 00047 00049 float wheel_diam_; 00050 00052 float torque_; 00053 00054 00055 ros::NodeHandle *rosnode_; 00056 //ros::Service operating_mode_srv_; 00057 //ros::Service digital_output_srv_; 00058 00059 ros::Publisher sensor_state_pub_; 00060 ros::Publisher odom_pub_; 00061 ros::Publisher joint_state_pub_; 00062 00063 ros::Subscriber cmd_vel_sub_; 00064 00065 physics::WorldPtr my_world_; 00066 physics::ModelPtr my_parent_; 00067 00069 float *wheel_speed_; 00070 00071 // Simulation time of the last update 00072 common::Time prev_update_time_; 00073 common::Time last_cmd_vel_time_; 00074 00075 float odom_pose_[3]; 00076 float odom_vel_[3]; 00077 00078 bool set_joints_[4]; 00079 physics::JointPtr joints_[4]; 00080 physics::CollisionPtr base_geom_; 00081 00082 sensors::RaySensorPtr left_cliff_sensor_; 00083 sensors::RaySensorPtr leftfront_cliff_sensor_; 00084 sensors::RaySensorPtr rightfront_cliff_sensor_; 00085 sensors::RaySensorPtr right_cliff_sensor_; 00086 sensors::RaySensorPtr wall_sensor_; 00087 00088 tf::TransformBroadcaster transform_broadcaster_; 00089 sensor_msgs::JointState js_; 00090 00091 create_node::TurtlebotSensorState sensor_state_; 00092 00093 void spin(); 00094 boost::thread *spinner_thread_; 00095 00096 event::ConnectionPtr contact_event_; 00097 00098 // Pointer to the update event connection 00099 event::ConnectionPtr updateConnection; 00100 }; 00101 } 00102 #endif