GazeboRosF3D controller This is a controller that simulates a 6 dof force sensor. More...
#include <gazebo_ros_f3d.h>
Public Member Functions | |
GazeboRosF3D () | |
Constructor. | |
void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
Load the controller. | |
virtual | ~GazeboRosF3D () |
Destructor. | |
Protected Member Functions | |
virtual void | UpdateChild () |
Update the controller. | |
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 | |
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. | |
physics::LinkPtr | link_ |
A pointer to the Gazebo Body. | |
std::string | link_name_ |
store bodyname | |
boost::mutex | lock_ |
A mutex to lock access to fields that are used in message callbacks. | |
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. | |
std::string | topic_name_ |
ROS WrenchStamped topic name. | |
event::ConnectionPtr | update_connection_ |
physics::WorldPtr | world_ |
geometry_msgs::WrenchStamped | wrench_msg_ |
ROS WrenchStamped message. |
GazeboRosF3D controller This is a controller that simulates a 6 dof force sensor.
Definition at line 45 of file gazebo_ros_f3d.h.
Constructor.
parent | The parent entity must be a Model |
Definition at line 33 of file gazebo_ros_f3d.cpp.
gazebo::GazeboRosF3D::~GazeboRosF3D | ( | ) | [virtual] |
Destructor.
Definition at line 40 of file gazebo_ros_f3d.cpp.
void gazebo::GazeboRosF3D::F3DConnect | ( | ) | [private] |
Definition at line 133 of file gazebo_ros_f3d.cpp.
void gazebo::GazeboRosF3D::F3DDisconnect | ( | ) | [private] |
Definition at line 140 of file gazebo_ros_f3d.cpp.
void gazebo::GazeboRosF3D::Load | ( | physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) |
Load the controller.
Definition at line 53 of file gazebo_ros_f3d.cpp.
void gazebo::GazeboRosF3D::QueueThread | ( | ) | [private] |
Definition at line 182 of file gazebo_ros_f3d.cpp.
void gazebo::GazeboRosF3D::UpdateChild | ( | ) | [protected, virtual] |
Update the controller.
Definition at line 147 of file gazebo_ros_f3d.cpp.
boost::thread gazebo::GazeboRosF3D::callback_queue_thread_ [private] |
Definition at line 97 of file gazebo_ros_f3d.h.
int gazebo::GazeboRosF3D::f3d_connect_count_ [private] |
: keep track of number of connections
Definition at line 90 of file gazebo_ros_f3d.h.
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.
physics::LinkPtr gazebo::GazeboRosF3D::link_ [private] |
A pointer to the Gazebo Body.
Definition at line 63 of file gazebo_ros_f3d.h.
std::string gazebo::GazeboRosF3D::link_name_ [private] |
store bodyname
Definition at line 74 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 87 of file gazebo_ros_f3d.h.
ros::Publisher gazebo::GazeboRosF3D::pub_ [private] |
Definition at line 68 of file gazebo_ros_f3d.h.
Definition at line 95 of file gazebo_ros_f3d.h.
std::string gazebo::GazeboRosF3D::robot_namespace_ [private] |
for setting ROS name space
Definition at line 84 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 67 of file gazebo_ros_f3d.h.
std::string gazebo::GazeboRosF3D::topic_name_ [private] |
ROS WrenchStamped topic name.
Definition at line 77 of file gazebo_ros_f3d.h.
Definition at line 100 of file gazebo_ros_f3d.h.
physics::WorldPtr gazebo::GazeboRosF3D::world_ [private] |
Definition at line 60 of file gazebo_ros_f3d.h.
geometry_msgs::WrenchStamped gazebo::GazeboRosF3D::wrench_msg_ [private] |
ROS WrenchStamped message.
Definition at line 71 of file gazebo_ros_f3d.h.