Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboRosF3D Class Reference

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

#include <gazebo_ros_f3d.h>

Inheritance diagram for gazebo::GazeboRosF3D:
Inheritance graph
[legend]

Public Member Functions

 GazeboRosF3D ()
 Constructor. More...
 
void Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 Load the controller. More...
 
virtual ~GazeboRosF3D ()
 Destructor. More...
 

Protected Member Functions

virtual void UpdateChild ()
 Update the controller. More...
 

Private Member Functions

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

Private Attributes

boost::thread callback_queue_thread_
 
int f3d_connect_count_
 : keep track of number of connections More...
 
std::string frame_name_
 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. More...
 
physics::LinkPtr link_
 A pointer to the Gazebo Body. More...
 
std::string link_name_
 store bodyname More...
 
boost::mutex lock_
 A mutex to lock access to fields that are used in message callbacks. More...
 
ros::Publisher pub_
 
ros::CallbackQueue queue_
 
std::string robot_namespace_
 for setting ROS name space More...
 
ros::NodeHandlerosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist. More...
 
std::string topic_name_
 ROS WrenchStamped topic name. More...
 
event::ConnectionPtr update_connection_
 
physics::WorldPtr world_
 
geometry_msgs::WrenchStamped wrench_msg_
 ROS WrenchStamped message. More...
 

Detailed Description

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

Definition at line 45 of file gazebo_ros_f3d.h.

Constructor & Destructor Documentation

◆ GazeboRosF3D()

gazebo::GazeboRosF3D::GazeboRosF3D ( )

Constructor.

Parameters
parentThe parent entity must be a Model

Definition at line 36 of file gazebo_ros_f3d.cpp.

◆ ~GazeboRosF3D()

gazebo::GazeboRosF3D::~GazeboRosF3D ( )
virtual

Destructor.

Definition at line 43 of file gazebo_ros_f3d.cpp.

Member Function Documentation

◆ F3DConnect()

void gazebo::GazeboRosF3D::F3DConnect ( )
private

Definition at line 136 of file gazebo_ros_f3d.cpp.

◆ F3DDisconnect()

void gazebo::GazeboRosF3D::F3DDisconnect ( )
private

Definition at line 143 of file gazebo_ros_f3d.cpp.

◆ Load()

void gazebo::GazeboRosF3D::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load the controller.

Definition at line 56 of file gazebo_ros_f3d.cpp.

◆ QueueThread()

void gazebo::GazeboRosF3D::QueueThread ( )
private

Definition at line 204 of file gazebo_ros_f3d.cpp.

◆ UpdateChild()

void gazebo::GazeboRosF3D::UpdateChild ( )
protectedvirtual

Update the controller.

Definition at line 150 of file gazebo_ros_f3d.cpp.

Member Data Documentation

◆ callback_queue_thread_

boost::thread gazebo::GazeboRosF3D::callback_queue_thread_
private

Definition at line 97 of file gazebo_ros_f3d.h.

◆ f3d_connect_count_

int gazebo::GazeboRosF3D::f3d_connect_count_
private

: keep track of number of connections

Definition at line 90 of file gazebo_ros_f3d.h.

◆ frame_name_

std::string gazebo::GazeboRosF3D::frame_name_
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 81 of file gazebo_ros_f3d.h.

◆ link_

physics::LinkPtr gazebo::GazeboRosF3D::link_
private

A pointer to the Gazebo Body.

Definition at line 63 of file gazebo_ros_f3d.h.

◆ link_name_

std::string gazebo::GazeboRosF3D::link_name_
private

store bodyname

Definition at line 74 of file gazebo_ros_f3d.h.

◆ lock_

boost::mutex gazebo::GazeboRosF3D::lock_
private

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

Definition at line 87 of file gazebo_ros_f3d.h.

◆ pub_

ros::Publisher gazebo::GazeboRosF3D::pub_
private

Definition at line 68 of file gazebo_ros_f3d.h.

◆ queue_

ros::CallbackQueue gazebo::GazeboRosF3D::queue_
private

Definition at line 95 of file gazebo_ros_f3d.h.

◆ robot_namespace_

std::string gazebo::GazeboRosF3D::robot_namespace_
private

for setting ROS name space

Definition at line 84 of file gazebo_ros_f3d.h.

◆ rosnode_

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 67 of file gazebo_ros_f3d.h.

◆ topic_name_

std::string gazebo::GazeboRosF3D::topic_name_
private

ROS WrenchStamped topic name.

Definition at line 77 of file gazebo_ros_f3d.h.

◆ update_connection_

event::ConnectionPtr gazebo::GazeboRosF3D::update_connection_
private

Definition at line 100 of file gazebo_ros_f3d.h.

◆ world_

physics::WorldPtr gazebo::GazeboRosF3D::world_
private

Definition at line 60 of file gazebo_ros_f3d.h.

◆ wrench_msg_

geometry_msgs::WrenchStamped gazebo::GazeboRosF3D::wrench_msg_
private

ROS WrenchStamped message.

Definition at line 71 of file gazebo_ros_f3d.h.


The documentation for this class was generated from the following files:


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28