Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
ObjectSingulation Class Reference

List of all members.

Public Member Functions

PushVector findRandomPushPose (XYZPointCloud &input_cloud)
PushVector getPushVector (bool no_push_calc, cv::Mat &color_img, cv::Mat &depth_img, XYZPointCloud &cloud, cv::Mat &workspace_mask, bool use_guided=true)
bool initialize (cv::Mat &color_img, cv::Mat &depth_img, XYZPointCloud &cloud, cv::Mat &workspace_mask)
bool isInitialized () const
 ObjectSingulation (shared_ptr< PointCloudSegmentation > pcl_segmenter)
void unInitialize ()

Public Attributes

double bad_icp_score_limit_
std::string base_output_path_
double boundary_ransac_thresh_
double depth_edge_weight_
double depth_edge_weight_thresh_
double edge_weight_thresh_
bool force_remain_singulated_
int histogram_bin_height_
int histogram_bin_width_
double max_push_angle_
double max_push_dist_
double max_pushing_x_
double max_pushing_y_
double max_table_x_
double max_table_y_
int min_boundary_length_
int min_cluster_size_
int min_edge_length_
double min_push_angle_
double min_push_dist_
double min_pushing_x_
double min_pushing_y_
double min_table_x_
double min_table_y_
int num_angle_bins_
int num_downsamples_
ros::Publisher obj_push_pub_
int per_object_rand_push_count_
double push_collision_intersection_thresh_
double push_dist_inflation_
int push_guess_limit_
double start_collision_thresh_
bool threshold_edges_
int upscale_
bool use_displays_
bool use_unguided_icp_
std::string workspace_frame_
bool write_to_disk_

Protected Member Functions

void associate3DBoundaries (std::vector< Boundary > &boundaries, ProtoObjects &objs, cv::Mat &obj_lbl_img)
ProtoObjects calcProtoObjects (XYZPointCloud &cloud, bool use_guided=true)
std::vector< unsigned int > checkSingulated (std::vector< Boundary > &boundaries, ProtoObjects &objs)
PushVector determinePushPose (cv::Mat &boundary_img, ProtoObjects &objs, std::vector< Boundary > &boundaries, XYZPointCloud &cloud)
PushVector determinePushVector (std::vector< Boundary > &boundaries, ProtoObjects &objs, cv::Mat &obj_lbl_img)
geometry_msgs::Point determineStartPoint (XYZPointCloud &pts, PushOpt &opt)
geometry_msgs::Point determineStartPoint (XYZPointCloud &obj_cloud, Eigen::Vector4f centroid, Eigen::Vector3f push_unit_vec, double &push_angle, double &push_dist)
void displayBoundaryOrientation (cv::Mat &obj_img, Boundary &boundary, std::string title)
void displayPushVector (cv::Mat &lbl_img, Boundary &boundary, PushVector &push, PushOpt &split)
void displayPushVector (ProtoObject &obj, PushVector &push, Eigen::Vector3f push_unit_vec)
void draw3DBoundaries (std::vector< Boundary > boundaries, cv::Mat &img, unsigned int objs_size, bool is_obj_img=false)
void drawObjectHists (cv::Mat &img, ProtoObjects &objs, int highlight_bin, int highlight_obj, bool is_obj_img=false)
void drawObjectTransformAxises (cv::Mat &obj_img, ProtoObjects &objs)
void drawSemicircleHist (std::vector< int > &hist, cv::Mat &disp_img, const cv::Point center, int w, int h, const cv::Scalar line_color, const cv::Scalar fill_color, const cv::Scalar highlight_color, const float start_rot, int highlight_bin=-1)
void drawUnguidedHist (std::vector< int > &hist, cv::Mat &disp_img, const cv::Point center, int w, int h, const cv::Scalar line_color, const cv::Scalar fill_color, const cv::Scalar highlight_color, const float start_rot, int highlight_bin=-1)
void drawUnguidedHists (cv::Mat &img, ProtoObjects &objs, int highlight_obj)
void evaluatePushOpts (PushOpts &split_opts, Boundary &boundary, ProtoObjects &objs)
PushVector findRandomPushVector (ProtoObjects &objs, XYZPointCloud &cloud, cv::Mat &color_img)
PushOpts generatePushOpts (Boundary &boundary)
void get3DBoundaries (std::vector< Boundary > &boundaries, XYZPointCloud &cloud)
void get3DBoundary (Boundary &b, XYZPointCloud &cloud)
double getBoundaryLengthXYMeters (Boundary &b)
int getNextID ()
std::vector< BoundarygetObjectBoundaryStrengths (cv::Mat &color_img, cv::Mat &depth_img, cv::Mat &workspace_mask, cv::Mat &combined_edges)
float getObjFrameAngleFromWorldFrame (float theta, Eigen::Matrix4f &t)
float getObjFrameBoundaryOrientation (Boundary &b, Eigen::Matrix4f &t)
Eigen::Vector3f getRANSACXYVector (Boundary &b)
Eigen::Vector3f getRANSACXYVector (Boundary &b, Eigen::Vector3f &l_pt)
void highlightBoundaryOrientation (cv::Mat &obj_img, Boundary &boundary, std::string title)
void matchMoved (ProtoObjects &cur_objs, ProtoObjects &prev_objs, std::vector< bool > matched, bool split, bool merged, bool use_guided)
std::vector< boolmatchUnmoved (ProtoObjects &cur_objs, ProtoObjects &prev_objs)
bool pushCollidesWithObject (PushOpt &po, ProtoObjects &objs)
int pushCollidesWithWhat (PushOpt &po, ProtoObjects &objs)
bool pushLeavesTable (PushOpt &po)
bool pushLeavesWorkspace (PushOpt &po, ProtoObject &obj)
int quantizeAngle (float angle)
ProtoObjects splitObject3D (Boundary &boundary, ProtoObject &to_split, bool update_boundary=false)
ProtoObjects splitObject3D (Eigen::Vector4f &hessian, ProtoObject &to_split)
Eigen::Vector4f splitPlaneVertical (Boundary &b, bool update_boundary=false, bool use_boundary=false)
bool startCollidesWithObject (PushOpt &po, ProtoObjects &objs)
bool startLeavesWorkspace (PushOpt &po)
float subHalfPiAngle (float angle)
void updateMovedObjs (ProtoObjects &cur_objs, ProtoObjects &prev_objs, bool use_guided=true)

