GazeboRosFT controller This is a controller that simulates a 6 dof force sensor. More...
#include <gazebo_ros_ft_sensor.h>
Public Member Functions | |
GazeboRosFT () | |
Constructor. | |
void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
Load the controller. | |
virtual | ~GazeboRosFT () |
Destructor. | |
Protected Member Functions | |
virtual void | UpdateChild () |
Update the controller. | |
Private Member Functions | |
void | FTConnect () |
void | FTDisconnect () |
double | GaussianKernel (double mu, double sigma) |
Gaussian noise generator. | |
void | QueueThread () |
Private Attributes | |
boost::thread | callback_queue_thread_ |
physics::LinkPtr | child_link_ |
A pointer to the Gazebo child link. | |
std::string | frame_name_ |
ROS frame transform name to use in the image message header. FIXME: extract link name directly? | |
int | ft_connect_count_ |
: keep track of number of connections | |
double | gaussian_noise_ |
Gaussian noise. | |
physics::JointPtr | joint_ |
A pointer to the Gazebo joint. | |
std::string | joint_name_ |
store bodyname | |
common::Time | last_time_ |
save last_time | |
boost::mutex | lock_ |
A mutex to lock access to fields that are used in message callbacks. | |
physics::ModelPtr | model_ |
A pointer to the Gazebo model. | |
physics::LinkPtr | parent_link_ |
A pointer to the Gazebo parent link. | |
ros::Publisher | pub_ |
ros::CallbackQueue | queue_ |
std::string | robot_namespace_ |
for setting ROS name space | |
ros::NodeHandle * | rosnode_ |
A pointer to the ROS node. A node will be instantiated if it does not exist. | |
unsigned int | seed |
std::string | topic_name_ |
ROS WrenchStamped topic name. | |
event::ConnectionPtr | update_connection_ |
double | update_rate_ |
physics::WorldPtr | world_ |
A pointer to the Gazebo world. | |
geometry_msgs::WrenchStamped | wrench_msg_ |
ROS WrenchStamped message. |
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.
parent | The parent entity must be a Model |
Definition at line 32 of file gazebo_ros_ft_sensor.cpp.
gazebo::GazeboRosFT::~GazeboRosFT | ( | ) | [virtual] |
Destructor.
Definition at line 40 of file gazebo_ros_ft_sensor.cpp.
void gazebo::GazeboRosFT::FTConnect | ( | ) | [private] |
Definition at line 144 of file gazebo_ros_ft_sensor.cpp.
void gazebo::GazeboRosFT::FTDisconnect | ( | ) | [private] |
Definition at line 151 of file gazebo_ros_ft_sensor.cpp.
double gazebo::GazeboRosFT::GaussianKernel | ( | double | mu, |
double | sigma | ||
) | [private] |
Gaussian noise generator.
Definition at line 206 of file gazebo_ros_ft_sensor.cpp.
void gazebo::GazeboRosFT::Load | ( | physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) |
Load the controller.
Definition at line 53 of file gazebo_ros_ft_sensor.cpp.
void gazebo::GazeboRosFT::QueueThread | ( | ) | [private] |
Definition at line 231 of file gazebo_ros_ft_sensor.cpp.
void gazebo::GazeboRosFT::UpdateChild | ( | ) | [protected, virtual] |
Update the controller.
Definition at line 158 of file gazebo_ros_ft_sensor.cpp.
boost::thread gazebo::GazeboRosFT::callback_queue_thread_ [private] |
Definition at line 147 of file gazebo_ros_ft_sensor.h.
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.
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.
int gazebo::GazeboRosFT::ft_connect_count_ [private] |
: keep track of number of connections
Definition at line 140 of file gazebo_ros_ft_sensor.h.
double gazebo::GazeboRosFT::gaussian_noise_ [private] |
Gaussian noise.
Definition at line 90 of file gazebo_ros_ft_sensor.h.
physics::JointPtr gazebo::GazeboRosFT::joint_ [private] |
A pointer to the Gazebo joint.
Definition at line 96 of file gazebo_ros_ft_sensor.h.
std::string gazebo::GazeboRosFT::joint_name_ [private] |
store bodyname
Definition at line 118 of file gazebo_ros_ft_sensor.h.
common::Time gazebo::GazeboRosFT::last_time_ [private] |
save last_time
Definition at line 134 of file gazebo_ros_ft_sensor.h.
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.
physics::ModelPtr gazebo::GazeboRosFT::model_ [private] |
A pointer to the Gazebo model.
Definition at line 105 of file gazebo_ros_ft_sensor.h.
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.
ros::Publisher gazebo::GazeboRosFT::pub_ [private] |
Definition at line 112 of file gazebo_ros_ft_sensor.h.
Definition at line 145 of file gazebo_ros_ft_sensor.h.
std::string gazebo::GazeboRosFT::robot_namespace_ [private] |
for setting ROS name space
Definition at line 128 of file gazebo_ros_ft_sensor.h.
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.
unsigned int gazebo::GazeboRosFT::seed [private] |
Definition at line 91 of file gazebo_ros_ft_sensor.h.
std::string gazebo::GazeboRosFT::topic_name_ [private] |
ROS WrenchStamped topic name.
Definition at line 121 of file gazebo_ros_ft_sensor.h.
Definition at line 150 of file gazebo_ros_ft_sensor.h.
double gazebo::GazeboRosFT::update_rate_ [private] |
Definition at line 137 of file gazebo_ros_ft_sensor.h.
physics::WorldPtr gazebo::GazeboRosFT::world_ [private] |
A pointer to the Gazebo world.
Definition at line 108 of file gazebo_ros_ft_sensor.h.
geometry_msgs::WrenchStamped gazebo::GazeboRosFT::wrench_msg_ [private] |
ROS WrenchStamped message.
Definition at line 115 of file gazebo_ros_ft_sensor.h.