Public Member Functions | Protected Member Functions | Protected Attributes
tabletop_pushing::ObjectTracker25D Class Reference

#include <object_tracker_25d.h>

List of all members.

Public Member Functions

void computeState (ProtoObject &cur_obj, pcl16::PointCloud< pcl16::PointXYZ > &cloud, std::string proxy_name, cv::Mat &in_frame, tabletop_pushing::VisFeedbackPushTrackingFeedback &state, bool init_state=false)
void findFootprintBox (ProtoObject &obj, cv::RotatedRect &ellipse)
void findFootprintEllipse (ProtoObject &obj, cv::RotatedRect &ellipse)
ProtoObject findTargetObject (cv::Mat &in_frame, pcl16::PointCloud< pcl16::PointXYZ > &cloud, bool &no_objects, bool init=false)
ProtoObject findTargetObjectGC (cv::Mat &in_frame, XYZPointCloud &cloud, cv::Mat &depth_frame, cv::Mat self_mask, bool &no_objects, bool init=false)
void fit2DMassEllipse (ProtoObject &obj, cv::RotatedRect &ellipse)
void fitHullEllipse (XYZPointCloud &hull_cloud, cv::RotatedRect &obj_ellipse)
void fitObjectEllipse (ProtoObject &obj, cv::RotatedRect &ellipse)
cv::RotatedRect getMostRecentEllipse () const
ProtoObject getMostRecentObject () const
tabletop_pushing::VisFeedbackPushTrackingFeedback getMostRecentState () const
bool getSwapState () const
double getThetaFromEllipse (cv::RotatedRect &obj_ellipse)
void initTracks (cv::Mat &in_frame, cv::Mat &depth_frame, cv::Mat &self_mask, pcl16::PointCloud< pcl16::PointXYZ > &cloud, std::string proxy_name, tabletop_pushing::VisFeedbackPushTrackingFeedback &state, bool start_swap=false)
bool isInitialized () const
bool isPaused () const
 ObjectTracker25D (boost::shared_ptr< PointCloudSegmentation > segmenter, boost::shared_ptr< ArmObjSegmentation > arm_segmenter, int num_downsamples=0, bool use_displays=false, bool write_to_disk=false, std::string base_output_path="", std::string camera_frame="", bool use_cv_ellipse=false, bool use_mps_segmentation=false, bool use_graphcut_arm_seg_=false, double hull_alpha=0.01)
void pause ()
void pausedUpdate (cv::Mat in_frame)
void setNumDownsamples (int num_downsamples)
void stopTracking ()
void toggleSwap ()
void trackerBoxDisplay (cv::Mat &in_frame, ProtoObject &cur_obj, cv::RotatedRect &obj_ellipse)
void trackerDisplay (cv::Mat &in_frame, ProtoObject &cur_obj, cv::RotatedRect &obj_ellipse)
void trackerDisplay (cv::Mat &in_frame, tabletop_pushing::VisFeedbackPushTrackingFeedback &state, ProtoObject &obj, bool other_color=false)
void unpause ()
void updateTracks (cv::Mat &in_frame, cv::Mat &depth_frame, cv::Mat &self_mask, pcl16::PointCloud< pcl16::PointXYZ > &cloud, std::string proxy_name, tabletop_pushing::VisFeedbackPushTrackingFeedback &state)

Protected Member Functions

GMM buildColorModel (XYZPointCloud &cloud, cv::Mat &frame, int num_clusters)
cv::Mat getTableMask (XYZPointCloud &cloud, XYZPointCloud &table_cloud, cv::Size mask_size, XYZPointCloud &obj_cloud)
ProtoObject matchToTargetObject (ProtoObjects &objects, cv::Mat &in_frame, bool init=false)
void updateHeading (tabletop_pushing::VisFeedbackPushTrackingFeedback &state, bool init_state)

Protected Attributes

boost::shared_ptr
< ArmObjSegmentation
arm_segmenter_
std::string base_output_path_
std::string camera_frame_
int frame_count_
int frame_set_count_
bool have_obj_color_model_
bool have_table_color_model_
double hull_alpha_
tabletop_pushing::VisFeedbackPushTrackingFeedback init_state_
bool initialized_
int num_downsamples_
GMM obj_color_model_
bool obj_saved_
bool paused_
boost::shared_ptr
< PointCloudSegmentation
pcl_segmenter_
XYZPointCloud previous_hull_cloud_
ProtoObject previous_obj_
cv::RotatedRect previous_obj_ellipse_
tabletop_pushing::VisFeedbackPushTrackingFeedback previous_state_
double previous_time_
int record_count_
bool swap_orientation_
GMM table_color_model_
int upscale_
bool use_cv_ellipse_fit_
bool use_displays_
bool use_graphcut_arm_seg_
bool use_mps_segmentation_
bool write_to_disk_

