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