Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef GAZEBO_ROS_BUMPER_HH
00019 #define GAZEBO_ROS_BUMPER_HH
00020
00021 #include <string>
00022
00023 #include <ros/ros.h>
00024 #include <ros/callback_queue.h>
00025 #include <ros/advertise_options.h>
00026
00027 #include <sys/time.h>
00028
00029 #include <boost/thread.hpp>
00030 #include <boost/thread/mutex.hpp>
00031
00032 #include <std_msgs/String.h>
00033
00034 #include <gazebo_msgs/ContactState.h>
00035 #include <gazebo_msgs/ContactsState.h>
00036
00037 #include <gazebo/sensors/sensors.hh>
00038 #include <gazebo/msgs/msgs.hh>
00039 #include <gazebo/physics/physics.hh>
00040 #include <sdf/sdf.hh>
00041 #include <gazebo/transport/TransportTypes.hh>
00042 #include <gazebo/msgs/MessageTypes.hh>
00043 #include <gazebo/common/Time.hh>
00044 #include <gazebo/sensors/SensorTypes.hh>
00045 #include <gazebo/sensors/ContactSensor.hh>
00046 #include <gazebo/common/Plugin.hh>
00047
00048 namespace gazebo
00049 {
00051 class GazeboRosBumper : public SensorPlugin
00052 {
00054 public: GazeboRosBumper();
00055
00057 public: ~GazeboRosBumper();
00058
00061 public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
00062
00064 private: void OnContact();
00065
00067 private: ros::NodeHandle* rosnode_;
00068 private: ros::Publisher contact_pub_;
00069
00070 private: sensors::ContactSensorPtr parentSensor;
00071
00073 private: std::string bumper_topic_name_;
00074
00075 private: std::string frame_name_;
00076
00078 private: gazebo_msgs::ContactsState contact_state_msg_;
00079
00081 private: std::string robot_namespace_;
00082
00083 private: ros::CallbackQueue contact_queue_;
00084 private: void ContactQueueThread();
00085 private: boost::thread callback_queue_thread_;
00086
00087
00088 private: event::ConnectionPtr update_connection_;
00089 };
00090 }
00091
00092 #endif
00093