Class for evaluation the algorithm. More...
#include <evaluation.hpp>
Public Member Functions | |
| Evaluation (const bool &verbose, const std::string &base_frame) | |
| constructor | |
| void | init (const double &test_step, const double &block_size_x, const double &block_size_y, const double floor_to_base_height, const double &x_min, const double &x_max, const double &y_min, const double &y_max, const double &z_min, const double &z_max) |
| initialization | |
| bool | inWorkSpace (geometry_msgs::Pose pose, const bool x=true, const bool y=true, const bool z=true) |
| checking if the pose is within the working space (close enough) | |
| void | printStat () |
| printing the successfully reached positions | |
| void | testReach (ros::NodeHandle &nh, ros::Publisher *pub_obj_pose, ros::Publisher *pub_obj_poses, ros::Publisher *pub_obj_moveit, moveit_visual_tools::MoveItVisualToolsPtr visual_tools, Action *action_left, Action *action_right, std::vector< MetaBlock > *blocks_surfaces, const bool pickVsReach, const bool test_poses_rnd=false) |
| testing grasping or approximate grasping | |
Protected Member Functions | |
| geometry_msgs::PoseArray | generatePosesGrid () |
| generating test poses in a regular maner | |
| geometry_msgs::PoseArray | generatePosesRnd (const int poses_nbr) |
| generating poses in a random maner | |
| int | testReachWithGenSingleHand (Action *action, std::vector< MetaBlock > *blocks_surfaces, ros::Publisher *pub_obj_pose, ros::Publisher *pub_obj_poses, ros::Publisher *pub_obj_moveit, moveit_visual_tools::MoveItVisualToolsPtr visual_tools, const bool pickVsReach, const int attempts_nbr, const double planning_time, geometry_msgs::PoseArray &msg_poses_validated) |
| testing a single hand | |
Protected Attributes | |
| std::string | base_frame_ |
| MetaBlock * | block_ |
| double | block_size_x_ |
| double | block_size_y_ |
| double | floor_to_base_height_ |
| geometry_msgs::Pose | pose_zero_ |
| std::vector< geometry_msgs::Pose > | stat_poses_success_ |
| MetaBlock * | table_ |
| double | test_step_ |
| bool | verbose_ |
| float | x_max_ |
| float | x_min_ |
| float | y_max_ |
| float | y_min_ |
| float | z_max_ |
| float | z_min_ |
Class for evaluation the algorithm.
Definition at line 29 of file evaluation.hpp.
| moveit_simple_actions::Evaluation::Evaluation | ( | const bool & | verbose, |
| const std::string & | base_frame | ||
| ) |
constructor
Definition at line 23 of file evaluation.cpp.
| geometry_msgs::PoseArray moveit_simple_actions::Evaluation::generatePosesGrid | ( | ) | [protected] |
generating test poses in a regular maner
Definition at line 79 of file evaluation.cpp.
| geometry_msgs::PoseArray moveit_simple_actions::Evaluation::generatePosesRnd | ( | const int | poses_nbr | ) | [protected] |
generating poses in a random maner
Definition at line 137 of file evaluation.cpp.
| void moveit_simple_actions::Evaluation::init | ( | const double & | test_step, |
| const double & | block_size_x, | ||
| const double & | block_size_y, | ||
| const double | floor_to_base_height, | ||
| const double & | x_min, | ||
| const double & | x_max, | ||
| const double & | y_min, | ||
| const double & | y_max, | ||
| const double & | z_min, | ||
| const double & | z_max | ||
| ) |
initialization
Definition at line 36 of file evaluation.cpp.
| bool moveit_simple_actions::Evaluation::inWorkSpace | ( | geometry_msgs::Pose | pose, |
| const bool | x = true, |
||
| const bool | y = true, |
||
| const bool | z = true |
||
| ) |
checking if the pose is within the working space (close enough)
Definition at line 326 of file evaluation.cpp.
printing the successfully reached positions
Definition at line 316 of file evaluation.cpp.
| void moveit_simple_actions::Evaluation::testReach | ( | ros::NodeHandle & | nh, |
| ros::Publisher * | pub_obj_pose, | ||
| ros::Publisher * | pub_obj_poses, | ||
| ros::Publisher * | pub_obj_moveit, | ||
| moveit_visual_tools::MoveItVisualToolsPtr | visual_tools, | ||
| Action * | action_left, | ||
| Action * | action_right, | ||
| std::vector< MetaBlock > * | blocks_surfaces, | ||
| const bool | pickVsReach, | ||
| const bool | test_poses_rnd = false |
||
| ) |
testing grasping or approximate grasping
Definition at line 156 of file evaluation.cpp.
| int moveit_simple_actions::Evaluation::testReachWithGenSingleHand | ( | Action * | action, |
| std::vector< MetaBlock > * | blocks_surfaces, | ||
| ros::Publisher * | pub_obj_pose, | ||
| ros::Publisher * | pub_obj_poses, | ||
| ros::Publisher * | pub_obj_moveit, | ||
| moveit_visual_tools::MoveItVisualToolsPtr | visual_tools, | ||
| const bool | pickVsReach, | ||
| const int | attempts_nbr, | ||
| const double | planning_time, | ||
| geometry_msgs::PoseArray & | msg_poses_validated | ||
| ) | [protected] |
testing a single hand
Definition at line 221 of file evaluation.cpp.
std::string moveit_simple_actions::Evaluation::base_frame_ [protected] |
robot's base_frame
Definition at line 91 of file evaluation.hpp.
MetaBlock* moveit_simple_actions::Evaluation::block_ [protected] |
default object to grasp
Definition at line 130 of file evaluation.hpp.
double moveit_simple_actions::Evaluation::block_size_x_ [protected] |
size X of a default object
Definition at line 97 of file evaluation.hpp.
double moveit_simple_actions::Evaluation::block_size_y_ [protected] |
size Y of a default object
Definition at line 100 of file evaluation.hpp.
double moveit_simple_actions::Evaluation::floor_to_base_height_ [protected] |
shift of the robot's base to the floor
Definition at line 103 of file evaluation.hpp.
default zero pose
Definition at line 124 of file evaluation.hpp.
std::vector<geometry_msgs::Pose> moveit_simple_actions::Evaluation::stat_poses_success_ [protected] |
successfully reached target poses
Definition at line 127 of file evaluation.hpp.
MetaBlock* moveit_simple_actions::Evaluation::table_ [protected] |
default table to grasp on
Definition at line 133 of file evaluation.hpp.
double moveit_simple_actions::Evaluation::test_step_ [protected] |
step for testing the working space
Definition at line 94 of file evaluation.hpp.
bool moveit_simple_actions::Evaluation::verbose_ [protected] |
verbose or not
Definition at line 88 of file evaluation.hpp.
float moveit_simple_actions::Evaluation::x_max_ [protected] |
working space in X dim max
Definition at line 109 of file evaluation.hpp.
float moveit_simple_actions::Evaluation::x_min_ [protected] |
working space in X dim min
Definition at line 106 of file evaluation.hpp.
float moveit_simple_actions::Evaluation::y_max_ [protected] |
working space in Y dim max
Definition at line 115 of file evaluation.hpp.
float moveit_simple_actions::Evaluation::y_min_ [protected] |
working space in Y dim min
Definition at line 112 of file evaluation.hpp.
float moveit_simple_actions::Evaluation::z_max_ [protected] |
working space in Z dim max
Definition at line 121 of file evaluation.hpp.
float moveit_simple_actions::Evaluation::z_min_ [protected] |
working space in Z dim min
Definition at line 118 of file evaluation.hpp.