A Bumper controller. More...
#include <gazebo_ros_bumper.h>
Public Member Functions | |
GazeboRosBumper (Entity *parent) | |
Constructor. | |
virtual | ~GazeboRosBumper () |
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::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_plugins::ContactsState | contactsStateMsg |
broadcast some string for now. | |
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::NodeHandle * | rosnode_ |
pointer to ros node |
A Bumper controller.
Definition at line 79 of file gazebo_ros_bumper.h.
gazebo::GazeboRosBumper::GazeboRosBumper | ( | Entity * | parent | ) |
Constructor.
Definition at line 46 of file gazebo_ros_bumper.cpp.
gazebo::GazeboRosBumper::~GazeboRosBumper | ( | ) | [virtual] |
Destructor.
Definition at line 65 of file gazebo_ros_bumper.cpp.
void gazebo::GazeboRosBumper::ContactConnect | ( | ) | [private] |
Definition at line 112 of file gazebo_ros_bumper.cpp.
void gazebo::GazeboRosBumper::ContactDisconnect | ( | ) | [private] |
Definition at line 118 of file gazebo_ros_bumper.cpp.
void gazebo::GazeboRosBumper::ContactQueueThread | ( | ) | [private] |
void gazebo::GazeboRosBumper::FiniChild | ( | ) | [protected, virtual] |
Finalize the controller.
Definition at line 316 of file gazebo_ros_bumper.cpp.
void gazebo::GazeboRosBumper::InitChild | ( | ) | [protected, virtual] |
Init the controller.
Definition at line 125 of file gazebo_ros_bumper.cpp.
void gazebo::GazeboRosBumper::LoadChild | ( | XMLConfigNode * | node | ) | [protected, virtual] |
Load the controller
node | XML config node |
Definition at line 75 of file gazebo_ros_bumper.cpp.
void gazebo::GazeboRosBumper::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 138 of file gazebo_ros_bumper.cpp.
std::string gazebo::GazeboRosBumper::bumperTopicName [private] |
Definition at line 113 of file gazebo_ros_bumper.h.
ParamT<std::string>* gazebo::GazeboRosBumper::bumperTopicNameP [private] |
set topic name of broadcast
Definition at line 112 of file gazebo_ros_bumper.h.
boost::thread gazebo::GazeboRosBumper::callback_queue_thread_ [private] |
Definition at line 136 of file gazebo_ros_bumper.h.
ros::Publisher gazebo::GazeboRosBumper::contact_pub_ [private] |
Definition at line 109 of file gazebo_ros_bumper.h.
ros::CallbackQueue gazebo::GazeboRosBumper::contact_queue_ [private] |
Definition at line 134 of file gazebo_ros_bumper.h.
int gazebo::GazeboRosBumper::contactConnectCount [private] |
Keep track of number of connctions.
Definition at line 129 of file gazebo_ros_bumper.h.
broadcast some string for now.
Definition at line 122 of file gazebo_ros_bumper.h.
std::string gazebo::GazeboRosBumper::frameName [private] |
Definition at line 116 of file gazebo_ros_bumper.h.
ParamT<std::string>* gazebo::GazeboRosBumper::frameNameP [private] |
Definition at line 115 of file gazebo_ros_bumper.h.
boost::mutex gazebo::GazeboRosBumper::lock [private] |
A mutex to lock access to fields that are used in message callbacks.
Definition at line 119 of file gazebo_ros_bumper.h.
Body* gazebo::GazeboRosBumper::myFrame [private] |
Return information in this body (link) coordinate if unavailable, use "/map" and global gazebo world frame.
Definition at line 105 of file gazebo_ros_bumper.h.
ContactSensor* gazebo::GazeboRosBumper::myParent [private] |
The parent Model.
Definition at line 101 of file gazebo_ros_bumper.h.
std::string gazebo::GazeboRosBumper::robotNamespace [private] |
Definition at line 126 of file gazebo_ros_bumper.h.
ParamT<std::string>* gazebo::GazeboRosBumper::robotNamespaceP [private] |
for setting ROS name space
Definition at line 125 of file gazebo_ros_bumper.h.
ros::NodeHandle* gazebo::GazeboRosBumper::rosnode_ [private] |
pointer to ros node
Definition at line 108 of file gazebo_ros_bumper.h.