Public Member Functions | Public Attributes | Protected Attributes | List of all members
CCalc_Grasppoints Class Reference

Public Member Functions

void calc_featurevectors (int roll, int tilt)
 
void calc_intimage (int roll, int tilt)
 
 CCalc_Grasppoints (string name)
 
void generate_grid (int roll, int tilt, pcl::PointCloud< pcl::PointXYZ > pcl_cloud_in)
 
void gp_to_marker (visualization_msgs::Marker *marker, float x, float y, float z, float green, bool pubmarker, int gripperwidth, int nr_roll, bool pub_grip_open_dir, bool pub_grid)
 
void grasp_area_to_marker (visualization_msgs::Marker *marker, float x, float y, float z, int gripperwidth, int nr_roll, int param_id, bool top_grasp)
 
void loop_control (pcl::PointCloud< pcl::PointXYZ > pcl_cloud_in)
 
void pnt_in_box (int nr_roll, int nr_tilt)
 
void predict_bestgp_withsvm (bool svm_with_probability=false)
 
void print_heights (int nr_roll, int nr_tilt)
 
void publish_grasp_grid (int nr_roll, int tilt, float graspsgrid[][WIDTH], int gripperwidth)
 
void publish_transformed_pcl_cloud (int roll, int tilt, pcl::PointCloud< pcl::PointXYZ > pcl_cloud_in)
 
void read_pc_cb (const haf_grasping::CalcGraspPointsServerGoalConstPtr &goal)
 
void show_predicted_gps (int nr_roll, int tilt, bool svm_with_probability=false)
 
void transform_gp_in_wcs_and_publish (int id_row_top_all, int id_col_top_all, int nr_roll_top_all, int nr_tilt_top_all, int scaled_gp_eval)
 

Public Attributes

geometry_msgs::Vector3 approach_vector
 
Eigen::Matrix4f av_trans_mat
 
string base_frame_id
 
ros::Subscriber box_position_sub
 
float boxrot_angle_init
 
string feature_file_path
 
haf_grasping::GraspOutput gp_result
 
int grasp_search_area_size_x_dir
 
int grasp_search_area_size_y_dir
 
geometry_msgs::Point graspsearchcenter
 
int graspval_max_diff_for_pub
 
int graspval_th
 
int graspval_top
 
int gripper_opening_width
 
float heightsgridroll [ROLL_MAX_DEGREE/ROLL_STEPS_DEGREE][TILT_STEPS][HEIGHT][WIDTH]
 
int id_col_top_overall
 
int id_row_top_overall
 
float integralimageroll [ROLL_MAX_DEGREE/ROLL_STEPS_DEGREE][TILT_STEPS][HEIGHT+1][WIDTH+1]
 
int marker_cnt
 
float max_duration_for_grasp_calc
 
int nr_features_without_shaf
 
int nr_roll_top_overall
 
int nr_tilt_top_overall
 
string outputpath_full
 
ros::Subscriber pc_sub
 
bool point_inside_box_grid [ROLL_MAX_DEGREE/ROLL_STEPS_DEGREE][TILT_STEPS][HEIGHT][WIDTH]
 
bool print_heights_bool
 
ros::Publisher pubGraspPoints
 
ros::Publisher pubGraspPointsEval
 
ros::Publisher pubInputPCROS
 
ros::Publisher pubTransformedPCROS
 
tf::Quaternion quat_tf_to_tf_help
 
string range_file_path
 
bool return_only_best_gp
 
string svmmodel_file_path
 
tf::TransformListener tf_listener
 
int topval_gp_overall
 
float trans_z_after_pc_transform
 
ros::Publisher vis_pub
 
ros::Publisher vis_pub_ma
 
ros::Publisher vis_pub_ma_params
 
bool visualization
 

Protected Attributes

std::string action_name_
 
actionlib::SimpleActionServer< haf_grasping::CalcGraspPointsServerAction > as_
 
haf_grasping::CalcGraspPointsServerFeedback feedback_
 
ros::NodeHandle nh_
 
haf_grasping::CalcGraspPointsServerResult result_
 

Detailed Description

Definition at line 107 of file calc_grasppoints_action_server.cpp.

Constructor & Destructor Documentation

CCalc_Grasppoints::CCalc_Grasppoints ( string  name)
inline