Detailed Description

Definition at line 63 of file object_tracker_25d.h.


Constructor & Destructor Documentation

ObjectTracker25D::ObjectTracker25D ( boost::shared_ptr< PointCloudSegmentation segmenter,
boost::shared_ptr< ArmObjSegmentation arm_segmenter,
int  num_downsamples = 0,
bool  use_displays = false,
bool  write_to_disk = false,
std::string  base_output_path = "",
std::string  camera_frame = "",
bool  use_cv_ellipse = false,
bool  use_mps_segmentation = false,
bool  use_graphcut_arm_seg_ = false,
double  hull_alpha = 0.01 
)

Definition at line 33 of file object_tracker_25d.cpp.


Member Function Documentation

GMM ObjectTracker25D::buildColorModel ( XYZPointCloud cloud,
cv::Mat &  frame,
int  num_clusters 
) [protected]

Definition at line 987 of file object_tracker_25d.cpp.

void ObjectTracker25D::computeState ( ProtoObject cur_obj,
pcl16::PointCloud< pcl16::PointXYZ > &  cloud,
std::string  proxy_name,
cv::Mat &  in_frame,
tabletop_pushing::VisFeedbackPushTrackingFeedback &  state,
bool  init_state = false 
)

Definition at line 259 of file object_tracker_25d.cpp.

void ObjectTracker25D::findFootprintBox ( ProtoObject obj,
cv::RotatedRect &  ellipse 
)

Definition at line 543 of file object_tracker_25d.cpp.

void ObjectTracker25D::findFootprintEllipse ( ProtoObject obj,
cv::RotatedRect &  ellipse 
)

Definition at line 530 of file object_tracker_25d.cpp.

ProtoObject ObjectTracker25D::findTargetObject ( cv::Mat &  in_frame,
pcl16::PointCloud< pcl16::PointXYZ > &  cloud,
bool no_objects,
bool  init = false 
)

Definition at line 129 of file object_tracker_25d.cpp.

ProtoObject ObjectTracker25D::findTargetObjectGC ( cv::Mat &  in_frame,
XYZPointCloud cloud,
cv::Mat &  depth_frame,
cv::Mat  self_mask,
bool no_objects,
bool  init = false 
)

Definition at line 50 of file object_tracker_25d.cpp.

void ObjectTracker25D::fit2DMassEllipse ( ProtoObject obj,
cv::RotatedRect &  ellipse 
)

Definition at line 555 of file object_tracker_25d.cpp.

void ObjectTracker25D::fitHullEllipse ( XYZPointCloud hull_cloud,
cv::RotatedRect &  obj_ellipse 
)

Definition at line 477 of file object_tracker_25d.cpp.

void ObjectTracker25D::fitObjectEllipse ( ProtoObject obj,
cv::RotatedRect &  ellipse 
)

Definition at line 465 of file object_tracker_25d.cpp.

Definition at line 136 of file object_tracker_25d.h.

Definition at line 131 of file object_tracker_25d.h.

tabletop_pushing::VisFeedbackPushTrackingFeedback tabletop_pushing::ObjectTracker25D::getMostRecentState ( ) const [inline]

Definition at line 126 of file object_tracker_25d.h.

Definition at line 156 of file object_tracker_25d.h.

cv::Mat ObjectTracker25D::getTableMask ( XYZPointCloud cloud,
XYZPointCloud table_cloud,
cv::Size  mask_size,
XYZPointCloud obj_cloud 
) [protected]

Definition at line 976 of file object_tracker_25d.cpp.

double ObjectTracker25D::getThetaFromEllipse ( cv::RotatedRect &  obj_ellipse)

Definition at line 687 of file object_tracker_25d.cpp.

void ObjectTracker25D::initTracks ( cv::Mat &  in_frame,
cv::Mat &  depth_frame,
cv::Mat &  self_mask,
pcl16::PointCloud< pcl16::PointXYZ > &  cloud,
std::string  proxy_name,
tabletop_pushing::VisFeedbackPushTrackingFeedback &  state,
bool  start_swap = false 
)

