Class of the NMEA gps plugin.
More...
#include <nmea_gps_plugin.h>
|
virtual void | Load (physics::ModelPtr model, sdf::ElementPtr sdf) |
| Load parameters for the nmea gps plugin. More...
|
|
virtual void | Reset () |
| Reset the nmea gps plugin. More...
|
|
virtual void | Update () |
| Update the sensor state and publish nmea sentence. More...
|
|
Class of the NMEA gps plugin.
Definition at line 104 of file nmea_gps_plugin.h.
◆ NmeaGpsPlugin()
gazebo::NmeaGpsPlugin::NmeaGpsPlugin |
( |
| ) |
|
◆ ~NmeaGpsPlugin()
gazebo::NmeaGpsPlugin::~NmeaGpsPlugin |
( |
| ) |
|
|
virtual |
◆ convertToDmm()
std::string gazebo::NmeaGpsPlugin::convertToDmm |
( |
double |
value | ) |
|
|
private |
◆ getCheckSum()
std::string gazebo::NmeaGpsPlugin::getCheckSum |
( |
std::string |
sentence | ) |
|
|
private |
◆ getGPGGA()
nmea_msgs::Sentence gazebo::NmeaGpsPlugin::getGPGGA |
( |
ros::Time |
stamp | ) |
|
|
private |
◆ getGPHDT()
nmea_msgs::Sentence gazebo::NmeaGpsPlugin::getGPHDT |
( |
ros::Time |
stamp | ) |
|
|
private |
◆ getGPRMC()
nmea_msgs::Sentence gazebo::NmeaGpsPlugin::getGPRMC |
( |
ros::Time |
stamp | ) |
|
|
private |
◆ getGPVTG()
nmea_msgs::Sentence gazebo::NmeaGpsPlugin::getGPVTG |
( |
ros::Time |
stamp | ) |
|
|
private |
◆ getHexString()
std::string gazebo::NmeaGpsPlugin::getHexString |
( |
uint8_t |
value | ) |
|
|
private |
◆ getUnixDay()
std::string gazebo::NmeaGpsPlugin::getUnixDay |
( |
ros::Time |
stamp | ) |
|
|
private |
◆ getUnixTime()
std::string gazebo::NmeaGpsPlugin::getUnixTime |
( |
ros::Time |
stamp | ) |
|
|
private |
◆ Load()
void gazebo::NmeaGpsPlugin::Load |
( |
physics::ModelPtr |
model, |
|
|
sdf::ElementPtr |
sdf |
|
) |
| |
|
protectedvirtual |
◆ Reset()
void gazebo::NmeaGpsPlugin::Reset |
( |
| ) |
|
|
protectedvirtual |
◆ Update()
void gazebo::NmeaGpsPlugin::Update |
( |
| ) |
|
|
protectedvirtual |
◆ current_geo_pose_
geographic_msgs::GeoPose gazebo::NmeaGpsPlugin::current_geo_pose_ |
|
private |
◆ current_twist_
geometry_msgs::Twist gazebo::NmeaGpsPlugin::current_twist_ |
|
private |
◆ frame_id_
std::string gazebo::NmeaGpsPlugin::frame_id_ |
|
private |
◆ initial_gazebo_pose_
◆ initial_pose_
geographic_msgs::GeoPose gazebo::NmeaGpsPlugin::initial_pose_ |
|
private |
◆ initial_utm_pose_
◆ last_publish_timestamp_
boost::optional<common::Time> gazebo::NmeaGpsPlugin::last_publish_timestamp_ |
|
private |
◆ link_name_
std::string gazebo::NmeaGpsPlugin::link_name_ |
|
private |
◆ link_ptr_
physics::LinkPtr gazebo::NmeaGpsPlugin::link_ptr_ |
|
private |
◆ model_ptr_
physics::ModelPtr gazebo::NmeaGpsPlugin::model_ptr_ |
|
private |
◆ namespace_
std::string gazebo::NmeaGpsPlugin::namespace_ |
|
private |
◆ nmea_pub_
◆ nmea_topic_
std::string gazebo::NmeaGpsPlugin::nmea_topic_ |
|
private |
◆ node_handle_
◆ orientation_gaussian_noise_
double gazebo::NmeaGpsPlugin::orientation_gaussian_noise_ |
|
private |
◆ position_gaussiaa_noise_
double gazebo::NmeaGpsPlugin::position_gaussiaa_noise_ |
|
private |
◆ publish_rate_
double gazebo::NmeaGpsPlugin::publish_rate_ |
|
private |
◆ reference_altitude_
double gazebo::NmeaGpsPlugin::reference_altitude_ |
|
private |
◆ reference_heading_
double gazebo::NmeaGpsPlugin::reference_heading_ |
|
private |
◆ reference_latitude_
double gazebo::NmeaGpsPlugin::reference_latitude_ |
|
private |
◆ reference_longitude_
double gazebo::NmeaGpsPlugin::reference_longitude_ |
|
private |
◆ sensor_model_ptr_
std::unique_ptr<GpsSensorModel> gazebo::NmeaGpsPlugin::sensor_model_ptr_ |
|
private |
◆ update_connection_
◆ velocity_gaussian_noise_
double gazebo::NmeaGpsPlugin::velocity_gaussian_noise_ |
|
private |
◆ world_ptr_
physics::WorldPtr gazebo::NmeaGpsPlugin::world_ptr_ |
|
private |
The documentation for this class was generated from the following files: