29 #ifndef HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_GPS_H 30 #define HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_GPS_H 32 #include <gazebo/common/Plugin.hh> 35 #include <sensor_msgs/NavSatFix.h> 36 #include <geometry_msgs/Vector3Stamped.h> 40 #include <dynamic_reconfigure/server.h> 41 #include <hector_gazebo_plugins/GNSSConfig.h> 53 virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
71 sensor_msgs::NavSatFix
fix_;
100 #endif // HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_GPS_H
double reference_longitude_
void dynamicReconfigureCallback(GNSSConfig &config, uint32_t level)
sensor_msgs::NavSatFix fix_
physics::WorldPtr world
The parent World.
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_velocity_
double reference_heading_
ros::Publisher fix_publisher_
boost::shared_ptr< dynamic_reconfigure::Server< GNSSConfig > > dynamic_reconfigure_server_status_
double reference_altitude_
hector_gazebo_plugins::GNSSConfig GNSSConfig
std::string velocity_topic_
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
SensorModel3 velocity_error_model_
geometry_msgs::Vector3Stamped velocity_
event::ConnectionPtr updateConnection
physics::LinkPtr link
The link referred to by this plugin.
double reference_latitude_
ros::Publisher velocity_publisher_
ros::NodeHandle * node_handle_
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_position_
SensorModel3 position_error_model_