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.
gazebo::NmeaGpsPlugin::NmeaGpsPlugin |
( |
| ) |
|
gazebo::NmeaGpsPlugin::~NmeaGpsPlugin |
( |
| ) |
|
|
virtual |
std::string gazebo::NmeaGpsPlugin::convertToDmm |
( |
double |
value | ) |
|
|
private |
std::string gazebo::NmeaGpsPlugin::getCheckSum |
( |
std::string |
sentence | ) |
|
|
private |
nmea_msgs::Sentence gazebo::NmeaGpsPlugin::getGPGGA |
( |
ros::Time |
stamp | ) |
|
|
private |
nmea_msgs::Sentence gazebo::NmeaGpsPlugin::getGPHDT |
( |
ros::Time |
stamp | ) |
|
|
private |
nmea_msgs::Sentence gazebo::NmeaGpsPlugin::getGPRMC |
( |
ros::Time |
stamp | ) |
|
|
private |
nmea_msgs::Sentence gazebo::NmeaGpsPlugin::getGPVTG |
( |
ros::Time |
stamp | ) |
|
|
private |
std::string gazebo::NmeaGpsPlugin::getHexString |
( |
uint8_t |
value | ) |
|
|
private |
std::string gazebo::NmeaGpsPlugin::getUnixDay |
( |
ros::Time |
stamp | ) |
|
|
private |
std::string gazebo::NmeaGpsPlugin::getUnixTime |
( |
ros::Time |
stamp | ) |
|
|
private |
void gazebo::NmeaGpsPlugin::Load |
( |
physics::ModelPtr |
model, |
|
|
sdf::ElementPtr |
sdf |
|
) |
| |
|
protectedvirtual |
void gazebo::NmeaGpsPlugin::Reset |
( |
| ) |
|
|
protectedvirtual |
void gazebo::NmeaGpsPlugin::Update |
( |
| ) |
|
|
protectedvirtual |
geographic_msgs::GeoPose gazebo::NmeaGpsPlugin::current_geo_pose_ |
|
private |
geometry_msgs::Twist gazebo::NmeaGpsPlugin::current_twist_ |
|
private |
std::string gazebo::NmeaGpsPlugin::frame_id_ |
|
private |
geographic_msgs::GeoPose gazebo::NmeaGpsPlugin::initial_pose_ |
|
private |
boost::optional<common::Time> gazebo::NmeaGpsPlugin::last_publish_timestamp_ |
|
private |
std::string gazebo::NmeaGpsPlugin::link_name_ |
|
private |
physics::LinkPtr gazebo::NmeaGpsPlugin::link_ptr_ |
|
private |
physics::ModelPtr gazebo::NmeaGpsPlugin::model_ptr_ |
|
private |
std::string gazebo::NmeaGpsPlugin::namespace_ |
|
private |
std::string gazebo::NmeaGpsPlugin::nmea_topic_ |
|
private |
double gazebo::NmeaGpsPlugin::orientation_gaussian_noise_ |
|
private |
double gazebo::NmeaGpsPlugin::position_gaussiaa_noise_ |
|
private |
double gazebo::NmeaGpsPlugin::publish_rate_ |
|
private |
double gazebo::NmeaGpsPlugin::reference_altitude_ |
|
private |
double gazebo::NmeaGpsPlugin::reference_heading_ |
|
private |
double gazebo::NmeaGpsPlugin::reference_latitude_ |
|
private |
double gazebo::NmeaGpsPlugin::reference_longitude_ |
|
private |
std::unique_ptr<GpsSensorModel> gazebo::NmeaGpsPlugin::sensor_model_ptr_ |
|
private |
double gazebo::NmeaGpsPlugin::velocity_gaussian_noise_ |
|
private |
physics::WorldPtr gazebo::NmeaGpsPlugin::world_ptr_ |
|
private |
The documentation for this class was generated from the following files: