Public Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboRosBumper Class Reference

A Bumper controller. More...

#include <gazebo_ros_bumper.h>

Inheritance diagram for gazebo::GazeboRosBumper:
Inheritance graph
[legend]

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::NodeHandlerosnode_
 pointer to ros node More...
 
event::ConnectionPtr update_connection_
 

Detailed Description

A Bumper controller.

Definition at line 51 of file gazebo_ros_bumper.h.

Constructor & Destructor Documentation

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.

Member Function Documentation

void gazebo::GazeboRosBumper::ContactQueueThread ( )
private

Definition at line 321 of file gazebo_ros_bumper.cpp.

void gazebo::GazeboRosBumper::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load the plugin.

Parameters
takein SDF root element

Definition at line 67 of file gazebo_ros_bumper.cpp.

void gazebo::GazeboRosBumper::OnContact ( )
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.

Member Data Documentation

std::string gazebo::GazeboRosBumper::bumper_topic_name_
private

set topic name of broadcast

Definition at line 73 of file gazebo_ros_bumper.h.

boost::thread gazebo::GazeboRosBumper::callback_queue_thread_
private

Definition at line 85 of file gazebo_ros_bumper.h.

ros::Publisher gazebo::GazeboRosBumper::contact_pub_
private

Definition at line 68 of file gazebo_ros_bumper.h.

ros::CallbackQueue gazebo::GazeboRosBumper::contact_queue_
private

Definition at line 83 of file gazebo_ros_bumper.h.

gazebo_msgs::ContactsState gazebo::GazeboRosBumper::contact_state_msg_
private

broadcast some string for now.

Definition at line 78 of file gazebo_ros_bumper.h.

std::string gazebo::GazeboRosBumper::frame_name_
private

Definition at line 75 of file gazebo_ros_bumper.h.

sensors::ContactSensorPtr gazebo::GazeboRosBumper::parentSensor
private

Definition at line 70 of file gazebo_ros_bumper.h.

std::string gazebo::GazeboRosBumper::robot_namespace_
private

for setting ROS name space

Definition at line 81 of file gazebo_ros_bumper.h.

ros::NodeHandle* gazebo::GazeboRosBumper::rosnode_
private

pointer to ros node

Definition at line 67 of file gazebo_ros_bumper.h.

event::ConnectionPtr gazebo::GazeboRosBumper::update_connection_
private

Definition at line 88 of file gazebo_ros_bumper.h.


The documentation for this class was generated from the following files:


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Apr 6 2021 02:19:40