Definition at line 2597 of file object_singulation_node.cpp.
ObjectSingulationNode::ObjectSingulationNode | ( | ros::NodeHandle & | n | ) | [inline] |
Definition at line 2600 of file object_singulation_node.cpp.
bool ObjectSingulationNode::getPushPose | ( | SingulationPush::Request & | req, |
SingulationPush::Response & | res | ||
) | [inline] |
Service request callback method to return a location and orientation for the robot to push.
req | The service request |
res | The service response |
Definition at line 2882 of file object_singulation_node.cpp.
PushVector ObjectSingulationNode::getPushPose | ( | bool | use_guided = true , |
bool | no_push_calc = false |
||
) | [inline] |
Wrapper method to call the push pose from the ObjectSingulation class
use_guided | find a random pose if false, otherwise calculate using the ObjectSingulation method |
Definition at line 2935 of file object_singulation_node.cpp.
bool ObjectSingulationNode::getTableLocation | ( | LocateTable::Request & | req, |
LocateTable::Response & | res | ||
) | [inline] |
ROS Service callback method for determining the location of a table in the scene
req | The service request |
res | The service response |
Definition at line 2951 of file object_singulation_node.cpp.
PoseStamped ObjectSingulationNode::getTablePlane | ( | XYZPointCloud & | cloud | ) | [inline] |
Calculate the location of the dominant plane (table) in a point cloud
cloud | The point cloud containing a table |
Definition at line 2983 of file object_singulation_node.cpp.
void ObjectSingulationNode::sensorCallback | ( | const sensor_msgs::ImageConstPtr & | img_msg, |
const sensor_msgs::ImageConstPtr & | depth_msg, | ||
const sensor_msgs::PointCloud2ConstPtr & | cloud_msg | ||
) | [inline] |
Definition at line 2737 of file object_singulation_node.cpp.
void ObjectSingulationNode::spin | ( | ) | [inline] |
Executive control function for launching the node.
Definition at line 3004 of file object_singulation_node.cpp.
bool ObjectSingulationNode::autorun_pcl_segmentation_ [protected] |
Definition at line 3057 of file object_singulation_node.cpp.
std::string ObjectSingulationNode::base_output_path_ [protected] |
Definition at line 3042 of file object_singulation_node.cpp.
sensor_msgs::CameraInfo ObjectSingulationNode::cam_info_ [protected] |
Definition at line 3019 of file object_singulation_node.cpp.
std::string ObjectSingulationNode::cam_info_topic_ [protected] |
Definition at line 3055 of file object_singulation_node.cpp.
bool ObjectSingulationNode::camera_initialized_ [protected] |
Definition at line 3054 of file object_singulation_node.cpp.
message_filters::Subscriber<sensor_msgs::PointCloud2> ObjectSingulationNode::cloud_sub_ [protected] |
Definition at line 3017 of file object_singulation_node.cpp.
int ObjectSingulationNode::crop_max_x_ [protected] |
Definition at line 3036 of file object_singulation_node.cpp.
int ObjectSingulationNode::crop_max_y_ [protected] |
Definition at line 3038 of file object_singulation_node.cpp.
int ObjectSingulationNode::crop_min_x_ [protected] |
Definition at line 3035 of file object_singulation_node.cpp.
int ObjectSingulationNode::crop_min_y_ [protected] |
Definition at line 3037 of file object_singulation_node.cpp.
Definition at line 3029 of file object_singulation_node.cpp.
cv::Mat ObjectSingulationNode::cur_color_frame_ [protected] |
Definition at line 3023 of file object_singulation_node.cpp.
cv::Mat ObjectSingulationNode::cur_depth_frame_ [protected] |
Definition at line 3024 of file object_singulation_node.cpp.
XYZPointCloud ObjectSingulationNode::cur_point_cloud_ [protected] |
Definition at line 3031 of file object_singulation_node.cpp.
cv::Mat ObjectSingulationNode::cur_workspace_mask_ [protected] |
Definition at line 3025 of file object_singulation_node.cpp.
message_filters::Subscriber<sensor_msgs::Image> ObjectSingulationNode::depth_sub_ [protected] |
Definition at line 3016 of file object_singulation_node.cpp.
int ObjectSingulationNode::display_wait_ms_ [protected] |
Definition at line 3039 of file object_singulation_node.cpp.
bool ObjectSingulationNode::have_depth_data_ [protected] |
Definition at line 3034 of file object_singulation_node.cpp.
message_filters::Subscriber<sensor_msgs::Image> ObjectSingulationNode::image_sub_ [protected] |
Definition at line 3015 of file object_singulation_node.cpp.
double ObjectSingulationNode::max_workspace_x_ [protected] |
Definition at line 3044 of file object_singulation_node.cpp.
double ObjectSingulationNode::max_workspace_y_ [protected] |
Definition at line 3046 of file object_singulation_node.cpp.
double ObjectSingulationNode::max_workspace_z_ [protected] |
Definition at line 3048 of file object_singulation_node.cpp.
double ObjectSingulationNode::min_workspace_x_ [protected] |
Definition at line 3043 of file object_singulation_node.cpp.
double ObjectSingulationNode::min_workspace_y_ [protected] |
Definition at line 3045 of file object_singulation_node.cpp.
double ObjectSingulationNode::min_workspace_z_ [protected] |
Definition at line 3047 of file object_singulation_node.cpp.
ros::NodeHandle ObjectSingulationNode::n_ [protected] |
Definition at line 3013 of file object_singulation_node.cpp.
ros::NodeHandle ObjectSingulationNode::n_private_ [protected] |
Definition at line 3014 of file object_singulation_node.cpp.
int ObjectSingulationNode::num_downsamples_ [protected] |
Definition at line 3049 of file object_singulation_node.cpp.
shared_ptr<ObjectSingulation> ObjectSingulationNode::os_ [protected] |
Definition at line 3033 of file object_singulation_node.cpp.
shared_ptr<PointCloudSegmentation> ObjectSingulationNode::pcl_segmenter_ [protected] |
Definition at line 3032 of file object_singulation_node.cpp.
Definition at line 3030 of file object_singulation_node.cpp.
cv::Mat ObjectSingulationNode::prev_color_frame_ [protected] |
Definition at line 3026 of file object_singulation_node.cpp.
cv::Mat ObjectSingulationNode::prev_depth_frame_ [protected] |
Definition at line 3027 of file object_singulation_node.cpp.
cv::Mat ObjectSingulationNode::prev_workspace_mask_ [protected] |
Definition at line 3028 of file object_singulation_node.cpp.
Definition at line 3021 of file object_singulation_node.cpp.
int ObjectSingulationNode::record_count_ [protected] |
Definition at line 3056 of file object_singulation_node.cpp.
bool ObjectSingulationNode::recording_input_ [protected] |
Definition at line 3059 of file object_singulation_node.cpp.
Definition at line 3018 of file object_singulation_node.cpp.
PoseStamped ObjectSingulationNode::table_centroid_ [protected] |
Definition at line 3051 of file object_singulation_node.cpp.
Definition at line 3022 of file object_singulation_node.cpp.
shared_ptr<tf::TransformListener> ObjectSingulationNode::tf_ [protected] |
Definition at line 3020 of file object_singulation_node.cpp.
bool ObjectSingulationNode::tracker_initialized_ [protected] |
Definition at line 3053 of file object_singulation_node.cpp.
bool ObjectSingulationNode::tracking_ [protected] |
Definition at line 3052 of file object_singulation_node.cpp.
bool ObjectSingulationNode::use_displays_ [protected] |
Definition at line 3040 of file object_singulation_node.cpp.
bool ObjectSingulationNode::use_guided_pushes_ [protected] |
Definition at line 3058 of file object_singulation_node.cpp.
std::string ObjectSingulationNode::workspace_frame_ [protected] |
Definition at line 3050 of file object_singulation_node.cpp.
bool ObjectSingulationNode::write_input_to_disk_ [protected] |
Definition at line 3041 of file object_singulation_node.cpp.