#include <gazebo_ros_bumper.h>

Public Member Functions | |
| GazeboRosBumper () | |
| Constructor. More... | |
| void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
| Load the plugin. More... | |
| ~GazeboRosBumper () | |
| Destructor. More... | |
Private Member Functions | |
| void | ContactQueueThread () |
| void | OnContact () |
| Update the controller. More... | |
Private Attributes | |
| std::string | bumper_topic_name_ |
| set topic name of broadcast More... | |
| boost::thread | callback_queue_thread_ |
| ros::Publisher | contact_pub_ |
| ros::CallbackQueue | contact_queue_ |
| gazebo_msgs::ContactsState | contact_state_msg_ |
| broadcast some string for now. More... | |
| std::string | frame_name_ |
| sensors::ContactSensorPtr | parentSensor |
| std::string | robot_namespace_ |
| for setting ROS name space More... | |
| ros::NodeHandle * | rosnode_ |
| pointer to ros node More... | |
| event::ConnectionPtr | update_connection_ |
A Bumper controller.
Definition at line 51 of file gazebo_ros_bumper.h.
| gazebo::GazeboRosBumper::GazeboRosBumper | ( | ) |
Constructor.
Definition at line 51 of file gazebo_ros_bumper.cpp.
| gazebo::GazeboRosBumper::~GazeboRosBumper | ( | ) |
Destructor.
Definition at line 57 of file gazebo_ros_bumper.cpp.
|
private |
Definition at line 321 of file gazebo_ros_bumper.cpp.
| void gazebo::GazeboRosBumper::Load | ( | sensors::SensorPtr | _parent, |
| sdf::ElementPtr | _sdf | ||
| ) |
Load the plugin.
| take | in SDF root element |
Definition at line 67 of file gazebo_ros_bumper.cpp.
|
private |
Update the controller.
: need a time for each Contact in i-loop, they may differ
:
Definition at line 133 of file gazebo_ros_bumper.cpp.
|
private |
set topic name of broadcast
Definition at line 73 of file gazebo_ros_bumper.h.
|
private |
Definition at line 85 of file gazebo_ros_bumper.h.
|
private |
Definition at line 68 of file gazebo_ros_bumper.h.
|
private |
Definition at line 83 of file gazebo_ros_bumper.h.
|
private |
broadcast some string for now.
Definition at line 78 of file gazebo_ros_bumper.h.
|
private |
Definition at line 75 of file gazebo_ros_bumper.h.
|
private |
Definition at line 70 of file gazebo_ros_bumper.h.
|
private |
for setting ROS name space
Definition at line 81 of file gazebo_ros_bumper.h.
|
private |
pointer to ros node
Definition at line 67 of file gazebo_ros_bumper.h.
|
private |
Definition at line 88 of file gazebo_ros_bumper.h.