GazeboRosF3D controller This is a controller that simulates a 6 dof force sensor. More...
#include <gazebo_ros_f3d.h>
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::NodeHandle * | rosnode_ |
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. |
GazeboRosF3D controller This is a controller that simulates a 6 dof force sensor.
Definition at line 71 of file gazebo_ros_f3d.h.
GazeboRosF3D::GazeboRosF3D | ( | Entity * | parent | ) |
Constructor.
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.
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.
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.
std::string gazebo::GazeboRosF3D::bodyName [private] |
Definition at line 109 of file gazebo_ros_f3d.h.
ParamT<std::string>* gazebo::GazeboRosF3D::bodyNameP [private] |
store bodyname
Definition at line 108 of file gazebo_ros_f3d.h.
boost::thread gazebo::GazeboRosF3D::callback_queue_thread_ [private] |
Definition at line 135 of file gazebo_ros_f3d.h.
int gazebo::GazeboRosF3D::f3dConnectCount [private] |
: keep track of number of connections
Definition at line 128 of file gazebo_ros_f3d.h.
std::string gazebo::GazeboRosF3D::frameName [private] |
Definition at line 118 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 117 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 125 of file gazebo_ros_f3d.h.
Body* gazebo::GazeboRosF3D::myBody [private] |
A pointer to the Gazebo Body.
Definition at line 97 of file gazebo_ros_f3d.h.
Model* gazebo::GazeboRosF3D::myParent [private] |
A link to the parent Model.
Definition at line 94 of file gazebo_ros_f3d.h.
ros::Publisher gazebo::GazeboRosF3D::pub_ [private] |
Definition at line 102 of file gazebo_ros_f3d.h.
ros::CallbackQueue gazebo::GazeboRosF3D::queue_ [private] |
Definition at line 133 of file gazebo_ros_f3d.h.
std::string gazebo::GazeboRosF3D::robotNamespace [private] |
Definition at line 122 of file gazebo_ros_f3d.h.
ParamT<std::string>* gazebo::GazeboRosF3D::robotNamespaceP [private] |
for setting ROS name space
Definition at line 121 of file gazebo_ros_f3d.h.
ros::NodeHandle* gazebo::GazeboRosF3D::rosnode_ [private] |
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition at line 101 of file gazebo_ros_f3d.h.
std::string gazebo::GazeboRosF3D::topicName [private] |
Definition at line 113 of file gazebo_ros_f3d.h.
ParamT<std::string>* gazebo::GazeboRosF3D::topicNameP [private] |
ROS WrenchStamped topic name.
Definition at line 112 of file gazebo_ros_f3d.h.
geometry_msgs::WrenchStamped gazebo::GazeboRosF3D::wrenchMsg [private] |
ROS WrenchStamped message.
Definition at line 105 of file gazebo_ros_f3d.h.