GazeboRosF3D controller This is a controller that simulates a 6 dof force sensor. More...
#include <gazebo_ros_f3d.h>
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::NodeHandle * | rosnode_ |
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... | |
GazeboRosF3D controller This is a controller that simulates a 6 dof force sensor.
Definition at line 45 of file gazebo_ros_f3d.h.
gazebo::GazeboRosF3D::GazeboRosF3D | ( | ) |
Constructor.
parent | The parent entity must be a Model |
Definition at line 33 of file gazebo_ros_f3d.cpp.
|
virtual |
Destructor.
Definition at line 40 of file gazebo_ros_f3d.cpp.
|
private |
Definition at line 133 of file gazebo_ros_f3d.cpp.
|
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.
|
private |
Definition at line 190 of file gazebo_ros_f3d.cpp.
|
protectedvirtual |
Update the controller.
Definition at line 147 of file gazebo_ros_f3d.cpp.
|
private |
Definition at line 97 of file gazebo_ros_f3d.h.
|
private |
: keep track of number of connections
Definition at line 90 of file gazebo_ros_f3d.h.
|
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.
|
private |
A pointer to the Gazebo Body.
Definition at line 63 of file gazebo_ros_f3d.h.
|
private |
store bodyname
Definition at line 74 of file gazebo_ros_f3d.h.
|
private |
A mutex to lock access to fields that are used in message callbacks.
Definition at line 87 of file gazebo_ros_f3d.h.
|
private |
Definition at line 68 of file gazebo_ros_f3d.h.
|
private |
Definition at line 95 of file gazebo_ros_f3d.h.
|
private |
for setting ROS name space
Definition at line 84 of file gazebo_ros_f3d.h.
|
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.
|
private |
ROS WrenchStamped topic name.
Definition at line 77 of file gazebo_ros_f3d.h.
|
private |
Definition at line 100 of file gazebo_ros_f3d.h.
|
private |
Definition at line 60 of file gazebo_ros_f3d.h.
|
private |
ROS WrenchStamped message.
Definition at line 71 of file gazebo_ros_f3d.h.