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

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

#include <gazebo_ros_ft_sensor.h>

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

Public Member Functions

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

Protected Member Functions

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

Private Member Functions

void FTConnect ()
 
void FTDisconnect ()
 
double GaussianKernel (double mu, double sigma)
 Gaussian noise generator. More...
 
void QueueThread ()
 

Private Attributes

boost::thread callback_queue_thread_
 
physics::LinkPtr child_link_
 A pointer to the Gazebo child link. More...
 
std::string frame_name_
 ROS frame transform name to use in the image message header. FIXME: extract link name directly? More...
 
int ft_connect_count_
 : keep track of number of connections More...
 
double gaussian_noise_
 Gaussian noise. More...
 
physics::JointPtr joint_
 A pointer to the Gazebo joint. More...
 
std::string joint_name_
 store bodyname More...
 
common::Time last_time_
 save last_time More...
 
boost::mutex lock_
 A mutex to lock access to fields that are used in message callbacks. More...
 
physics::ModelPtr model_
 A pointer to the Gazebo model. More...
 
physics::LinkPtr parent_link_
 A pointer to the Gazebo parent link. 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_
 
double update_rate_
 
physics::WorldPtr world_
 A pointer to the Gazebo world. More...
 
geometry_msgs::WrenchStamped wrench_msg_
 ROS WrenchStamped message. More...
 

Detailed Description

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

Definition at line 74 of file gazebo_ros_ft_sensor.h.

Constructor & Destructor Documentation

◆ GazeboRosFT()

gazebo::GazeboRosFT::GazeboRosFT ( )

Constructor.

Parameters
parentThe parent entity must be a Model

Definition at line 36 of file gazebo_ros_ft_sensor.cpp.

◆ ~GazeboRosFT()

gazebo::GazeboRosFT::~GazeboRosFT ( )
virtual

Destructor.

Definition at line 43 of file gazebo_ros_ft_sensor.cpp.

Member Function Documentation

◆ FTConnect()

void gazebo::GazeboRosFT::FTConnect ( )
private

Definition at line 147 of file gazebo_ros_ft_sensor.cpp.

◆ FTDisconnect()

void gazebo::GazeboRosFT::FTDisconnect ( )
private

Definition at line 154 of file gazebo_ros_ft_sensor.cpp.

◆ GaussianKernel()

double gazebo::GazeboRosFT::GaussianKernel ( double  mu,
double  sigma 
)
private

Gaussian noise generator.

Definition at line 233 of file gazebo_ros_ft_sensor.cpp.

◆ Load()

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

Load the controller.

Definition at line 56 of file gazebo_ros_ft_sensor.cpp.

◆ QueueThread()

void gazebo::GazeboRosFT::QueueThread ( )
private

Definition at line 256 of file gazebo_ros_ft_sensor.cpp.

◆ UpdateChild()

void gazebo::GazeboRosFT::UpdateChild ( )
protectedvirtual

Update the controller.

Definition at line 161 of file gazebo_ros_ft_sensor.cpp.

Member Data Documentation

◆ callback_queue_thread_

boost::thread gazebo::GazeboRosFT::callback_queue_thread_
private

Definition at line 147 of file gazebo_ros_ft_sensor.h.

◆ child_link_

physics::LinkPtr gazebo::GazeboRosFT::child_link_
private

A pointer to the Gazebo child link.

Definition at line 102 of file gazebo_ros_ft_sensor.h.

◆ frame_name_

std::string gazebo::GazeboRosFT::frame_name_
private

ROS frame transform name to use in the image message header. FIXME: extract link name directly?

Definition at line 125 of file gazebo_ros_ft_sensor.h.

◆ ft_connect_count_

int gazebo::GazeboRosFT::ft_connect_count_
private

: keep track of number of connections

Definition at line 140 of file gazebo_ros_ft_sensor.h.

◆ gaussian_noise_

double gazebo::GazeboRosFT::gaussian_noise_
private

Gaussian noise.

Definition at line 90 of file gazebo_ros_ft_sensor.h.

◆ joint_

physics::JointPtr gazebo::GazeboRosFT::joint_
private

A pointer to the Gazebo joint.

Definition at line 96 of file gazebo_ros_ft_sensor.h.

◆ joint_name_

std::string gazebo::GazeboRosFT::joint_name_
private

store bodyname

Definition at line 118 of file gazebo_ros_ft_sensor.h.

◆ last_time_

common::Time gazebo::GazeboRosFT::last_time_
private

save last_time

Definition at line 134 of file gazebo_ros_ft_sensor.h.

◆ lock_

boost::mutex gazebo::GazeboRosFT::lock_
private

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

Definition at line 131 of file gazebo_ros_ft_sensor.h.

◆ model_

physics::ModelPtr gazebo::GazeboRosFT::model_
private

A pointer to the Gazebo model.

Definition at line 105 of file gazebo_ros_ft_sensor.h.

◆ parent_link_

physics::LinkPtr gazebo::GazeboRosFT::parent_link_
private

A pointer to the Gazebo parent link.

Definition at line 99 of file gazebo_ros_ft_sensor.h.

◆ pub_

ros::Publisher gazebo::GazeboRosFT::pub_
private

Definition at line 112 of file gazebo_ros_ft_sensor.h.

◆ queue_

ros::CallbackQueue gazebo::GazeboRosFT::queue_
private

Definition at line 145 of file gazebo_ros_ft_sensor.h.

◆ robot_namespace_

std::string gazebo::GazeboRosFT::robot_namespace_
private

for setting ROS name space

Definition at line 128 of file gazebo_ros_ft_sensor.h.

◆ rosnode_

ros::NodeHandle* gazebo::GazeboRosFT::rosnode_
private

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

Definition at line 111 of file gazebo_ros_ft_sensor.h.

◆ topic_name_

std::string gazebo::GazeboRosFT::topic_name_
private

ROS WrenchStamped topic name.

Definition at line 121 of file gazebo_ros_ft_sensor.h.

◆ update_connection_

event::ConnectionPtr gazebo::GazeboRosFT::update_connection_
private

Definition at line 150 of file gazebo_ros_ft_sensor.h.

◆ update_rate_

double gazebo::GazeboRosFT::update_rate_
private

Definition at line 137 of file gazebo_ros_ft_sensor.h.

◆ world_

physics::WorldPtr gazebo::GazeboRosFT::world_
private

A pointer to the Gazebo world.

Definition at line 108 of file gazebo_ros_ft_sensor.h.

◆ wrench_msg_

geometry_msgs::WrenchStamped gazebo::GazeboRosFT::wrench_msg_
private

ROS WrenchStamped message.

Definition at line 115 of file gazebo_ros_ft_sensor.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