Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboGpsPlugin Class Reference

#include <gazebo_gps_plugin.h>

Inheritance diagram for gazebo::GazeboGpsPlugin:
Inheritance graph
[legend]

Public Types

typedef std::normal_distribution NormalDistribution
 

Public Member Functions

 GazeboGpsPlugin ()
 
virtual ~GazeboGpsPlugin ()
 

Protected Member Functions

void Load (sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
 
void OnUpdate ()
 Publishes both a NavSatFix and Gazebo message. More...
 

Private Member Functions

void CreatePubsAndSubs ()
 Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. More...
 

Private Attributes

std::string gps_topic_
 Name of topic for GPS messages, read from SDF file. More...
 
NormalDistribution ground_speed_n_ [3]
 Normal distributions for ground speed noise in x, y, and z directions. More...
 
std::string ground_speed_topic_
 Name of topic for ground speed messages, read from SDF file. More...
 
gz_sensor_msgs::NavSatFix gz_gps_message_
 GPS message to be published on sensor update. More...
 
gazebo::transport::PublisherPtr gz_gps_pub_
 
gz_geometry_msgs::TwistStamped gz_ground_speed_message_
 Ground speed message to be published on sensor update. More...
 
gazebo::transport::PublisherPtr gz_ground_speed_pub_
 
physics::LinkPtr link_
 Pointer to the sensor link. More...
 
std::string namespace_
 
gazebo::transport::NodePtr node_handle_
 
sensors::GpsSensorPtr parent_sensor_
 Pointer to the parent sensor. More...
 
bool pubs_and_subs_created_
 Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate(). More...
 
std::random_device random_device_
 Random number generator. More...
 
std::mt19937 random_generator_
 
event::ConnectionPtr updateConnection_
 Pointer to the update event connection. More...
 
physics::WorldPtr world_
 Pointer to the world. More...
 

Detailed Description

Definition at line 42 of file gazebo_gps_plugin.h.

Member Typedef Documentation

◆ NormalDistribution

typedef std::normal_distribution gazebo::GazeboGpsPlugin::NormalDistribution

Definition at line 44 of file gazebo_gps_plugin.h.

Constructor & Destructor Documentation

◆ GazeboGpsPlugin()

gazebo::GazeboGpsPlugin::GazeboGpsPlugin ( )

Definition at line 29 of file gazebo_gps_plugin.cpp.

◆ ~GazeboGpsPlugin()

gazebo::GazeboGpsPlugin::~GazeboGpsPlugin ( )
virtual

Definition at line 35 of file gazebo_gps_plugin.cpp.

Member Function Documentation

◆ CreatePubsAndSubs()

void gazebo::GazeboGpsPlugin::CreatePubsAndSubs ( )
private

Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required.

Call this once the first time OnUpdate() is called (can't be called from Load() because there is no guarantee GazeboRosInterfacePlugin has has loaded and listening to ConnectGazeboToRosTopic and ConnectRosToGazeboTopic messages).

Definition at line 206 of file gazebo_gps_plugin.cpp.

◆ Load()

void gazebo::GazeboGpsPlugin::Load ( sensors::SensorPtr  _sensor,
sdf::ElementPtr  _sdf 
)
protected

Definition at line 38 of file gazebo_gps_plugin.cpp.

◆ OnUpdate()

void gazebo::GazeboGpsPlugin::OnUpdate ( )
protected

Publishes both a NavSatFix and Gazebo message.

Definition at line 155 of file gazebo_gps_plugin.cpp.

Member Data Documentation

◆ gps_topic_

std::string gazebo::GazeboGpsPlugin::gps_topic_
private

Name of topic for GPS messages, read from SDF file.

Definition at line 76 of file gazebo_gps_plugin.h.

◆ ground_speed_n_

NormalDistribution gazebo::GazeboGpsPlugin::ground_speed_n_[3]
private

Normal distributions for ground speed noise in x, y, and z directions.

Definition at line 100 of file gazebo_gps_plugin.h.

◆ ground_speed_topic_

std::string gazebo::GazeboGpsPlugin::ground_speed_topic_
private

Name of topic for ground speed messages, read from SDF file.

Definition at line 79 of file gazebo_gps_plugin.h.

◆ gz_gps_message_

gz_sensor_msgs::NavSatFix gazebo::GazeboGpsPlugin::gz_gps_message_
private

GPS message to be published on sensor update.

Definition at line 94 of file gazebo_gps_plugin.h.

◆ gz_gps_pub_

gazebo::transport::PublisherPtr gazebo::GazeboGpsPlugin::gz_gps_pub_
private

Definition at line 71 of file gazebo_gps_plugin.h.

◆ gz_ground_speed_message_

gz_geometry_msgs::TwistStamped gazebo::GazeboGpsPlugin::gz_ground_speed_message_
private

Ground speed message to be published on sensor update.

Definition at line 97 of file gazebo_gps_plugin.h.

◆ gz_ground_speed_pub_

gazebo::transport::PublisherPtr gazebo::GazeboGpsPlugin::gz_ground_speed_pub_
private

Definition at line 73 of file gazebo_gps_plugin.h.

◆ link_

physics::LinkPtr gazebo::GazeboGpsPlugin::link_
private

Pointer to the sensor link.

Definition at line 88 of file gazebo_gps_plugin.h.

◆ namespace_

std::string gazebo::GazeboGpsPlugin::namespace_
private

Definition at line 57 of file gazebo_gps_plugin.h.

◆ node_handle_

gazebo::transport::NodePtr gazebo::GazeboGpsPlugin::node_handle_
private

Definition at line 69 of file gazebo_gps_plugin.h.

◆ parent_sensor_

sensors::GpsSensorPtr gazebo::GazeboGpsPlugin::parent_sensor_
private

Pointer to the parent sensor.

Definition at line 82 of file gazebo_gps_plugin.h.

◆ pubs_and_subs_created_

bool gazebo::GazeboGpsPlugin::pubs_and_subs_created_
private

Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate().

Definition at line 61 of file gazebo_gps_plugin.h.

◆ random_device_

std::random_device gazebo::GazeboGpsPlugin::random_device_
private

Random number generator.

Definition at line 103 of file gazebo_gps_plugin.h.

◆ random_generator_

std::mt19937 gazebo::GazeboGpsPlugin::random_generator_
private

Definition at line 105 of file gazebo_gps_plugin.h.

◆ updateConnection_

event::ConnectionPtr gazebo::GazeboGpsPlugin::updateConnection_
private

Pointer to the update event connection.

Definition at line 91 of file gazebo_gps_plugin.h.

◆ world_

physics::WorldPtr gazebo::GazeboGpsPlugin::world_
private

Pointer to the world.

Definition at line 85 of file gazebo_gps_plugin.h.


The documentation for this class was generated from the following files:


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:04