Definition at line 628 of file object_tracker_25d.cpp.

Definition at line 109 of file object_tracker_25d.h.

Definition at line 151 of file object_tracker_25d.h.

ProtoObject ObjectTracker25D::matchToTargetObject ( ProtoObjects objects,
cv::Mat &  in_frame,
bool  init = false 
) [protected]

Definition at line 159 of file object_tracker_25d.cpp.

Definition at line 141 of file object_tracker_25d.h.

void ObjectTracker25D::pausedUpdate ( cv::Mat  in_frame)

Definition at line 789 of file object_tracker_25d.cpp.

void tabletop_pushing::ObjectTracker25D::setNumDownsamples ( int  num_downsamples) [inline]

Definition at line 120 of file object_tracker_25d.h.

Definition at line 114 of file object_tracker_25d.h.

Definition at line 161 of file object_tracker_25d.h.

void ObjectTracker25D::trackerBoxDisplay ( cv::Mat &  in_frame,
ProtoObject cur_obj,
cv::RotatedRect &  obj_ellipse 
)

Definition at line 857 of file object_tracker_25d.cpp.

void ObjectTracker25D::trackerDisplay ( cv::Mat &  in_frame,
ProtoObject cur_obj,
cv::RotatedRect &  obj_ellipse 
)

Definition at line 803 of file object_tracker_25d.cpp.

void ObjectTracker25D::trackerDisplay ( cv::Mat &  in_frame,
tabletop_pushing::VisFeedbackPushTrackingFeedback &  state,
ProtoObject obj,
bool  other_color = false 
)

Definition at line 918 of file object_tracker_25d.cpp.

Definition at line 146 of file object_tracker_25d.h.

void ObjectTracker25D::updateHeading ( tabletop_pushing::VisFeedbackPushTrackingFeedback &  state,
bool  init_state 
) [protected]

Definition at line 237 of file object_tracker_25d.cpp.

void ObjectTracker25D::updateTracks ( cv::Mat &  in_frame,
cv::Mat &  depth_frame,
cv::Mat &  self_mask,
pcl16::PointCloud< pcl16::PointXYZ > &  cloud,
std::string  proxy_name,
tabletop_pushing::VisFeedbackPushTrackingFeedback &  state 
)

Definition at line 692 of file object_tracker_25d.cpp.


Member Data Documentation

Definition at line 184 of file object_tracker_25d.h.

Definition at line 196 of file object_tracker_25d.h.

Definition at line 201 of file object_tracker_25d.h.

Definition at line 187 of file object_tracker_25d.h.

Definition at line 200 of file object_tracker_25d.h.

Definition at line 207 of file object_tracker_25d.h.

Definition at line 208 of file object_tracker_25d.h.

Definition at line 210 of file object_tracker_25d.h.

tabletop_pushing::VisFeedbackPushTrackingFeedback tabletop_pushing::ObjectTracker25D::init_state_ [protected]

Definition at line 192 of file object_tracker_25d.h.

Definition at line 186 of file object_tracker_25d.h.

Definition at line 185 of file object_tracker_25d.h.

Definition at line 205 of file object_tracker_25d.h.

Definition at line 204 of file object_tracker_25d.h.

Definition at line 199 of file object_tracker_25d.h.

Definition at line 183 of file object_tracker_25d.h.

Definition at line 211 of file object_tracker_25d.h.

Definition at line 190 of file object_tracker_25d.h.

Definition at line 193 of file object_tracker_25d.h.

tabletop_pushing::VisFeedbackPushTrackingFeedback tabletop_pushing::ObjectTracker25D::previous_state_ [protected]

Definition at line 191 of file object_tracker_25d.h.

Definition at line 189 of file object_tracker_25d.h.

Definition at line 197 of file object_tracker_25d.h.

Definition at line 198 of file object_tracker_25d.h.

Definition at line 206 of file object_tracker_25d.h.

Definition at line 188 of file object_tracker_25d.h.

Definition at line 202 of file object_tracker_25d.h.

Definition at line 194 of file object_tracker_25d.h.

Definition at line 209 of file object_tracker_25d.h.

Definition at line 203 of file object_tracker_25d.h.

Definition at line 195 of file object_tracker_25d.h.


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


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