#include <gazebo_gps_plugin.h>
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. | |
Private Member Functions | |
void | CreatePubsAndSubs () |
Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. | |
Private Attributes | |
std::string | gps_topic_ |
Name of topic for GPS messages, read from SDF file. | |
NormalDistribution | ground_speed_n_ [3] |
Normal distributions for ground speed noise in x, y, and z directions. | |
std::string | ground_speed_topic_ |
Name of topic for ground speed messages, read from SDF file. | |
gz_sensor_msgs::NavSatFix | gz_gps_message_ |
GPS message to be published on sensor update. | |
gazebo::transport::PublisherPtr | gz_gps_pub_ |
gz_geometry_msgs::TwistStamped | gz_ground_speed_message_ |
Ground speed message to be published on sensor update. | |
gazebo::transport::PublisherPtr | gz_ground_speed_pub_ |
physics::LinkPtr | link_ |
Pointer to the sensor link. | |
std::string | namespace_ |
gazebo::transport::NodePtr | node_handle_ |
sensors::GpsSensorPtr | parent_sensor_ |
Pointer to the parent sensor. | |
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(). | |
std::random_device | random_device_ |
Random number generator. | |
std::mt19937 | random_generator_ |
event::ConnectionPtr | updateConnection_ |
Pointer to the update event connection. | |
physics::WorldPtr | world_ |
Pointer to the world. |
Definition at line 42 of file gazebo_gps_plugin.h.
typedef std::normal_distribution gazebo::GazeboGpsPlugin::NormalDistribution |
Definition at line 44 of file gazebo_gps_plugin.h.
Definition at line 29 of file gazebo_gps_plugin.cpp.
gazebo::GazeboGpsPlugin::~GazeboGpsPlugin | ( | ) | [virtual] |
Definition at line 35 of file gazebo_gps_plugin.cpp.
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.
void gazebo::GazeboGpsPlugin::Load | ( | sensors::SensorPtr | _sensor, |
sdf::ElementPtr | _sdf | ||
) | [protected] |
Definition at line 38 of file gazebo_gps_plugin.cpp.
void gazebo::GazeboGpsPlugin::OnUpdate | ( | ) | [protected] |
Publishes both a NavSatFix and Gazebo message.
Definition at line 155 of file gazebo_gps_plugin.cpp.
Name of topic for GPS messages, read from SDF file.
Definition at line 76 of file gazebo_gps_plugin.h.
Normal distributions for ground speed noise in x, y, and z directions.
Definition at line 100 of file gazebo_gps_plugin.h.
Name of topic for ground speed messages, read from SDF file.
Definition at line 79 of file gazebo_gps_plugin.h.
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.
gazebo::transport::PublisherPtr gazebo::GazeboGpsPlugin::gz_gps_pub_ [private] |
Definition at line 71 of file gazebo_gps_plugin.h.
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.
gazebo::transport::PublisherPtr gazebo::GazeboGpsPlugin::gz_ground_speed_pub_ [private] |
Definition at line 73 of file gazebo_gps_plugin.h.
physics::LinkPtr gazebo::GazeboGpsPlugin::link_ [private] |
Pointer to the sensor link.
Definition at line 88 of file gazebo_gps_plugin.h.
Definition at line 57 of file gazebo_gps_plugin.h.
gazebo::transport::NodePtr gazebo::GazeboGpsPlugin::node_handle_ [private] |
Definition at line 69 of file gazebo_gps_plugin.h.
sensors::GpsSensorPtr gazebo::GazeboGpsPlugin::parent_sensor_ [private] |
Pointer to the parent sensor.
Definition at line 82 of file gazebo_gps_plugin.h.
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.
std::random_device gazebo::GazeboGpsPlugin::random_device_ [private] |
Random number generator.
Definition at line 103 of file gazebo_gps_plugin.h.
std::mt19937 gazebo::GazeboGpsPlugin::random_generator_ [private] |
Definition at line 105 of file gazebo_gps_plugin.h.
Pointer to the update event connection.
Definition at line 91 of file gazebo_gps_plugin.h.
physics::WorldPtr gazebo::GazeboGpsPlugin::world_ [private] |
Pointer to the world.
Definition at line 85 of file gazebo_gps_plugin.h.