18 #ifndef GAZEBO_ROS_BUMPER_HH 19 #define GAZEBO_ROS_BUMPER_HH 31 #include <boost/thread.hpp> 32 #include <boost/thread/mutex.hpp> 34 #include <std_msgs/String.h> 36 #include <gazebo_msgs/ContactState.h> 37 #include <gazebo_msgs/ContactsState.h> 39 #include <gazebo/sensors/sensors.hh> 40 #include <gazebo/msgs/msgs.hh> 41 #include <gazebo/physics/physics.hh> 43 #include <gazebo/transport/TransportTypes.hh> 44 #include <gazebo/msgs/MessageTypes.hh> 45 #include <gazebo/common/Time.hh> 46 #include <gazebo/sensors/SensorTypes.hh> 47 #include <gazebo/sensors/ContactSensor.hh> 48 #include <gazebo/common/Plugin.hh> 63 public:
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
std::string bumper_topic_name_
set topic name of broadcast
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
~GazeboRosBumper()
Destructor.
ros::CallbackQueue contact_queue_
void ContactQueueThread()
boost::thread callback_queue_thread_
std::string robot_namespace_
for setting ROS name space
event::ConnectionPtr update_connection_
GazeboRosBumper()
Constructor.
void OnContact()
Update the controller.
ros::Publisher contact_pub_
ros::NodeHandle * rosnode_
pointer to ros node
sensors::ContactSensorPtr parentSensor
gazebo_msgs::ContactsState contact_state_msg_
broadcast some string for now.