Definition at line 181 of file calc_grasppoints_action_server.cpp.

Member Function Documentation

void CCalc_Grasppoints::calc_featurevectors ( int  roll,
int  tilt 
)

Definition at line 616 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::calc_intimage ( int  roll,
int  tilt 
)

Definition at line 577 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::generate_grid ( int  roll,
int  tilt,
pcl::PointCloud< pcl::PointXYZ >  pcl_cloud_in 
)

Definition at line 406 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::gp_to_marker ( visualization_msgs::Marker *  marker,
float  x,
float  y,
float  z,
float  green,
bool  pubmarker,
int  gripperwidth = 1,
int  nr_roll = 0,
bool  pub_grip_open_dir = false,
bool  pub_grid = true 
)

Definition at line 1020 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::grasp_area_to_marker ( visualization_msgs::Marker *  marker,
float  x,
float  y,
float  z,
int  gripperwidth = 1,
int  nr_roll = 0,
int  param_id = 1,
bool  top_grasp = false 
)

!!!!!!!!!!!!!!!!

Definition at line 1145 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::loop_control ( pcl::PointCloud< pcl::PointXYZ >  pcl_cloud_in)

Definition at line 335 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::pnt_in_box ( int  nr_roll,
int  nr_tilt 
)

Definition at line 666 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::predict_bestgp_withsvm ( bool  svm_with_probability = false)

Definition at line 754 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::print_heights ( int  nr_roll,
int  nr_tilt 
)

Definition at line 234 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::publish_grasp_grid ( int  nr_roll,
int  tilt,
float  graspsgrid[][WIDTH],
int  gripperwidth = 1 
)

Definition at line 979 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::publish_transformed_pcl_cloud ( int  roll,
int  tilt,
pcl::PointCloud< pcl::PointXYZ >  pcl_cloud_in 
)

Definition at line 533 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::read_pc_cb ( const haf_grasping::CalcGraspPointsServerGoalConstPtr &  goal)

Definition at line 250 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::show_predicted_gps ( int  nr_roll,
int  tilt,
bool  svm_with_probability = false 
)

Definition at line 803 of file calc_grasppoints_action_server.cpp.

void CCalc_Grasppoints::transform_gp_in_wcs_and_publish ( int  id_row_top_all,
int  id_col_top_all,
int  nr_roll_top_all,
int  nr_tilt_top_all,
int  scaled_gp_eval 
)

Definition at line 1274 of file calc_grasppoints_action_server.cpp.

Member Data Documentation

std::string CCalc_Grasppoints::action_name_
protected

Definition at line 114 of file calc_grasppoints_action_server.cpp.

geometry_msgs::Vector3 CCalc_Grasppoints::approach_vector

Definition at line 134 of file calc_grasppoints_action_server.cpp.

actionlib::SimpleActionServer<haf_grasping::CalcGraspPointsServerAction> CCalc_Grasppoints::as_
protected

Definition at line 113 of file calc_grasppoints_action_server.cpp.

Eigen::Matrix4f CCalc_Grasppoints::av_trans_mat

Definition at line 156 of file calc_grasppoints_action_server.cpp.

string CCalc_Grasppoints::base_frame_id

Definition at line 141 of file calc_grasppoints_action_server.cpp.

ros::Subscriber CCalc_Grasppoints::box_position_sub

Definition at line 121 of file calc_grasppoints_action_server.cpp.

float CCalc_Grasppoints::boxrot_angle_init

Definition at line 131 of file calc_grasppoints_action_server.cpp.

string CCalc_Grasppoints::feature_file_path

Definition at line 159 of file calc_grasppoints_action_server.cpp.

haf_grasping::CalcGraspPointsServerFeedback CCalc_Grasppoints::feedback_
protected

Definition at line 116 of file calc_grasppoints_action_server.cpp.

haf_grasping::GraspOutput CCalc_Grasppoints::gp_result

Definition at line 152 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::grasp_search_area_size_x_dir

Definition at line 132 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::grasp_search_area_size_y_dir

Definition at line 133 of file calc_grasppoints_action_server.cpp.

geometry_msgs::Point CCalc_Grasppoints::graspsearchcenter

Definition at line 130 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::graspval_max_diff_for_pub

