gazebo_ros_bumper.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2012 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
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     // Pointer to the update event connection
00088     private: event::ConnectionPtr update_connection_;
00089   };
00090 }
00091 
00092 #endif
00093 


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Jun 6 2019 18:41:09