This class is used to simulate typical errors of an object recognition system. More...
#include <error_simulation.h>
Public Member Functions | |
geometry_msgs::Pose | addNoiseToOrientation (const geometry_msgs::Pose &pose) |
Adds error values to the given pose (orientation only) More... | |
geometry_msgs::Pose | addNoiseToPosition (const geometry_msgs::Pose &pose) |
Adds error values to the given pose (position only) More... | |
ErrorSimulation () | |
The constructor of this class. More... | |
ErrorSimulation (bool use_pose_invalidation, bool use_position_noise, bool use_orientation_noise) | |
The constructor of this class (with parameters) More... | |
bool | poseInvalidation () |
Invalidates a pose by the probability member of this class. More... | |
void | setOrXNoiseDistDev (double or_x_noise_dist_dev) |
Sets the standard deviation value of the normal distribution used by the orientation error generation (x-axis) More... | |
void | setOrXNoiseDistMean (double or_x_noise_dist_mean) |
Sets the mean value of the normal distribution used by the orientation error generation (x-axis) More... | |
void | setOrYNoiseDistDev (double or_y_noise_dist_dev) |
Sets the standard deviation value of the normal distribution used by the orientation error generation (y-axis) More... | |
void | setOrYNoiseDistMean (double or_y_noise_dist_mean) |
Sets the mean value of the normal distribution used by the orientation error generation (y-axis) More... | |
void | setOrZNoiseDistDev (double or_z_noise_dist_dev) |
Sets the standard deviation value of the normal distribution used by the orientation error generation (z-axis) More... | |
void | setOrZNoiseDistMean (double or_z_noise_dist_mean) |
Sets the mean value of the normal distribution used by the orientation error generation (z-axis) More... | |
void | setPoseNoiseDistDev (double pos_noise_dist_dev) |
Sets the standard deviation value of the normal distribution used by the position error generation. More... | |
void | setPoseNoiseDistMean (double pos_noise_dist_mean) |
Sets the mean value of the normal distribution used by the position error generation. More... | |
void | setProbPoseInval (double prob_pose_inval) |
Set the probability of the pose invalidation. More... | |
Private Member Functions | |
double | genNormalDistNumber (double mean, double std_deviation) |
Returns a value calculated on a normal distribution. More... | |
double | genUniformNumber (double interval_start, double interval_end) |
Returns a value calculated on a uniform distribution. More... | |
Private Attributes | |
double | or_x_noise_dist_dev_ |
double | or_x_noise_dist_mean_ |
double | or_y_noise_dist_dev_ |
double | or_y_noise_dist_mean_ |
double | or_z_noise_dist_dev_ |
double | or_z_noise_dist_mean_ |
double | pos_noise_dist_dev_ |
double | pos_noise_dist_mean_ |
double | prob_pose_inval_ |
bool | use_orientation_noise_ |
bool | use_pose_invalidation_ |
bool | use_position_noise_ |
This class is used to simulate typical errors of an object recognition system.
Definition at line 55 of file error_simulation.h.
fake_object_recognition::ErrorSimulation::ErrorSimulation | ( | ) |
The constructor of this class.
Definition at line 27 of file error_simulation.cpp.
fake_object_recognition::ErrorSimulation::ErrorSimulation | ( | bool | use_pose_invalidation, |
bool | use_position_noise, | ||
bool | use_orientation_noise | ||
) |
The constructor of this class (with parameters)
use_pose_invalidation | Indicates if pose invalidation is used |
use_position_noise | Indicates if position errors are used |
use_orientation_noise | Indicates if orientation errors are used |
Definition at line 29 of file error_simulation.cpp.
geometry_msgs::Pose fake_object_recognition::ErrorSimulation::addNoiseToOrientation | ( | const geometry_msgs::Pose & | pose | ) |
Adds error values to the given pose (orientation only)
pose | The given pose |
Definition at line 75 of file error_simulation.cpp.
geometry_msgs::Pose fake_object_recognition::ErrorSimulation::addNoiseToPosition | ( | const geometry_msgs::Pose & | pose | ) |
Adds error values to the given pose (position only)
pose | The given pose |
Definition at line 64 of file error_simulation.cpp.
|
private |
Returns a value calculated on a normal distribution.
interval_start | The mean value of the normal distribution |
interval_end | The standard deviation value of the normal distribution |
Definition at line 50 of file error_simulation.cpp.
|
private |
Returns a value calculated on a uniform distribution.
interval_start | The lower value of the interval used for the uniform distribution |
interval_end | The upper value of the interval used for the uniform distribution |
Definition at line 43 of file error_simulation.cpp.
bool fake_object_recognition::ErrorSimulation::poseInvalidation | ( | ) |
Invalidates a pose by the probability member of this class.
Definition at line 57 of file error_simulation.cpp.
void fake_object_recognition::ErrorSimulation::setOrXNoiseDistDev | ( | double | or_x_noise_dist_dev | ) |
Sets the standard deviation value of the normal distribution used by the orientation error generation (x-axis)
or_x_noise_dist_dev | The standard deviation value to set |
Definition at line 109 of file error_simulation.cpp.
void fake_object_recognition::ErrorSimulation::setOrXNoiseDistMean | ( | double | or_x_noise_dist_mean | ) |
Sets the mean value of the normal distribution used by the orientation error generation (x-axis)
or_x_noise_dist_mean | The mean value to set |
Definition at line 105 of file error_simulation.cpp.
void fake_object_recognition::ErrorSimulation::setOrYNoiseDistDev | ( | double | or_y_noise_dist_dev | ) |
Sets the standard deviation value of the normal distribution used by the orientation error generation (y-axis)
or_y_noise_dist_dev | The standard deviation value to set |
Definition at line 117 of file error_simulation.cpp.
void fake_object_recognition::ErrorSimulation::setOrYNoiseDistMean | ( | double | or_y_noise_dist_mean | ) |
Sets the mean value of the normal distribution used by the orientation error generation (y-axis)
or_y_noise_dist_mean | The mean value to set |
Definition at line 113 of file error_simulation.cpp.
void fake_object_recognition::ErrorSimulation::setOrZNoiseDistDev | ( | double | or_z_noise_dist_dev | ) |
Sets the standard deviation value of the normal distribution used by the orientation error generation (z-axis)
or_z_noise_dist_dev | The standard deviation value to set |
Definition at line 125 of file error_simulation.cpp.
void fake_object_recognition::ErrorSimulation::setOrZNoiseDistMean | ( | double | or_z_noise_dist_mean | ) |
Sets the mean value of the normal distribution used by the orientation error generation (z-axis)
or_z_noise_dist_mean | The mean value to set |
Definition at line 121 of file error_simulation.cpp.
void fake_object_recognition::ErrorSimulation::setPoseNoiseDistDev | ( | double | pos_noise_dist_dev | ) |
Sets the standard deviation value of the normal distribution used by the position error generation.
pos_noise_dist_mean | The standard deviation value to set |
Definition at line 101 of file error_simulation.cpp.
void fake_object_recognition::ErrorSimulation::setPoseNoiseDistMean | ( | double | pos_noise_dist_mean | ) |
Sets the mean value of the normal distribution used by the position error generation.
pos_noise_dist_mean | The mean value to set |
Definition at line 97 of file error_simulation.cpp.
void fake_object_recognition::ErrorSimulation::setProbPoseInval | ( | double | prob_pose_inval | ) |
Set the probability of the pose invalidation.
prob_pose_inval | The probability to set |
Definition at line 94 of file error_simulation.cpp.
|
private |
The value of the normal distribution's standard deviation value used for orientation errors (x-axis)
Definition at line 80 of file error_simulation.h.
|
private |
The value of the normal distribution's mean value used for orientation errors (x-axis)
Definition at line 77 of file error_simulation.h.
|
private |
The value of the normal distribution's standard deviation value used for orientation errors (y-axis)
Definition at line 86 of file error_simulation.h.
|
private |
The value of the normal distribution's mean value used for orientation errors (y-axis)
Definition at line 83 of file error_simulation.h.
|
private |
The value of the normal distribution's standard deviation value used for orientation errors (z-axis)
Definition at line 92 of file error_simulation.h.
|
private |
The value of the normal distribution's mean value used for orientation errors (z-axis)
Definition at line 89 of file error_simulation.h.
|
private |
The value of the normal distribution's standard deviation value used for position errors
Definition at line 73 of file error_simulation.h.
|
private |
The value of the normal distribution's mean value used for position errors
Definition at line 70 of file error_simulation.h.
|
private |
The value of the pose invalidation probability
Definition at line 67 of file error_simulation.h.
|
private |
If this is true orientation errors are calculated
Definition at line 64 of file error_simulation.h.
|
private |
If this is true pose invalidation errors are calculated
Definition at line 58 of file error_simulation.h.
|
private |
If this is true position errors are calculated
Definition at line 61 of file error_simulation.h.