23 #ifndef GAZEBO_ROS_FT_HH 24 #define GAZEBO_ROS_FT_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> 72 class GazeboRosFT :
public ModelPlugin
84 public:
void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
91 private:
unsigned int seed;
virtual void UpdateChild()
Update the controller.
std::string topic_name_
ROS WrenchStamped topic name.
virtual ~GazeboRosFT()
Destructor.
int ft_connect_count_
: keep track of number of connections
std::string robot_namespace_
for setting ROS name space
physics::JointPtr joint_
A pointer to the Gazebo joint.
geometry_msgs::WrenchStamped wrench_msg_
ROS WrenchStamped message.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
ros::CallbackQueue queue_
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
boost::mutex lock_
A mutex to lock access to fields that are used in message callbacks.
boost::thread callback_queue_thread_
double gaussian_noise_
Gaussian noise.
physics::WorldPtr world_
A pointer to the Gazebo world.
event::ConnectionPtr update_connection_
physics::ModelPtr model_
A pointer to the Gazebo model.
physics::LinkPtr parent_link_
A pointer to the Gazebo parent link.
physics::LinkPtr child_link_
A pointer to the Gazebo child link.
common::Time last_time_
save last_time
GazeboRosFT()
Constructor.
std::string joint_name_
store bodyname
std::string frame_name_
ROS frame transform name to use in the image message header. FIXME: extract link name directly...