29 #ifndef HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_BARO_H 30 #define HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_BARO_H 32 #include <gazebo/common/Plugin.hh> 35 #include <geometry_msgs/PointStamped.h> 36 #include <hector_uav_msgs/Altimeter.h> 41 #include <dynamic_reconfigure/server.h> 53 virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
90 #endif // HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_BARO_H
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_
physics::WorldPtr world
The parent World.
geometry_msgs::PointStamped height_
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
ros::Publisher height_publisher_
hector_uav_msgs::Altimeter altimeter_
ros::NodeHandle * node_handle_
physics::LinkPtr link
The link referred to by this plugin.
SensorModel sensor_model_
std::string height_topic_
ros::Publisher altimeter_publisher_
event::ConnectionPtr updateConnection
std::string altimeter_topic_