18 #ifndef ROTORS_GAZEBO_PLUGINS_GPS_PLUGIN_H 19 #define ROTORS_GAZEBO_PLUGINS_GPS_PLUGIN_H 25 #include <gazebo/gazebo.hh> 26 #include <gazebo/physics/physics.hh> 27 #include <gazebo/sensors/sensors.hh> 30 #include "NavSatFix.pb.h" 31 #include "TwistStamped.pb.h" 50 void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf);
110 #endif // ROTORS_GAZEBO_PLUGINS_GPS_PLUGIN_H std::random_device random_device_
Random number generator.
gz_sensor_msgs::NavSatFix gz_gps_message_
GPS message to be published on sensor update.
gazebo::transport::PublisherPtr gz_ground_speed_pub_
sensors::GpsSensorPtr parent_sensor_
Pointer to the parent sensor.
NormalDistribution ground_speed_n_[3]
Normal distributions for ground speed noise in x, y, and z directions.
gazebo::transport::PublisherPtr gz_gps_pub_
event::ConnectionPtr updateConnection_
Pointer to the update event connection.
gz_geometry_msgs::TwistStamped gz_ground_speed_message_
Ground speed message to be published on sensor update.
std::string ground_speed_topic_
Name of topic for ground speed messages, read from SDF file.
std::string gps_topic_
Name of topic for GPS messages, read from SDF file.
std::normal_distribution NormalDistribution
physics::LinkPtr link_
Pointer to the sensor link.
static constexpr double kDefaultHorVelStdDev
static constexpr double kDefaultVerPosStdDev
static constexpr double kDefaultHorPosStdDev
void CreatePubsAndSubs()
Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required...
physics::WorldPtr world_
Pointer to the world.
void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
std::mt19937 random_generator_
bool pubs_and_subs_created_
Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from...
gazebo::transport::NodePtr node_handle_
void OnUpdate()
Publishes both a NavSatFix and Gazebo message.
virtual ~GazeboGpsPlugin()
static constexpr double kDefaultVerVelStdDev