rating.h
Go to the documentation of this file.
1 
18 #ifndef RATING_H
19 #define RATING_H
20 
21 #include <geometry_msgs/Pose.h>
22 #include <geometry_msgs/Point.h>
23 #include <Eigen/Dense>
24 
25 namespace fake_object_recognition {
26 
30 class Rating {
31 
33  double fovx_;
34 
36  double fovy_;
37 
39  double ncp_;
40 
42  double fcp_;
43 
45  const Eigen::Vector3d camera_orientation_;
46 
53  double getDistanceRating(const geometry_msgs::Pose &object_pose);
54 
62  double getAngleRating(const geometry_msgs::Pose &object_pose, bool direction);
63 
70  bool getBBRating(const std::array<geometry_msgs::Point, 8> &bounding_box);
71 
80  double getNormalRating(const geometry_msgs::Pose &object_pose, const std::vector<geometry_msgs::Point> &normals);
81 
82 public:
91  Rating(double fovx, double fovy, double ncp, double fcp);
92 
102  bool ratePose(const geometry_msgs::Pose &pose, double threshold_d, double threshold_x, double threshold_y);
103 
115  bool rateBBandNormal(const geometry_msgs::Pose &object_pose, const std::array<geometry_msgs::Point, 8> &bounding_box, const std::vector<geometry_msgs::Point> &normals, double threshold);
116 };
117 
118 }
119 
120 #endif /* RATING_H */
121 
bool getBBRating(const std::array< geometry_msgs::Point, 8 > &bounding_box)
Returns the amount of points of the bounding box inside the frustum divided by the amount of all poin...
Definition: rating.cpp:95
double getAngleRating(const geometry_msgs::Pose &object_pose, bool direction)
Returns a rating of an object&#39;s pose based on the (azimut or elevation) angle between the camera&#39;s vi...
Definition: rating.cpp:64
This class is used to rate an object&#39;s pose based on the current camera position. ...
Definition: rating.h:30
bool rateBBandNormal(const geometry_msgs::Pose &object_pose, const std::array< geometry_msgs::Point, 8 > &bounding_box, const std::vector< geometry_msgs::Point > &normals, double threshold)
Rates an objects visibility based on its bounding box and its normals.
Definition: rating.cpp:159
double getNormalRating(const geometry_msgs::Pose &object_pose, const std::vector< geometry_msgs::Point > &normals)
Returns a rating for the angle between sight vector to object and object&#39;s normal. 1.0 is best, 0.0 worst.
Definition: rating.cpp:126
bool ratePose(const geometry_msgs::Pose &pose, double threshold_d, double threshold_x, double threshold_y)
Return whether a pose is visible in the camera frustum based on the distance and angle rating...
Definition: rating.cpp:37
const Eigen::Vector3d camera_orientation_
Definition: rating.h:45
double getDistanceRating(const geometry_msgs::Pose &object_pose)
Returns a rating of an object&#39;s pose based on the distance to the camera.
Definition: rating.cpp:49
Rating(double fovx, double fovy, double ncp, double fcp)
The constructor of the class.
Definition: rating.cpp:30


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