Public Types | |
enum | SegLabels { MOVING, ARM, TABLE, BG } |
Public Member Functions | |
cv::Mat | convertFlowResultsToCvMat (GraphType *g, int R, int C) |
cv::Mat | convertFlowResultsToCvMat (GraphType *g, int R, int C, cv::Rect roi, cv::Size out_size) |
float | getArmFGScore (cv::Mat &color_frame, cv::Mat &depth_frame, int r, int c, std::vector< cv::Vec3f > &arm_stats, std::vector< cv::Vec3f > &hand_stats, ArmModel &arms, cv::Rect &roi) |
float | getEdgeWeight (cv::Vec3f c0, float d0, cv::Vec3f c1, float d1) |
float | getFlowFGScore (float magnitude) |
std::vector< cv::Vec3f > | getImagePointGaussian (cv::Mat &color_frame, std::vector< cv::Point > points, int min_x=0, int min_y=0) |
float | getTableScore (cv::Vec3f cur_c, float height_from_table) |
MotionGraphcut (double workspace_background_weight=1.0f, double min_weight=0.01, double magnitude_thresh=0.1, double flow_gain=0.3, int arm_grow_radius=2) | |
cv::Mat | operator() (cv::Mat &color_frame, cv::Mat &depth_frame, cv::Mat &u, cv::Mat &v, cv::Mat &workspace_mask, cv::Mat &table_heights, ArmModel arm_locs) |
cv::Mat | segmentRobotArm (cv::Mat &color_frame_in, cv::Mat &depth_frame_in, cv::Mat &workspace_mask_in, ArmModel &arms, int min_arm_x, int max_arm_x, int min_arm_y, int max_arm_y) |
void | setTableColorStats (cv::Mat &color_frame, std::vector< cv::Point > &pts) |
virtual | ~MotionGraphcut () |
Public Attributes | |
double | arm_alpha_ |
double | arm_beta_ |
double | arm_color_var_add_ |
double | arm_dist_var_ |
int | arm_grow_radius_ |
int | arm_search_radius_ |
double | flow_gain_ |
double | magnitude_thresh_ |
double | min_weight_ |
double | table_height_var_ |
std::vector< cv::Vec3f > | table_stats_ |
double | w_c_alpha_ |
double | w_c_beta_ |
double | w_c_gamma_ |
double | workspace_background_weight_ |
Definition at line 160 of file motion_graphcut.cpp.
Definition at line 670 of file motion_graphcut.cpp.
MotionGraphcut::MotionGraphcut | ( | double | workspace_background_weight = 1.0f , |
double | min_weight = 0.01 , |
||
double | magnitude_thresh = 0.1 , |
||
double | flow_gain = 0.3 , |
||
int | arm_grow_radius = 2 |
||
) | [inline] |
Definition at line 163 of file motion_graphcut.cpp.
virtual MotionGraphcut::~MotionGraphcut | ( | ) | [inline, virtual] |
Definition at line 172 of file motion_graphcut.cpp.
cv::Mat MotionGraphcut::convertFlowResultsToCvMat | ( | GraphType * | g, |
int | R, | ||
int | C | ||
) | [inline] |
Definition at line 631 of file motion_graphcut.cpp.
cv::Mat MotionGraphcut::convertFlowResultsToCvMat | ( | GraphType * | g, |
int | R, | ||
int | C, | ||
cv::Rect | roi, | ||
cv::Size | out_size | ||
) | [inline] |
Definition at line 646 of file motion_graphcut.cpp.
float MotionGraphcut::getArmFGScore | ( | cv::Mat & | color_frame, |
cv::Mat & | depth_frame, | ||
int | r, | ||
int | c, | ||
std::vector< cv::Vec3f > & | arm_stats, | ||
std::vector< cv::Vec3f > & | hand_stats, | ||
ArmModel & | arms, | ||
cv::Rect & | roi | ||
) | [inline] |
Definition at line 526 of file motion_graphcut.cpp.
float MotionGraphcut::getEdgeWeight | ( | cv::Vec3f | c0, |
float | d0, | ||
cv::Vec3f | c1, | ||
float | d1 | ||
) | [inline] |
Definition at line 661 of file motion_graphcut.cpp.
float MotionGraphcut::getFlowFGScore | ( | float | magnitude | ) | [inline] |
Definition at line 501 of file motion_graphcut.cpp.
std::vector<cv::Vec3f> MotionGraphcut::getImagePointGaussian | ( | cv::Mat & | color_frame, |
std::vector< cv::Point > | points, | ||
int | min_x = 0 , |
||
int | min_y = 0 |
||
) | [inline] |
Definition at line 559 of file motion_graphcut.cpp.
float MotionGraphcut::getTableScore | ( | cv::Vec3f | cur_c, |
float | height_from_table | ||
) | [inline] |
Definition at line 506 of file motion_graphcut.cpp.
cv::Mat MotionGraphcut::operator() | ( | cv::Mat & | color_frame, |
cv::Mat & | depth_frame, | ||
cv::Mat & | u, | ||
cv::Mat & | v, | ||
cv::Mat & | workspace_mask, | ||
cv::Mat & | table_heights, | ||
ArmModel | arm_locs | ||
) | [inline] |
Segment moving stuff from static stuff using graphcut
color_frame | The current color image to segment |
depth_frame | The current depth image to segment |
u | Flow dx/dt |
v | Flow dy/dt |
eigen_scores | Scores corresponding to texture at the point |
workspace_mask | Binary image where white is valid locations for things to be moving at |
arm_locs | Image locations of projected arm kinematics |
Definition at line 191 of file motion_graphcut.cpp.
cv::Mat MotionGraphcut::segmentRobotArm | ( | cv::Mat & | color_frame_in, |
cv::Mat & | depth_frame_in, | ||
cv::Mat & | workspace_mask_in, | ||
ArmModel & | arms, | ||
int | min_arm_x, | ||
int | max_arm_x, | ||
int | min_arm_y, | ||
int | max_arm_y | ||
) | [inline] |
Method to segment the arm from the rest of the stuff moving in the scene
color_frame | Current color frame |
depth_frame | Current depth frame |
moving_mask | Binary image representing where the moving stuff is |
workspace_mask | Binary image where white is valid locations for things to be moving at |
arms | Position of the arm projected into the image frame |
Definition at line 334 of file motion_graphcut.cpp.
void MotionGraphcut::setTableColorStats | ( | cv::Mat & | color_frame, |
std::vector< cv::Point > & | pts | ||
) | [inline] |
Definition at line 622 of file motion_graphcut.cpp.
double MotionGraphcut::arm_alpha_ |
Definition at line 688 of file motion_graphcut.cpp.
double MotionGraphcut::arm_beta_ |
Definition at line 689 of file motion_graphcut.cpp.
Definition at line 687 of file motion_graphcut.cpp.
Definition at line 686 of file motion_graphcut.cpp.
Definition at line 690 of file motion_graphcut.cpp.
Definition at line 691 of file motion_graphcut.cpp.
double MotionGraphcut::flow_gain_ |
Definition at line 684 of file motion_graphcut.cpp.
Definition at line 683 of file motion_graphcut.cpp.
double MotionGraphcut::min_weight_ |
Definition at line 679 of file motion_graphcut.cpp.
Definition at line 685 of file motion_graphcut.cpp.
std::vector<cv::Vec3f> MotionGraphcut::table_stats_ |
Definition at line 692 of file motion_graphcut.cpp.
double MotionGraphcut::w_c_alpha_ |
Definition at line 680 of file motion_graphcut.cpp.
double MotionGraphcut::w_c_beta_ |
Definition at line 681 of file motion_graphcut.cpp.
double MotionGraphcut::w_c_gamma_ |
Definition at line 682 of file motion_graphcut.cpp.
Definition at line 678 of file motion_graphcut.cpp.