Public Member Functions | Private Member Functions | Private Attributes
fake_object_recognition::ErrorSimulation Class Reference

This class is used to simulate typical errors of an object recognition system. More...

#include <error_simulation.h>

List of all members.

Public Member Functions

geometry_msgs::Pose addNoiseToOrientation (const geometry_msgs::Pose &pose)
 Adds error values to the given pose (orientation only)
geometry_msgs::Pose addNoiseToPosition (const geometry_msgs::Pose &pose)
 Adds error values to the given pose (position only)
 ErrorSimulation ()
 The constructor of this class.
 ErrorSimulation (bool use_pose_invalidation, bool use_position_noise, bool use_orientation_noise)
 The constructor of this class (with parameters)
bool poseInvalidation ()
 Invalidates a pose by the probability member of this class.
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)
void setOrXNoiseDistMean (double or_x_noise_dist_mean)
 Sets the mean value of the normal distribution used by the orientation error generation (x-axis)
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)
void setOrYNoiseDistMean (double or_y_noise_dist_mean)
 Sets the mean value of the normal distribution used by the orientation error generation (y-axis)
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)
void setOrZNoiseDistMean (double or_z_noise_dist_mean)
 Sets the mean value of the normal distribution used by the orientation error generation (z-axis)
void setPoseNoiseDistDev (double pos_noise_dist_dev)
 Sets the standard deviation value of the normal distribution used by the position error generation.
void setPoseNoiseDistMean (double pos_noise_dist_mean)
 Sets the mean value of the normal distribution used by the position error generation.
void setProbPoseInval (double prob_pose_inval)
 Set the probability of the pose invalidation.

Private Member Functions

double genNormalDistNumber (double mean, double std_deviation)
 Returns a value calculated on a normal distribution.
double genUniformNumber (double interval_start, double interval_end)
 Returns a value calculated on a uniform distribution.

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_

Detailed Description

This class is used to simulate typical errors of an object recognition system.

Definition at line 55 of file error_simulation.h.


Constructor & Destructor Documentation

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)

Parameters:
use_pose_invalidationIndicates if pose invalidation is used
use_position_noiseIndicates if position errors are used
use_orientation_noiseIndicates if orientation errors are used

Definition at line 29 of file error_simulation.cpp.


Member Function Documentation

Adds error values to the given pose (orientation only)

Parameters:
poseThe given pose
Returns:
The pose with errors

Definition at line 75 of file error_simulation.cpp.

Adds error values to the given pose (position only)

Parameters:
poseThe given pose
Returns:
The pose with errors

Definition at line 64 of file error_simulation.cpp.

double fake_object_recognition::ErrorSimulation::genNormalDistNumber ( double  mean,
double  std_deviation 
) [private]

Returns a value calculated on a normal distribution.

Parameters:
interval_startThe mean value of the normal distribution
interval_endThe standard deviation value of the normal distribution
Returns:
The calculated value

Definition at line 50 of file error_simulation.cpp.

double fake_object_recognition::ErrorSimulation::genUniformNumber ( double  interval_start,
double  interval_end 
) [private]

Returns a value calculated on a uniform distribution.

Parameters:
interval_startThe lower value of the interval used for the uniform distribution
interval_endThe upper value of the interval used for the uniform distribution
Returns:
The calculated value

Definition at line 43 of file error_simulation.cpp.

Invalidates a pose by the probability member of this class.

Returns:
True if the pose is calculated as invalid, false otherwise

Definition at line 57 of file error_simulation.cpp.

Sets the standard deviation value of the normal distribution used by the orientation error generation (x-axis)

Parameters:
or_x_noise_dist_devThe standard deviation value to set

Definition at line 109 of file error_simulation.cpp.

Sets the mean value of the normal distribution used by the orientation error generation (x-axis)

Parameters:
or_x_noise_dist_meanThe mean value to set

Definition at line 105 of file error_simulation.cpp.

Sets the standard deviation value of the normal distribution used by the orientation error generation (y-axis)

Parameters:
or_y_noise_dist_devThe standard deviation value to set

Definition at line 117 of file error_simulation.cpp.

Sets the mean value of the normal distribution used by the orientation error generation (y-axis)

Parameters:
or_y_noise_dist_meanThe mean value to set

Definition at line 113 of file error_simulation.cpp.

Sets the standard deviation value of the normal distribution used by the orientation error generation (z-axis)

Parameters:
or_z_noise_dist_devThe standard deviation value to set

Definition at line 125 of file error_simulation.cpp.

Sets the mean value of the normal distribution used by the orientation error generation (z-axis)

Parameters:
or_z_noise_dist_meanThe mean value to set

Definition at line 121 of file error_simulation.cpp.

Sets the standard deviation value of the normal distribution used by the position error generation.

Parameters:
pos_noise_dist_meanThe standard deviation value to set

Definition at line 101 of file error_simulation.cpp.

Sets the mean value of the normal distribution used by the position error generation.

Parameters:
pos_noise_dist_meanThe mean value to set

Definition at line 97 of file error_simulation.cpp.

Set the probability of the pose invalidation.

Parameters:
prob_pose_invalThe probability to set

Definition at line 94 of file error_simulation.cpp.


Member Data Documentation

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.

The value of the normal distribution's mean value used for orientation errors (x-axis)

Definition at line 77 of file error_simulation.h.

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.

The value of the normal distribution's mean value used for orientation errors (y-axis)

Definition at line 83 of file error_simulation.h.

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.

The value of the normal distribution's mean value used for orientation errors (z-axis)

Definition at line 89 of file error_simulation.h.

The value of the normal distribution's standard deviation value used for position errors

Definition at line 73 of file error_simulation.h.

The value of the normal distribution's mean value used for position errors

Definition at line 70 of file error_simulation.h.

The value of the pose invalidation probability

Definition at line 67 of file error_simulation.h.

If this is true orientation errors are calculated

Definition at line 64 of file error_simulation.h.

If this is true pose invalidation errors are calculated

Definition at line 58 of file error_simulation.h.

If this is true position errors are calculated

Definition at line 61 of file error_simulation.h.


The documentation for this class was generated from the following files:


asr_fake_object_recognition
Author(s): Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Meißner Pascal, Qattan Mohamad
autogenerated on Sat Jun 8 2019 19:15:45