$search

gazebo::GazeboRosF3D Class Reference
[Applied Force State Plugin XML Reference and Example]

GazeboRosF3D controller This is a controller that simulates a 6 dof force sensor. More...

#include <gazebo_ros_f3d.h>

List of all members.

Public Member Functions

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

Protected Member Functions

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

Private Member Functions

void F3DConnect ()
void F3DDisconnect ()
void QueueThread ()

Private Attributes

std::string bodyName
ParamT< std::string > * bodyNameP
 store bodyname
boost::thread callback_queue_thread_
int f3dConnectCount
 : keep track of number of connections
std::string frameName
ParamT< std::string > * frameNameP
 ROS frame transform name to use in the image message header. This should be simply map since the returned info is in Gazebo Global Frame.
boost::mutex lock
 A mutex to lock access to fields that are used in message callbacks.
Body * myBody
 A pointer to the Gazebo Body.
Model * myParent
 A link to the parent Model.
ros::Publisher pub_
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.
std::string topicName
ParamT< std::string > * topicNameP
 ROS WrenchStamped topic name.
geometry_msgs::WrenchStamped wrenchMsg
 ROS WrenchStamped message.

Detailed Description

GazeboRosF3D controller This is a controller that simulates a 6 dof force sensor.

Definition at line 73 of file gazebo_ros_f3d.h.


Constructor & Destructor Documentation

GazeboRosF3D::GazeboRosF3D ( Entity *  parent  ) 

Constructor.

Parameters:
parent The parent entity must be a Model

Definition at line 49 of file gazebo_ros_f3d.cpp.

GazeboRosF3D::~GazeboRosF3D (  )  [virtual]

Destructor.

Definition at line 69 of file gazebo_ros_f3d.cpp.


Member Function Documentation

void GazeboRosF3D::F3DConnect (  )  [private]

Definition at line 115 of file gazebo_ros_f3d.cpp.

void GazeboRosF3D::F3DDisconnect (  )  [private]

Definition at line 122 of file gazebo_ros_f3d.cpp.

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

Finalize the controller.

Definition at line 171 of file gazebo_ros_f3d.cpp.

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

Init the controller.

Definition at line 129 of file gazebo_ros_f3d.cpp.

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

Load the controller.

Parameters:
node XML config node

Definition at line 80 of file gazebo_ros_f3d.cpp.

void GazeboRosF3D::QueueThread (  )  [private]

Definition at line 183 of file gazebo_ros_f3d.cpp.

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

Update the controller.

Definition at line 137 of file gazebo_ros_f3d.cpp.


Member Data Documentation

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

Definition at line 111 of file gazebo_ros_f3d.h.

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

store bodyname

Definition at line 110 of file gazebo_ros_f3d.h.

Definition at line 137 of file gazebo_ros_f3d.h.

: keep track of number of connections

Definition at line 130 of file gazebo_ros_f3d.h.

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

Definition at line 120 of file gazebo_ros_f3d.h.

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

ROS frame transform name to use in the image message header. This should be simply map since the returned info is in Gazebo Global Frame.

Definition at line 119 of file gazebo_ros_f3d.h.

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

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

Definition at line 127 of file gazebo_ros_f3d.h.

A pointer to the Gazebo Body.

Definition at line 99 of file gazebo_ros_f3d.h.

A link to the parent Model.

Definition at line 96 of file gazebo_ros_f3d.h.

Definition at line 104 of file gazebo_ros_f3d.h.

Definition at line 135 of file gazebo_ros_f3d.h.

std::string gazebo::GazeboRosF3D::robotNamespace [private]

Definition at line 124 of file gazebo_ros_f3d.h.

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

for setting ROS name space

Definition at line 123 of file gazebo_ros_f3d.h.

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

Definition at line 103 of file gazebo_ros_f3d.h.

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

Definition at line 115 of file gazebo_ros_f3d.h.

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

ROS WrenchStamped topic name.

Definition at line 114 of file gazebo_ros_f3d.h.

ROS WrenchStamped message.

Definition at line 107 of file gazebo_ros_f3d.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