Protected Attributes

int callback_count_
ProtoObjects cur_proto_objs_
XYZPointCloud cur_table_cloud_
cv::Mat dx_kernel_
cv::Mat dy_kernel_
cv::Mat g_kernel_
bool initialized_
bool merged_
int next_id_
shared_ptr
< PointCloudSegmentation
pcl_segmenter_
XYZPointCloud prev_cloud_down_
XYZPointCloud prev_objs_down_
ProtoObjects prev_proto_objs_
PushVector prev_push_vector_
bool split_

Detailed Description

Definition at line 293 of file object_singulation_node.cpp.


Constructor & Destructor Documentation

ObjectSingulation::ObjectSingulation ( shared_ptr< PointCloudSegmentation pcl_segmenter) [inline]

Definition at line 296 of file object_singulation_node.cpp.


Member Function Documentation

void ObjectSingulation::associate3DBoundaries ( std::vector< Boundary > &  boundaries,
ProtoObjects &  objs,
cv::Mat &  obj_lbl_img 
) [inline, protected]

Definition at line 1197 of file object_singulation_node.cpp.

ProtoObjects ObjectSingulation::calcProtoObjects ( XYZPointCloud cloud,
bool  use_guided = true 
) [inline, protected]

Find the current object estimates in the current cloud, dependent on the previous cloud

Parameters:
cloudThe cloud to find the objects in.
Returns:
The current estimate of the objects

Definition at line 477 of file object_singulation_node.cpp.

std::vector<unsigned int> ObjectSingulation::checkSingulated ( std::vector< Boundary > &  boundaries,
ProtoObjects &  objs 
) [inline, protected]

Definition at line 1371 of file object_singulation_node.cpp.

PushVector ObjectSingulation::determinePushPose ( cv::Mat &  boundary_img,
ProtoObjects &  objs,
std::vector< Boundary > &  boundaries,
XYZPointCloud cloud 
) [inline, protected]

Determine what push to make given the current object and boundary estimates

Parameters:
boundary_imgThe image of the estimated boundary strengths
objsThe estimated set of proto objects
Returns:
A push for the robot to make to singulate objects

Definition at line 800 of file object_singulation_node.cpp.

PushVector ObjectSingulation::determinePushVector ( std::vector< Boundary > &  boundaries,
ProtoObjects &  objs,
cv::Mat &  obj_lbl_img 
) [inline, protected]

Definition at line 837 of file object_singulation_node.cpp.

Definition at line 1701 of file object_singulation_node.cpp.

geometry_msgs::Point ObjectSingulation::determineStartPoint ( XYZPointCloud obj_cloud,
Eigen::Vector4f  centroid,
Eigen::Vector3f  push_unit_vec,
double &  push_angle,
double &  push_dist 
) [inline, protected]