Definition at line 144 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::graspval_th

Definition at line 142 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::graspval_top

Definition at line 143 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::gripper_opening_width

Definition at line 163 of file calc_grasppoints_action_server.cpp.

float CCalc_Grasppoints::heightsgridroll[ROLL_MAX_DEGREE/ROLL_STEPS_DEGREE][TILT_STEPS][HEIGHT][WIDTH]

Definition at line 136 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::id_col_top_overall

Definition at line 147 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::id_row_top_overall

Definition at line 146 of file calc_grasppoints_action_server.cpp.

float CCalc_Grasppoints::integralimageroll[ROLL_MAX_DEGREE/ROLL_STEPS_DEGREE][TILT_STEPS][HEIGHT+1][WIDTH+1]

Definition at line 137 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::marker_cnt

Definition at line 151 of file calc_grasppoints_action_server.cpp.

float CCalc_Grasppoints::max_duration_for_grasp_calc

Definition at line 135 of file calc_grasppoints_action_server.cpp.

ros::NodeHandle CCalc_Grasppoints::nh_
protected

Definition at line 111 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::nr_features_without_shaf

Definition at line 162 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::nr_roll_top_overall

Definition at line 148 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::nr_tilt_top_overall

Definition at line 149 of file calc_grasppoints_action_server.cpp.

string CCalc_Grasppoints::outputpath_full

Definition at line 139 of file calc_grasppoints_action_server.cpp.

ros::Subscriber CCalc_Grasppoints::pc_sub

Definition at line 122 of file calc_grasppoints_action_server.cpp.

bool CCalc_Grasppoints::point_inside_box_grid[ROLL_MAX_DEGREE/ROLL_STEPS_DEGREE][TILT_STEPS][HEIGHT][WIDTH]

Definition at line 138 of file calc_grasppoints_action_server.cpp.

bool CCalc_Grasppoints::print_heights_bool

Definition at line 155 of file calc_grasppoints_action_server.cpp.

ros::Publisher CCalc_Grasppoints::pubGraspPoints

Definition at line 125 of file calc_grasppoints_action_server.cpp.

ros::Publisher CCalc_Grasppoints::pubGraspPointsEval

Definition at line 126 of file calc_grasppoints_action_server.cpp.

ros::Publisher CCalc_Grasppoints::pubInputPCROS

Definition at line 123 of file calc_grasppoints_action_server.cpp.

ros::Publisher CCalc_Grasppoints::pubTransformedPCROS

Definition at line 124 of file calc_grasppoints_action_server.cpp.

tf::Quaternion CCalc_Grasppoints::quat_tf_to_tf_help

Definition at line 158 of file calc_grasppoints_action_server.cpp.

string CCalc_Grasppoints::range_file_path

Definition at line 160 of file calc_grasppoints_action_server.cpp.

haf_grasping::CalcGraspPointsServerResult CCalc_Grasppoints::result_
protected

Definition at line 117 of file calc_grasppoints_action_server.cpp.

bool CCalc_Grasppoints::return_only_best_gp

Definition at line 140 of file calc_grasppoints_action_server.cpp.

string CCalc_Grasppoints::svmmodel_file_path

Definition at line 161 of file calc_grasppoints_action_server.cpp.

tf::TransformListener CCalc_Grasppoints::tf_listener

Definition at line 153 of file calc_grasppoints_action_server.cpp.

int CCalc_Grasppoints::topval_gp_overall

Definition at line 150 of file calc_grasppoints_action_server.cpp.

float CCalc_Grasppoints::trans_z_after_pc_transform

Definition at line 157 of file calc_grasppoints_action_server.cpp.

ros::Publisher CCalc_Grasppoints::vis_pub

Definition at line 127 of file calc_grasppoints_action_server.cpp.

ros::Publisher CCalc_Grasppoints::vis_pub_ma

Definition at line 128 of file calc_grasppoints_action_server.cpp.

ros::Publisher CCalc_Grasppoints::vis_pub_ma_params

Definition at line 129 of file calc_grasppoints_action_server.cpp.

bool CCalc_Grasppoints::visualization

Definition at line 154 of file calc_grasppoints_action_server.cpp.


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


haf_grasping
Author(s): David Fischinger
autogenerated on Mon Jun 10 2019 13:28:43