error_simulation.h
Go to the documentation of this file.
1 
18 #ifndef ERROR_SIMULATION_H
19 #define ERROR_SIMULATION_H
20 
21 #include <geometry_msgs/Pose.h>
22 
24 
26 const static double DEFAULT_PROB_POSE_INVAL(0.01);
27 
29 const static double DEFAULT_POS_NOISE_MEAN(0.0);
30 
32 const static double DEFAULT_POS_NOISE_DEV(0.005);
33 
35 const static double DEFAULT_OR_X_NOISE_MEAN(0.0);
36 
38 const static double DEFAULT_OR_X_NOISE_DEV(0.02);
39 
41 const static double DEFAULT_OR_Y_NOISE_MEAN(0.0);
42 
44 const static double DEFAULT_OR_Y_NOISE_DEV(0.02);
45 
47 const static double DEFAULT_OR_Z_NOISE_MEAN(0.0);
48 
50 const static double DEFAULT_OR_Z_NOISE_DEV(0.02);
51 
56 
59 
62 
65 
68 
71 
74 
75 
78 
81 
84 
87 
90 
93 
94 
101  double genUniformNumber(double interval_start, double interval_end);
102 
109  double genNormalDistNumber(double mean, double std_deviation);
110 
111 
112 public:
116  ErrorSimulation();
117 
124  ErrorSimulation(bool use_pose_invalidation, bool use_position_noise, bool use_orientation_noise);
125 
130  bool poseInvalidation();
131 
137  geometry_msgs::Pose addNoiseToPosition(const geometry_msgs::Pose &pose);
138 
144  geometry_msgs::Pose addNoiseToOrientation(const geometry_msgs::Pose &pose);
145 
151  void setProbPoseInval(double prob_pose_inval);
152 
158  void setPoseNoiseDistMean(double pos_noise_dist_mean);
159 
165  void setPoseNoiseDistDev(double pos_noise_dist_dev);
166 
172  void setOrXNoiseDistMean(double or_x_noise_dist_mean);
173 
178  void setOrXNoiseDistDev(double or_x_noise_dist_dev);
179 
185  void setOrYNoiseDistMean(double or_y_noise_dist_mean);
186 
191  void setOrYNoiseDistDev(double or_y_noise_dist_dev);
192 
198  void setOrZNoiseDistMean(double or_z_noise_dist_mean);
199 
204  void setOrZNoiseDistDev(double or_z_noise_dist_dev);
205 };
206 
207 }
208 
209 #endif /* ERROR_SIMULATION_H */
double genUniformNumber(double interval_start, double interval_end)
Returns a value calculated on a uniform distribution.
void setOrZNoiseDistMean(double or_z_noise_dist_mean)
Sets the mean value of the normal distribution used by the orientation error generation (z-axis) ...
static const double DEFAULT_OR_Y_NOISE_DEV(0.02)
This class is used to simulate typical errors of an object recognition system.
double genNormalDistNumber(double mean, double std_deviation)
Returns a value calculated on a normal distribution.
static const double DEFAULT_OR_Z_NOISE_MEAN(0.0)
void setProbPoseInval(double prob_pose_inval)
Set the probability of the pose invalidation.
void setOrZNoiseDistDev(double or_z_noise_dist_dev)
Sets the standard deviation value of the normal distribution used by the orientation error generation...
ErrorSimulation()
The constructor of this class.
geometry_msgs::Pose addNoiseToOrientation(const geometry_msgs::Pose &pose)
Adds error values to the given pose (orientation only)
void setOrYNoiseDistDev(double or_y_noise_dist_dev)
Sets the standard deviation value of the normal distribution used by the orientation error generation...
void setOrXNoiseDistMean(double or_x_noise_dist_mean)
Sets the mean value of the normal distribution used by the orientation error generation (x-axis) ...
static const double DEFAULT_OR_X_NOISE_DEV(0.02)
static const double DEFAULT_OR_Y_NOISE_MEAN(0.0)
static const double DEFAULT_OR_Z_NOISE_DEV(0.02)
void setOrYNoiseDistMean(double or_y_noise_dist_mean)
Sets the mean value of the normal distribution used by the orientation error generation (y-axis) ...
bool poseInvalidation()
Invalidates a pose by the probability member of this class.
static const double DEFAULT_POS_NOISE_DEV(0.005)
void setPoseNoiseDistMean(double pos_noise_dist_mean)
Sets the mean value of the normal distribution used by the position error generation.
static const double DEFAULT_OR_X_NOISE_MEAN(0.0)
geometry_msgs::Pose addNoiseToPosition(const geometry_msgs::Pose &pose)
Adds error values to the given pose (position only)
void setPoseNoiseDistDev(double pos_noise_dist_dev)
Sets the standard deviation value of the normal distribution used by the position error generation...
static const double DEFAULT_PROB_POSE_INVAL(0.01)
static const double DEFAULT_POS_NOISE_MEAN(0.0)
void setOrXNoiseDistDev(double or_x_noise_dist_dev)
Sets the standard deviation value of the normal distribution used by the orientation error generation...


asr_fake_object_recognition
Author(s): Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Meißner Pascal, Qattan Mohamad
autogenerated on Wed Feb 19 2020 03:58:59