Go to the documentation of this file.
23 #ifndef GAZEBO_ROS_F3D_HH
24 #define GAZEBO_ROS_F3D_HH
30 #include <gazebo/physics/physics.hh>
31 #include <gazebo/transport/TransportTypes.hh>
32 #include <gazebo/common/Plugin.hh>
33 #include <gazebo/common/Events.hh>
36 #include <boost/thread.hpp>
37 #include <boost/thread/mutex.hpp>
38 #include <geometry_msgs/WrenchStamped.h>
55 public:
void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
63 private: physics::LinkPtr
link_;
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 link_name_
store bodyname
boost::mutex lock_
A mutex to lock access to fields that are used in message callbacks.
GazeboRosF3D controller This is a controller that simulates a 6 dof force sensor.
geometry_msgs::WrenchStamped wrench_msg_
ROS WrenchStamped message.
virtual ~GazeboRosF3D()
Destructor.
boost::thread callback_queue_thread_
std::string topic_name_
ROS WrenchStamped topic name.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
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 retu...
virtual void UpdateChild()
Update the controller.
physics::LinkPtr link_
A pointer to the Gazebo Body.
event::ConnectionPtr update_connection_
ros::CallbackQueue queue_
GazeboRosF3D()
Constructor.
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55