Definition at line 695 of file motion_graphcut.cpp.
MGCNode::MGCNode | ( | ros::NodeHandle & | n | ) | [inline] |
Definition at line 698 of file motion_graphcut.cpp.
cv::Mat MGCNode::downSample | ( | cv::Mat | data_in, |
int | scales | ||
) | [inline] |
Definition at line 1652 of file motion_graphcut.cpp.
void MGCNode::drawTablePlaneOnImage | ( | XYZPointCloud & | plane, |
PoseStamped | cent | ||
) | [inline] |
Definition at line 1618 of file motion_graphcut.cpp.
PushPose::Response MGCNode::findPushPose | ( | cv::Mat | visual_frame, |
cv::Mat | depth_frame, | ||
XYZPointCloud & | cloud, | ||
bool | use_guided | ||
) | [inline] |
Definition at line 1003 of file motion_graphcut.cpp.
PoseStamped MGCNode::findRandomPushPose | ( | XYZPointCloud & | input_cloud | ) | [inline] |
Definition at line 1719 of file motion_graphcut.cpp.
bool MGCNode::getLineValues | ( | cv::Point | p1, |
cv::Point | p2, | ||
std::vector< cv::Point > & | line, | ||
cv::Size | frame_size, | ||
int & | min_x, | ||
int & | max_x, | ||
int & | min_y, | ||
int & | max_y | ||
) | [inline] |
Definition at line 1358 of file motion_graphcut.cpp.
XYZPointCloud MGCNode::getMaskedPointCloud | ( | XYZPointCloud & | input_cloud, |
cv::Mat & | mask_in | ||
) | [inline] |
Definition at line 1770 of file motion_graphcut.cpp.
bool MGCNode::getPushPose | ( | PushPose::Request & | req, |
PushPose::Response & | res | ||
) | [inline] |
Definition at line 961 of file motion_graphcut.cpp.
PoseStamped MGCNode::getPushVector | ( | ) | [inline] |
Definition at line 976 of file motion_graphcut.cpp.
cv::Mat MGCNode::getTableHeightDistances | ( | ) | [inline] |
Definition at line 1676 of file motion_graphcut.cpp.
bool MGCNode::getTableLocation | ( | LocateTable::Request & | req, |
LocateTable::Response & | res | ||
) | [inline] |
Definition at line 936 of file motion_graphcut.cpp.
PoseStamped MGCNode::getTablePlane | ( | XYZPointCloud & | cloud | ) | [inline] |
Definition at line 1702 of file motion_graphcut.cpp.
void MGCNode::initTracker | ( | ) | [inline] |
Definition at line 1056 of file motion_graphcut.cpp.
ArmModel MGCNode::projectArmPoses | ( | std_msgs::Header | img_header, |
cv::Size | frame_size, | ||
int & | min_x, | ||
int & | max_x, | ||
int & | min_y, | ||
int & | max_y | ||
) | [inline] |
Definition at line 1452 of file motion_graphcut.cpp.
cv::Point MGCNode::projectJointOriginIntoImage | ( | std_msgs::Header | img_header, |
std::string | joint_name | ||
) | [inline] |
Definition at line 1563 of file motion_graphcut.cpp.
cv::Point MGCNode::projectPointIntoImage | ( | PointStamped | cur_point, |
std::string | target_frame | ||
) | [inline] |
Definition at line 1318 of file motion_graphcut.cpp.
cv::Point MGCNode::projectPointIntoImage | ( | PoseStamped | cur_pose, |
std::string | target_frame | ||
) | [inline] |
Definition at line 1349 of file motion_graphcut.cpp.
void MGCNode::sensorCallback | ( | const sensor_msgs::ImageConstPtr & | img_msg, |
const sensor_msgs::ImageConstPtr & | depth_msg, | ||
const sensor_msgs::PointCloud2ConstPtr & | cloud_msg | ||
) | [inline] |
Definition at line 829 of file motion_graphcut.cpp.
void MGCNode::spin | ( | ) | [inline] |
Executive control function for launching the node.
Definition at line 1798 of file motion_graphcut.cpp.
void MGCNode::startTracker | ( | ) | [inline] |
Definition at line 1062 of file motion_graphcut.cpp.
void MGCNode::stopTracker | ( | ) | [inline] |
Definition at line 1068 of file motion_graphcut.cpp.
void MGCNode::trackerGoalCallback | ( | const tabletop_pushing::ObjectSingulationGoalConstPtr & | goal | ) | [inline] |
Definition at line 1024 of file motion_graphcut.cpp.
void MGCNode::updateTracks | ( | cv::Mat | color_frame, |
cv::Mat & | depth_frame, | ||
cv::Mat & | prev_color_frame, | ||
cv::Mat & | prev_depth_frame, | ||
XYZPointCloud & | cloud | ||
) | [inline] |
Definition at line 1074 of file motion_graphcut.cpp.
cv::Mat MGCNode::upSample | ( | cv::Mat | data_in, |
int | scales | ||
) | [inline] |
Definition at line 1663 of file motion_graphcut.cpp.
image_transport::Publisher MGCNode::arm_img_pub_ [protected] |
Definition at line 1817 of file motion_graphcut.cpp.
std::deque<cv::Mat> MGCNode::arm_mask_hist_ [protected] |
Definition at line 1833 of file motion_graphcut.cpp.
image_transport::Publisher MGCNode::arm_mask_pub_ [protected] |
Definition at line 1818 of file motion_graphcut.cpp.
bool MGCNode::auto_flow_cluster_ [protected] |
Definition at line 1872 of file motion_graphcut.cpp.
bool MGCNode::autorun_pcl_segmentation_ [protected] |
Definition at line 1871 of file motion_graphcut.cpp.
std::string MGCNode::base_output_path_ [protected] |
Definition at line 1868 of file motion_graphcut.cpp.
double MGCNode::below_table_z_ [protected] |
Definition at line 1860 of file motion_graphcut.cpp.
sensor_msgs::CvBridge MGCNode::bridge_ [protected] |
Definition at line 1821 of file motion_graphcut.cpp.
sensor_msgs::CameraInfo MGCNode::cam_info_ [protected] |
Definition at line 1814 of file motion_graphcut.cpp.
std::string MGCNode::cam_info_topic_ [protected] |
Definition at line 1866 of file motion_graphcut.cpp.
message_filters::Subscriber<sensor_msgs::PointCloud2> MGCNode::cloud_sub_ [protected] |
Definition at line 1811 of file motion_graphcut.cpp.
std::deque<cv::Mat> MGCNode::color_frame_hist_ [protected] |
Definition at line 1835 of file motion_graphcut.cpp.
int MGCNode::crop_max_x_ [protected] |
Definition at line 1846 of file motion_graphcut.cpp.
int MGCNode::crop_max_y_ [protected] |
Definition at line 1848 of file motion_graphcut.cpp.
int MGCNode::crop_min_x_ [protected] |
Definition at line 1845 of file motion_graphcut.cpp.
int MGCNode::crop_min_y_ [protected] |
Definition at line 1847 of file motion_graphcut.cpp.
std_msgs::Header MGCNode::cur_camera_header_ [protected] |
Definition at line 1839 of file motion_graphcut.cpp.
cv::Mat MGCNode::cur_color_frame_ [protected] |
Definition at line 1825 of file motion_graphcut.cpp.
cv::Mat MGCNode::cur_depth_frame_ [protected] |
Definition at line 1826 of file motion_graphcut.cpp.
XYZPointCloud MGCNode::cur_point_cloud_ [protected] |
Definition at line 1841 of file motion_graphcut.cpp.
ProtoObjects MGCNode::cur_proto_objs_ [protected] |
Definition at line 1875 of file motion_graphcut.cpp.
cv::Mat MGCNode::cur_workspace_mask_ [protected] |
Definition at line 1827 of file motion_graphcut.cpp.
std::deque<cv::Mat> MGCNode::depth_frame_hist_ [protected] |
Definition at line 1836 of file motion_graphcut.cpp.
message_filters::Subscriber<sensor_msgs::Image> MGCNode::depth_sub_ [protected] |
Definition at line 1810 of file motion_graphcut.cpp.
int MGCNode::display_wait_ms_ [protected] |
Definition at line 1849 of file motion_graphcut.cpp.
std::deque<cv::Mat> MGCNode::flow_u_hist_ [protected] |
Definition at line 1837 of file motion_graphcut.cpp.
std::deque<cv::Mat> MGCNode::flow_v_hist_ [protected] |
Definition at line 1838 of file motion_graphcut.cpp.
bool MGCNode::have_depth_data_ [protected] |
Definition at line 1844 of file motion_graphcut.cpp.
int MGCNode::image_hist_size_ [protected] |
Definition at line 1869 of file motion_graphcut.cpp.
message_filters::Subscriber<sensor_msgs::Image> MGCNode::image_sub_ [protected] |
Definition at line 1809 of file motion_graphcut.cpp.
image_transport::ImageTransport MGCNode::it_ [protected] |
Definition at line 1813 of file motion_graphcut.cpp.
double MGCNode::max_pushing_x_ [protected] |
Definition at line 1857 of file motion_graphcut.cpp.
double MGCNode::max_pushing_y_ [protected] |
Definition at line 1859 of file motion_graphcut.cpp.
double MGCNode::max_workspace_x_ [protected] |
Definition at line 1851 of file motion_graphcut.cpp.
double MGCNode::max_workspace_y_ [protected] |
Definition at line 1853 of file motion_graphcut.cpp.
double MGCNode::max_workspace_z_ [protected] |
Definition at line 1855 of file motion_graphcut.cpp.
double MGCNode::min_pushing_x_ [protected] |
Definition at line 1856 of file motion_graphcut.cpp.
double MGCNode::min_pushing_y_ [protected] |
Definition at line 1858 of file motion_graphcut.cpp.
double MGCNode::min_workspace_x_ [protected] |
Definition at line 1850 of file motion_graphcut.cpp.
double MGCNode::min_workspace_y_ [protected] |
Definition at line 1852 of file motion_graphcut.cpp.
double MGCNode::min_workspace_z_ [protected] |
Definition at line 1854 of file motion_graphcut.cpp.
image_transport::Publisher MGCNode::motion_img_pub_ [protected] |
Definition at line 1815 of file motion_graphcut.cpp.
std::deque<cv::Mat> MGCNode::motion_mask_hist_ [protected] |
Definition at line 1832 of file motion_graphcut.cpp.
image_transport::Publisher MGCNode::motion_mask_pub_ [protected] |
Definition at line 1816 of file motion_graphcut.cpp.
ros::NodeHandle MGCNode::n_ [protected] |
Definition at line 1807 of file motion_graphcut.cpp.
ros::NodeHandle MGCNode::n_private_ [protected] |
Definition at line 1808 of file motion_graphcut.cpp.
double MGCNode::norm_est_radius_ [protected] |
Definition at line 1870 of file motion_graphcut.cpp.
int MGCNode::num_downsamples_ [protected] |
Definition at line 1861 of file motion_graphcut.cpp.
ObjectSingulation MGCNode::os_ [protected] |
Definition at line 1843 of file motion_graphcut.cpp.
PointCloudSegmentation MGCNode::pcl_segmenter_ [protected] |
Definition at line 1842 of file motion_graphcut.cpp.
std_msgs::Header MGCNode::prev_camera_header_ [protected] |
Definition at line 1840 of file motion_graphcut.cpp.
cv::Mat MGCNode::prev_color_frame_ [protected] |
Definition at line 1828 of file motion_graphcut.cpp.
cv::Mat MGCNode::prev_depth_frame_ [protected] |
Definition at line 1829 of file motion_graphcut.cpp.
ProtoObjects MGCNode::prev_proto_objs_ [protected] |
Definition at line 1874 of file motion_graphcut.cpp.
cv::Mat MGCNode::prev_seg_mask_ [protected] |
Definition at line 1831 of file motion_graphcut.cpp.
cv::Mat MGCNode::prev_workspace_mask_ [protected] |
Definition at line 1830 of file motion_graphcut.cpp.
ros::ServiceServer MGCNode::push_pose_server_ [protected] |
Definition at line 1823 of file motion_graphcut.cpp.
bool MGCNode::segmenting_moving_stuff_ [protected] |
Definition at line 1873 of file motion_graphcut.cpp.
actionlib::SimpleActionServer<tabletop_pushing:: ObjectSingulationAction> MGCNode::singulation_server_ [protected] |
Definition at line 1820 of file motion_graphcut.cpp.
message_filters::Synchronizer<MySyncPolicy> MGCNode::sync_ [protected] |
Definition at line 1812 of file motion_graphcut.cpp.
PoseStamped MGCNode::table_centroid_ [protected] |
Definition at line 1863 of file motion_graphcut.cpp.
ros::ServiceServer MGCNode::table_location_server_ [protected] |
Definition at line 1824 of file motion_graphcut.cpp.
tf::TransformListener MGCNode::tf_ [protected] |
Definition at line 1822 of file motion_graphcut.cpp.
int MGCNode::tracker_count_ [protected] |
Definition at line 1867 of file motion_graphcut.cpp.
bool MGCNode::tracker_initialized_ [protected] |
Definition at line 1865 of file motion_graphcut.cpp.
bool MGCNode::tracking_ [protected] |
Definition at line 1864 of file motion_graphcut.cpp.
std::string MGCNode::workspace_frame_ [protected] |
Definition at line 1862 of file motion_graphcut.cpp.
std::deque<cv::Mat> MGCNode::workspace_mask_hist_ [protected] |
Definition at line 1834 of file motion_graphcut.cpp.