$search

gazebo::GazeboRosForce Class Reference
[Plugin XML Reference and Example]

#include <gazebo_ros_force.h>

List of all members.

Public Member Functions

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

Protected Member Functions

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

Private Member Functions

void QueueThread ()
void UpdateObjectForce (const geometry_msgs::Wrench::ConstPtr &wrenchMsg)
 call back when a Wrench message is published

Private Attributes

std::string bodyName
ParamT< std::string > * bodyNameP
boost::thread callback_queue_thread_
boost::mutex lock
 A mutex to lock access to fields that are used in ROS message callbacks.
Body * myBody
 A pointer to the Body.
Model * myParent
 A pointer to the parent entity.
ros::CallbackQueue queue_
std::string robotNamespace
ParamT< std::string > * robotNamespaceP
 for setting ROS name space
ros::NodeHandlerosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist.
ros::Subscriber sub_
std::string topicName
ParamT< std::string > * topicNameP
 ROS Wrench topic name.
geometry_msgs::Wrench wrench

Detailed Description

Definition at line 76 of file gazebo_ros_force.h.


Constructor & Destructor Documentation

GazeboRosForce::GazeboRosForce ( Entity *  parent  ) 

Constructor.

Parameters:
parent The parent entity, must be a Model or a Sensor

Definition at line 52 of file gazebo_ros_force.cpp.

GazeboRosForce::~GazeboRosForce (  )  [virtual]

Destructor.

Definition at line 85 of file gazebo_ros_force.cpp.


Member Function Documentation

void GazeboRosForce::FiniChild (  )  [protected, virtual]

Finalize the controller, unadvertise topics.

Definition at line 171 of file gazebo_ros_force.cpp.

void GazeboRosForce::InitChild (  )  [protected, virtual]

Init the controller.

Definition at line 137 of file gazebo_ros_force.cpp.

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

Load the controller.

Parameters:
node XML config node

Definition at line 97 of file gazebo_ros_force.cpp.

void GazeboRosForce::QueueThread (  )  [private]

Definition at line 183 of file gazebo_ros_force.cpp.

void GazeboRosForce::UpdateChild (  )  [protected, virtual]

Update the controller.

Definition at line 157 of file gazebo_ros_force.cpp.

void GazeboRosForce::UpdateObjectForce ( const geometry_msgs::Wrench::ConstPtr wrenchMsg  )  [private]

call back when a Wrench message is published

Definition at line 145 of file gazebo_ros_force.cpp.


Member Data Documentation

std::string gazebo::GazeboRosForce::bodyName [private]

Definition at line 117 of file gazebo_ros_force.h.

ParamT<std::string> * gazebo::GazeboRosForce::bodyNameP [private]

Definition at line 116 of file gazebo_ros_force.h.

Definition at line 126 of file gazebo_ros_force.h.

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

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

Definition at line 112 of file gazebo_ros_force.h.

A pointer to the Body.

Definition at line 105 of file gazebo_ros_force.h.

A pointer to the parent entity.

Definition at line 102 of file gazebo_ros_force.h.

Definition at line 124 of file gazebo_ros_force.h.

Definition at line 121 of file gazebo_ros_force.h.

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

for setting ROS name space

Definition at line 120 of file gazebo_ros_force.h.

A pointer to the ROS node. A node will be instantiated if it does not exist.

Definition at line 108 of file gazebo_ros_force.h.

Definition at line 109 of file gazebo_ros_force.h.

std::string gazebo::GazeboRosForce::topicName [private]

Definition at line 117 of file gazebo_ros_force.h.

ParamT<std::string>* gazebo::GazeboRosForce::topicNameP [private]

ROS Wrench topic name.

inputs

Definition at line 116 of file gazebo_ros_force.h.

Definition at line 127 of file gazebo_ros_force.h.


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


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Sat Mar 2 13:40:08 2013