Class for the GPS sensor model. More...
#include <gps_sensor_model.h>
Public Member Functions | |
geometry_msgs::Twist | addGaussianNoise (geometry_msgs::Twist twist) |
add gausiann noise to the twist More... | |
geometry_msgs::Quaternion | addGaussianNoise (geometry_msgs::Quaternion orientation) |
add gaussian noise to the orientation More... | |
geodesy::UTMPoint | addGaussianNoise (geodesy::UTMPoint point) |
add gausiann noise to the point More... | |
GpsSensorModel (double position_gaussian_noise, double orientation_gaussian_noise, double velocity_gaussian_noise) | |
constructer of the GpsSensorModel class More... | |
~GpsSensorModel () | |
destructor of GpsSensorModel class More... | |
Public Attributes | |
const double | orientation_gaussian_noise |
variance of the orientation gaussian noise More... | |
const double | position_gaussian_noise |
variance of the position gaussian noise More... | |
const double | velocity_gaussian_noise |
variance of the velocity gaussian noise More... | |
Private Attributes | |
std::default_random_engine | engine_ |
random generation engine More... | |
std::normal_distribution | orientation_dist_ |
normal distribution generator for orientation More... | |
std::normal_distribution | position_dist_ |
normal distribution generator for position More... | |
std::random_device | seed_gen_ |
random seed generator More... | |
std::normal_distribution | twist_dist_ |
normal distribution generator for twist More... | |
Class for the GPS sensor model.
Definition at line 28 of file gps_sensor_model.h.
GpsSensorModel::GpsSensorModel | ( | double | position_gaussian_noise, |
double | orientation_gaussian_noise, | ||
double | velocity_gaussian_noise | ||
) |
constructer of the GpsSensorModel class
Definition at line 14 of file gps_sensor_model.cpp.
GpsSensorModel::~GpsSensorModel | ( | ) |
destructor of GpsSensorModel class
Definition at line 27 of file gps_sensor_model.cpp.
geometry_msgs::Twist GpsSensorModel::addGaussianNoise | ( | geometry_msgs::Twist | twist | ) |
add gausiann noise to the twist
Definition at line 32 of file gps_sensor_model.cpp.
geometry_msgs::Quaternion GpsSensorModel::addGaussianNoise | ( | geometry_msgs::Quaternion | orientation | ) |
add gaussian noise to the orientation
Definition at line 43 of file gps_sensor_model.cpp.
geodesy::UTMPoint GpsSensorModel::addGaussianNoise | ( | geodesy::UTMPoint | point | ) |
add gausiann noise to the point
Definition at line 50 of file gps_sensor_model.cpp.
|
private |
random generation engine
Definition at line 96 of file gps_sensor_model.h.
|
private |
normal distribution generator for orientation
Definition at line 81 of file gps_sensor_model.h.
const double GpsSensorModel::orientation_gaussian_noise |
variance of the orientation gaussian noise
Definition at line 45 of file gps_sensor_model.h.
|
private |
normal distribution generator for position
Definition at line 76 of file gps_sensor_model.h.
const double GpsSensorModel::position_gaussian_noise |
variance of the position gaussian noise
Definition at line 35 of file gps_sensor_model.h.
|
private |
random seed generator
Definition at line 91 of file gps_sensor_model.h.
|
private |
normal distribution generator for twist
Definition at line 86 of file gps_sensor_model.h.
const double GpsSensorModel::velocity_gaussian_noise |
variance of the velocity gaussian noise
Definition at line 40 of file gps_sensor_model.h.