29 #ifndef HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_AERODYNAMICS_H 30 #define HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_AERODYNAMICS_H 32 #include <gazebo/common/Plugin.hh> 33 #include <gazebo/common/Time.hh> 38 #include <boost/thread.hpp> 52 virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
89 #endif // HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_AERODYNAMICS_H
boost::thread callback_queue_thread_
virtual ~GazeboQuadrotorAerodynamics()
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
ros::CallbackQueue callback_queue_
ros::Publisher wrench_publisher_
ros::Subscriber wind_subscriber_
std::string wrench_topic_
GazeboQuadrotorAerodynamics()
physics::LinkPtr link
The link referred to by this plugin.
std::string param_namespace_
ros::NodeHandle * node_handle_
physics::WorldPtr world
The parent World.
hector_quadrotor_model::QuadrotorAerodynamics model_
event::ConnectionPtr updateConnection