Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef EVALUATION_HPP
00018 #define EVALUATION_HPP
00019
00020 #include <ros/ros.h>
00021
00022 #include "romeo_moveit_actions/metablock.hpp"
00023 #include "romeo_moveit_actions/action.hpp"
00024
00025 namespace moveit_simple_actions
00026 {
00027
00029 class Evaluation
00030 {
00031 public:
00033 Evaluation(const bool &verbose, const std::string &base_frame);
00034
00036 void init(const double &test_step,
00037 const double &block_size_x,
00038 const double &block_size_y,
00039 const double floor_to_base_height,
00040 const double &x_min,
00041 const double &x_max,
00042 const double &y_min,
00043 const double &y_max,
00044 const double &z_min,
00045 const double &z_max);
00046
00048 void testReach(ros::NodeHandle &nh,
00049 ros::Publisher *pub_obj_pose,
00050 ros::Publisher *pub_obj_poses,
00051 ros::Publisher *pub_obj_moveit,
00052 moveit_visual_tools::MoveItVisualToolsPtr visual_tools,
00053 Action *action_left,
00054 Action *action_right,
00055 std::vector<MetaBlock> *blocks_surfaces,
00056 const bool pickVsReach,
00057 const bool test_poses_rnd=false);
00058
00060 void printStat();
00061
00063 bool inWorkSpace(geometry_msgs::Pose pose,
00064 const bool x=true,
00065 const bool y=true,
00066 const bool z=true);
00067
00068 protected:
00070 geometry_msgs::PoseArray generatePosesGrid();
00071
00073 geometry_msgs::PoseArray generatePosesRnd(const int poses_nbr);
00074
00076 int testReachWithGenSingleHand(Action *action,
00077 std::vector<MetaBlock> *blocks_surfaces,
00078 ros::Publisher *pub_obj_pose,
00079 ros::Publisher *pub_obj_poses,
00080 ros::Publisher *pub_obj_moveit,
00081 moveit_visual_tools::MoveItVisualToolsPtr visual_tools,
00082 const bool pickVsReach,
00083 const int attempts_nbr,
00084 const double planning_time,
00085 geometry_msgs::PoseArray &msg_poses_validated);
00086
00088 bool verbose_;
00089
00091 std::string base_frame_;
00092
00094 double test_step_;
00095
00097 double block_size_x_;
00098
00100 double block_size_y_;
00101
00103 double floor_to_base_height_;
00104
00106 float x_min_;
00107
00109 float x_max_;
00110
00112 float y_min_;
00113
00115 float y_max_;
00116
00118 float z_min_;
00119
00121 float z_max_;
00122
00124 geometry_msgs::Pose pose_zero_;
00125
00127 std::vector <geometry_msgs::Pose> stat_poses_success_;
00128
00130 MetaBlock *block_;
00131
00133 MetaBlock *table_;
00134 };
00135 }
00136 #endif // EVALUATION_HPP