$search

gazebo::My_Generic_Bumper Class Reference

A Bumper controller. More...

#include <reem_bumper_gazebo.h>

List of all members.

Public Member Functions

 My_Generic_Bumper (Entity *parent)
 Constructor.
virtual ~My_Generic_Bumper ()
 Destructor.

Protected Member Functions

virtual void FiniChild ()
 Finalize the controller.
virtual void InitChild ()
 Init the controller.
virtual void LoadChild (XMLConfigNode *node)
virtual void UpdateChild ()
 Update the controller.

Private Member Functions

void ContactConnect ()
void ContactDisconnect ()
void ContactQueueThread ()

Private Attributes

std_msgs::Bool boolMsg
std::string bumperTopicName
ParamT< std::string > * bumperTopicNameP
 set topic name of broadcast
boost::thread callback_queue_thread_
ros::Publisher contact_pub_
ros::CallbackQueue contact_queue_
int contactConnectCount
 Keep track of number of connctions.
gazebo_msgs::ContactsState contactsStateMsg
 broadcast some string for now.
std::string frameId
ParamT< std::string > * frameIdP
std::string frameName
ParamT< std::string > * frameNameP
boost::mutex lock
 A mutex to lock access to fields that are used in message callbacks.
Body * myFrame
 Return information in this body (link) coordinate if unavailable, use "/map" and global gazebo world frame.
ContactSensor * myParent
 The parent Model.
std::string robotNamespace
ParamT< std::string > * robotNamespaceP
 for setting ROS name space
ros::NodeHandlerosnode_
 pointer to ros node

Detailed Description

A Bumper controller.

Definition at line 65 of file reem_bumper_gazebo.h.


Constructor & Destructor Documentation

gazebo::My_Generic_Bumper::My_Generic_Bumper ( Entity *  parent  ) 

Constructor.

Definition at line 59 of file reem_bumper_gazebo.cpp.

gazebo::My_Generic_Bumper::~My_Generic_Bumper (  )  [virtual]

Destructor.

Definition at line 79 of file reem_bumper_gazebo.cpp.


Member Function Documentation

void gazebo::My_Generic_Bumper::ContactConnect (  )  [private]

Definition at line 129 of file reem_bumper_gazebo.cpp.

void gazebo::My_Generic_Bumper::ContactDisconnect (  )  [private]

Definition at line 135 of file reem_bumper_gazebo.cpp.

void gazebo::My_Generic_Bumper::ContactQueueThread (  )  [private]

Definition at line 370 of file reem_bumper_gazebo.cpp.

void gazebo::My_Generic_Bumper::FiniChild (  )  [protected, virtual]

Finalize the controller.

Definition at line 361 of file reem_bumper_gazebo.cpp.

void gazebo::My_Generic_Bumper::InitChild (  )  [protected, virtual]

Init the controller.

Definition at line 142 of file reem_bumper_gazebo.cpp.

void gazebo::My_Generic_Bumper::LoadChild ( XMLConfigNode *  node  )  [protected, virtual]

Load the controller

Parameters:
node XML config node

Definition at line 90 of file reem_bumper_gazebo.cpp.

void gazebo::My_Generic_Bumper::UpdateChild (  )  [protected, virtual]

Update the controller.

if frameName specified is "world", "/map" or "map" report back inertial values in the gazebo world

Definition at line 155 of file reem_bumper_gazebo.cpp.


Member Data Documentation

std_msgs::Bool gazebo::My_Generic_Bumper::boolMsg [private]

Definition at line 112 of file reem_bumper_gazebo.h.

Definition at line 99 of file reem_bumper_gazebo.h.

ParamT<std::string>* gazebo::My_Generic_Bumper::bumperTopicNameP [private]

set topic name of broadcast

Definition at line 98 of file reem_bumper_gazebo.h.

Definition at line 126 of file reem_bumper_gazebo.h.

Definition at line 95 of file reem_bumper_gazebo.h.

Definition at line 124 of file reem_bumper_gazebo.h.

Keep track of number of connctions.

Definition at line 119 of file reem_bumper_gazebo.h.

broadcast some string for now.

Definition at line 111 of file reem_bumper_gazebo.h.

std::string gazebo::My_Generic_Bumper::frameId [private]

Definition at line 105 of file reem_bumper_gazebo.h.

ParamT<std::string>* gazebo::My_Generic_Bumper::frameIdP [private]

Definition at line 104 of file reem_bumper_gazebo.h.

std::string gazebo::My_Generic_Bumper::frameName [private]

Definition at line 102 of file reem_bumper_gazebo.h.

ParamT<std::string>* gazebo::My_Generic_Bumper::frameNameP [private]

Definition at line 101 of file reem_bumper_gazebo.h.

boost::mutex gazebo::My_Generic_Bumper::lock [private]

A mutex to lock access to fields that are used in message callbacks.

Definition at line 108 of file reem_bumper_gazebo.h.

Return information in this body (link) coordinate if unavailable, use "/map" and global gazebo world frame.

Definition at line 91 of file reem_bumper_gazebo.h.

ContactSensor* gazebo::My_Generic_Bumper::myParent [private]

The parent Model.

Definition at line 87 of file reem_bumper_gazebo.h.

Definition at line 116 of file reem_bumper_gazebo.h.

ParamT<std::string>* gazebo::My_Generic_Bumper::robotNamespaceP [private]

for setting ROS name space

Definition at line 115 of file reem_bumper_gazebo.h.

pointer to ros node

Definition at line 94 of file reem_bumper_gazebo.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


bumper_gazebo_plugin
Author(s): Jose Rafael Capriles
autogenerated on Fri Mar 1 16:45:48 2013