Definition at line 1751 of file object_singulation_node.cpp.

void ObjectSingulation::displayBoundaryOrientation ( cv::Mat &  obj_img,
Boundary boundary,
std::string  title 
) [inline, protected]

Definition at line 1857 of file object_singulation_node.cpp.

void ObjectSingulation::displayPushVector ( cv::Mat &  lbl_img,
Boundary boundary,
PushVector push,
PushOpt split 
) [inline, protected]

Definition at line 1501 of file object_singulation_node.cpp.

void ObjectSingulation::displayPushVector ( ProtoObject obj,
PushVector push,
Eigen::Vector3f  push_unit_vec 
) [inline, protected]

Definition at line 1556 of file object_singulation_node.cpp.

void ObjectSingulation::draw3DBoundaries ( std::vector< Boundary boundaries,
cv::Mat &  img,
unsigned int  objs_size,
bool  is_obj_img = false 
) [inline, protected]

Definition at line 1966 of file object_singulation_node.cpp.

void ObjectSingulation::drawObjectHists ( cv::Mat &  img,
ProtoObjects &  objs,
int  highlight_bin,
int  highlight_obj,
bool  is_obj_img = false 
) [inline, protected]

Definition at line 2155 of file object_singulation_node.cpp.

void ObjectSingulation::drawObjectTransformAxises ( cv::Mat &  obj_img,
ProtoObjects &  objs 
) [inline, protected]

Definition at line 2054 of file object_singulation_node.cpp.

void ObjectSingulation::drawSemicircleHist ( std::vector< int > &  hist,
cv::Mat &  disp_img,
const cv::Point  center,
int  w,
int  h,
const cv::Scalar  line_color,
const cv::Scalar  fill_color,
const cv::Scalar  highlight_color,
const float  start_rot,
int  highlight_bin = -1 
) [inline, protected]

Definition at line 2296 of file object_singulation_node.cpp.

void ObjectSingulation::drawUnguidedHist ( std::vector< int > &  hist,
cv::Mat &  disp_img,
const cv::Point  center,
int  w,
int  h,
const cv::Scalar  line_color,
const cv::Scalar  fill_color,
const cv::Scalar  highlight_color,
const float  start_rot,
int  highlight_bin = -1 
) [inline, protected]

Definition at line 2417 of file object_singulation_node.cpp.

void ObjectSingulation::drawUnguidedHists ( cv::Mat &  img,
ProtoObjects &  objs,
int  highlight_obj 
) [inline, protected]

Definition at line 2241 of file object_singulation_node.cpp.

void ObjectSingulation::evaluatePushOpts ( PushOpts split_opts,
Boundary boundary,
ProtoObjects &  objs 
) [inline, protected]

Definition at line 1470 of file object_singulation_node.cpp.

Randomly choose an object to push that is within reach. Chooses a random direction to push from.

Parameters:
input_cloudPoint cloud containing the tabletop scene to push in
Returns:
The location and direction to push.

Definition at line 414 of file object_singulation_node.cpp.

PushVector ObjectSingulation::findRandomPushVector ( ProtoObjects &  objs,
XYZPointCloud cloud,
cv::Mat &  color_img 
) [inline, protected]

Randomly choose an object to push that is within reach. Chooses a random direction to push from.

Parameters:
input_cloudPoint cloud containing the tabletop scene to push in
Returns:
The location and direction to push.

Definition at line 960 of file object_singulation_node.cpp.

PushOpts ObjectSingulation::generatePushOpts ( Boundary boundary) [inline, protected]

Definition at line 1417 of file object_singulation_node.cpp.

void ObjectSingulation::get3DBoundaries ( std::vector< Boundary > &  boundaries,
XYZPointCloud cloud 
) [inline, protected]

Definition at line 1174 of file object_singulation_node.cpp.

void ObjectSingulation::get3DBoundary ( Boundary b,
XYZPointCloud cloud 
) [inline, protected]

Definition at line 1182 of file object_singulation_node.cpp.

double ObjectSingulation::getBoundaryLengthXYMeters ( Boundary b) [inline, protected]

Definition at line 1683 of file object_singulation_node.cpp.

int ObjectSingulation::getNextID ( ) [inline, protected]

Definition at line 2149 of file object_singulation_node.cpp.

std::vector<Boundary> ObjectSingulation::getObjectBoundaryStrengths ( cv::Mat &  color_img,
cv::Mat &  depth_img,
cv::Mat &  workspace_mask,
cv::Mat &  combined_edges 
) [inline, protected]

