#include <gazebo_gps_plugin.h>
|
| void | Load (sensors::SensorPtr _sensor, sdf::ElementPtr _sdf) |
| |
| void | OnUpdate () |
| | Publishes both a NavSatFix and Gazebo message. More...
|
| |
|
| void | CreatePubsAndSubs () |
| | Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. More...
|
| |
Definition at line 42 of file gazebo_gps_plugin.h.
◆ NormalDistribution
◆ GazeboGpsPlugin()
| gazebo::GazeboGpsPlugin::GazeboGpsPlugin |
( |
| ) |
|
◆ ~GazeboGpsPlugin()
| gazebo::GazeboGpsPlugin::~GazeboGpsPlugin |
( |
| ) |
|
|
virtual |
◆ 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 |
◆ OnUpdate()
| void gazebo::GazeboGpsPlugin::OnUpdate |
( |
| ) |
|
|
protected |
◆ gps_topic_
| std::string gazebo::GazeboGpsPlugin::gps_topic_ |
|
private |
◆ ground_speed_n_
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 |
◆ gz_gps_pub_
| gazebo::transport::PublisherPtr gazebo::GazeboGpsPlugin::gz_gps_pub_ |
|
private |
◆ 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 |
◆ link_
| physics::LinkPtr gazebo::GazeboGpsPlugin::link_ |
|
private |
◆ namespace_
| std::string gazebo::GazeboGpsPlugin::namespace_ |
|
private |
◆ node_handle_
| gazebo::transport::NodePtr gazebo::GazeboGpsPlugin::node_handle_ |
|
private |
◆ parent_sensor_
| sensors::GpsSensorPtr gazebo::GazeboGpsPlugin::parent_sensor_ |
|
private |
◆ pubs_and_subs_created_
| bool gazebo::GazeboGpsPlugin::pubs_and_subs_created_ |
|
private |
◆ random_device_
| std::random_device gazebo::GazeboGpsPlugin::random_device_ |
|
private |
◆ random_generator_
| std::mt19937 gazebo::GazeboGpsPlugin::random_generator_ |
|
private |
◆ updateConnection_
◆ world_
| physics::WorldPtr gazebo::GazeboGpsPlugin::world_ |
|
private |
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