Determine the strength of object boundaries in an RGB-D image

Parameters:
color_imgThe color image
depth_imgThe depth image
workspace_maskA mask depicting locations of interest
combined_edgesEdge image
Returns:
A vector of the detected Boundary objects

Definition at line 1088 of file object_singulation_node.cpp.

float ObjectSingulation::getObjFrameAngleFromWorldFrame ( float  theta,
Eigen::Matrix4f &  t 
) [inline, protected]

Definition at line 1283 of file object_singulation_node.cpp.

float ObjectSingulation::getObjFrameBoundaryOrientation ( Boundary b,
Eigen::Matrix4f &  t 
) [inline, protected]

Definition at line 1274 of file object_singulation_node.cpp.

PushVector ObjectSingulation::getPushVector ( bool  no_push_calc,
cv::Mat &  color_img,
cv::Mat &  depth_img,
XYZPointCloud cloud,
cv::Mat &  workspace_mask,
bool  use_guided = true 
) [inline]

Determine the pushing pose and direction to verify separate objects

Parameters:
color_imgThe current color image
depth_imgThe current depth image
cloudThe current point cloud
workspace_maskThe current workspace mask
Returns:
The location and orientation to push

Definition at line 334 of file object_singulation_node.cpp.

Eigen::Vector3f ObjectSingulation::getRANSACXYVector ( Boundary b) [inline, protected]

Definition at line 1314 of file object_singulation_node.cpp.

Eigen::Vector3f ObjectSingulation::getRANSACXYVector ( Boundary b,
Eigen::Vector3f &  l_pt 
) [inline, protected]

Definition at line 1320 of file object_singulation_node.cpp.

void ObjectSingulation::highlightBoundaryOrientation ( cv::Mat &  obj_img,
Boundary boundary,
std::string  title 
) [inline, protected]

Definition at line 1927 of file object_singulation_node.cpp.

bool ObjectSingulation::initialize ( cv::Mat &  color_img,
cv::Mat &  depth_img,
XYZPointCloud cloud,
cv::Mat &  workspace_mask 
) [inline]

Definition at line 306 of file object_singulation_node.cpp.

Definition at line 2532 of file object_singulation_node.cpp.

void ObjectSingulation::matchMoved ( ProtoObjects &  cur_objs,
ProtoObjects &  prev_objs,
std::vector< bool matched,
bool  split,
bool  merged,
bool  use_guided 
) [inline, protected]

Definition at line 696 of file object_singulation_node.cpp.

std::vector<bool> ObjectSingulation::matchUnmoved ( ProtoObjects &  cur_objs,
ProtoObjects &  prev_objs 
) [inline, protected]

Definition at line 654 of file object_singulation_node.cpp.

bool ObjectSingulation::pushCollidesWithObject ( PushOpt po,
ProtoObjects &  objs 
) [inline, protected]

Definition at line 1600 of file object_singulation_node.cpp.

int ObjectSingulation::pushCollidesWithWhat ( PushOpt po,
ProtoObjects &  objs 
) [inline, protected]

Definition at line 1628 of file object_singulation_node.cpp.

bool ObjectSingulation::pushLeavesTable ( PushOpt po) [inline, protected]

Definition at line 1676 of file object_singulation_node.cpp.

bool ObjectSingulation::pushLeavesWorkspace ( PushOpt po,
ProtoObject obj 
) [inline, protected]

Definition at line 1653 of file object_singulation_node.cpp.

int ObjectSingulation::quantizeAngle ( float  angle) [inline, protected]

Definition at line 1293 of file object_singulation_node.cpp.

ProtoObjects ObjectSingulation::splitObject3D ( Boundary boundary,
ProtoObject to_split,
bool  update_boundary = false 
) [inline, protected]

Definition at line 1810 of file object_singulation_node.cpp.

ProtoObjects ObjectSingulation::splitObject3D ( Eigen::Vector4f &  hessian,
ProtoObject to_split 
) [inline, protected]

Definition at line 1819 of file object_singulation_node.cpp.

Eigen::Vector4f ObjectSingulation::splitPlaneVertical ( Boundary b,
bool  update_boundary = false,
bool  use_boundary = false 
) [inline, protected]

Definition at line 1349 of file object_singulation_node.cpp.

bool ObjectSingulation::startCollidesWithObject ( PushOpt po,
ProtoObjects &  objs 
) [inline, protected]

Definition at line 1615 of file object_singulation_node.cpp.

bool ObjectSingulation::startLeavesWorkspace ( PushOpt po) [inline, protected]

Definition at line 1668 of file object_singulation_node.cpp.

float ObjectSingulation::subHalfPiAngle ( float  angle) [inline, protected]

Definition at line 1300 of file object_singulation_node.cpp.

Definition at line 2534 of file object_singulation_node.cpp.

void ObjectSingulation::updateMovedObjs ( ProtoObjects &  cur_objs,
ProtoObjects &  prev_objs,
bool  use_guided = true 
) [inline, protected]

Method to update the IDs and of moved proto objects

Parameters:
cur_objsThe current set of proto objects
prev_objsThe previous set of proto objects
moved_objsMoved proto objects
Returns:

Definition at line 557 of file object_singulation_node.cpp.


Member Data Documentation

Definition at line 2590 of file object_singulation_node.cpp.

Definition at line 2584 of file object_singulation_node.cpp.

Definition at line 2575 of file object_singulation_node.cpp.

Definition at line 2549 of file object_singulation_node.cpp.

ProtoObjects ObjectSingulation::cur_proto_objs_ [protected]

Definition at line 2547 of file object_singulation_node.cpp.

Definition at line 2554 of file object_singulation_node.cpp.

Definition at line 2570 of file object_singulation_node.cpp.

Definition at line 2572 of file object_singulation_node.cpp.

cv::Mat ObjectSingulation::dx_kernel_ [protected]

Definition at line 2540 of file object_singulation_node.cpp.

cv::Mat ObjectSingulation::dy_kernel_ [protected]

Definition at line 2541 of file object_singulation_node.cpp.

Definition at line 2571 of file object_singulation_node.cpp.

Definition at line 2591 of file object_singulation_node.cpp.

cv::Mat ObjectSingulation::g_kernel_ [protected]

Definition at line 2542 of file object_singulation_node.cpp.

Definition at line 2586 of file object_singulation_node.cpp.

Definition at line 2585 of file object_singulation_node.cpp.

Definition at line 2551 of file object_singulation_node.cpp.

Definition at line 2573 of file object_singulation_node.cpp.

Definition at line 2588 of file object_singulation_node.cpp.

Definition at line 2558 of file object_singulation_node.cpp.

Definition at line 2560 of file object_singulation_node.cpp.

Definition at line 2562 of file object_singulation_node.cpp.

Definition at line 2564 of file object_singulation_node.cpp.

Definition at line 2552 of file object_singulation_node.cpp.

Definition at line 2583 of file object_singulation_node.cpp.

Definition at line 2582 of file object_singulation_node.cpp.

Definition at line 2576 of file object_singulation_node.cpp.

Definition at line 2574 of file object_singulation_node.cpp.

Definition at line 2587 of file object_singulation_node.cpp.

Definition at line 2557 of file object_singulation_node.cpp.

Definition at line 2559 of file object_singulation_node.cpp.

Definition at line 2561 of file object_singulation_node.cpp.

Definition at line 2563 of file object_singulation_node.cpp.

int ObjectSingulation::next_id_ [protected]

Definition at line 2550 of file object_singulation_node.cpp.

Definition at line 2577 of file object_singulation_node.cpp.

Definition at line 2578 of file object_singulation_node.cpp.

Definition at line 2568 of file object_singulation_node.cpp.

Definition at line 2543 of file object_singulation_node.cpp.

Definition at line 2592 of file object_singulation_node.cpp.

Definition at line 2544 of file object_singulation_node.cpp.

Definition at line 2545 of file object_singulation_node.cpp.

ProtoObjects ObjectSingulation::prev_proto_objs_ [protected]

Definition at line 2546 of file object_singulation_node.cpp.

Definition at line 2548 of file object_singulation_node.cpp.

Definition at line 2565 of file object_singulation_node.cpp.

Definition at line 2589 of file object_singulation_node.cpp.

Definition at line 2594 of file object_singulation_node.cpp.

Definition at line 2553 of file object_singulation_node.cpp.

Definition at line 2566 of file object_singulation_node.cpp.

Definition at line 2569 of file object_singulation_node.cpp.

Definition at line 2579 of file object_singulation_node.cpp.

Definition at line 2580 of file object_singulation_node.cpp.

Definition at line 2593 of file object_singulation_node.cpp.

Definition at line 2567 of file object_singulation_node.cpp.

Definition at line 2581 of file object_singulation_node.cpp.


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


tabletop_pushing
Author(s): Tucker Hermans
autogenerated on Wed Nov 27 2013 11:59:45