#include <ShapeTracker.h>
Public Member Functions | |
ShapeTrackerPtr | clone () const |
virtual void | setCameraInfo (const sensor_msgs::CameraInfo &camera_info) |
virtual void | setShapeModel (const sensor_msgs::PointCloud2 &model) |
ShapeTracker (omip::RB_id_t rb_id) | |
ShapeTracker (const ShapeTracker &sr) | |
virtual void | step (const sensor_msgs::PointCloud2ConstPtr &pc_msg, const omip_msgs::RigidBodyPoseAndVelMsg &tracked_rbm, omip_msgs::ShapeTrackerState &st_state) |
virtual | ~ShapeTracker () |
Protected Member Functions | |
virtual void | _FindInconsistentPoints (const pcl::PointCloud< pcl::PointXYZ >::Ptr &pc_source, const cv::Mat &dm_true, pcl::PointIndicesPtr &indices_to_remove, pcl::PointIndicesPtr &indices_matching_in_true, pcl::PointIndicesPtr &indices_matching_in_dm, const double min_depth_error=0.03) |
virtual void | _RemoveInconsistentPointsFromRBModel (pcl::PointCloud< pcl::PointXYZ >::Ptr model_current_pose, pcl::PointCloud< pcl::PointXYZ >::Ptr current_pc, pcl::PointCloud< pcl::PointXYZ >::Ptr &rb_segment_depth, pcl::PointCloud< pcl::PointXYZ >::Ptr ¤t_pc_extended_segment) |
virtual ShapeTracker * | doClone () const |
Clone function. | |
Protected Attributes | |
sensor_msgs::CameraInfo | _ci |
cv::Mat | _current_dm |
cv::Mat | _dilation_element |
pcl::ExtractIndices < pcl::PointXYZ > | _extractor |
pcl::IterativeClosestPoint < pcl::PointXYZ, pcl::PointXYZ > | _icp |
bool | _new_model |
ros::NodeHandle | _nh |
omip::RB_id_t | _rb_id |
pcl::PointCloud< pcl::PointXYZ > ::Ptr | _rb_model |
cv::Mat | _segment_of_current |
cv::Mat | _segment_of_current_dilated |
ros::Publisher | _segment_pub |
Definition at line 80 of file ShapeTracker.h.
ShapeTracker::ShapeTracker | ( | omip::RB_id_t | rb_id | ) |
Definition at line 43 of file ShapeTracker.cpp.
ShapeTracker::ShapeTracker | ( | const ShapeTracker & | sr | ) |
Definition at line 151 of file ShapeTracker.cpp.
ShapeTracker::~ShapeTracker | ( | ) | [virtual] |
Definition at line 159 of file ShapeTracker.cpp.
void ShapeTracker::_FindInconsistentPoints | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | pc_source, |
const cv::Mat & | dm_true, | ||
pcl::PointIndicesPtr & | indices_to_remove, | ||
pcl::PointIndicesPtr & | indices_matching_in_true, | ||
pcl::PointIndicesPtr & | indices_matching_in_dm, | ||
const double | min_depth_error = 0.03 |
||
) | [protected, virtual] |
Definition at line 397 of file ShapeTracker.cpp.
void ShapeTracker::_RemoveInconsistentPointsFromRBModel | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr | model_current_pose, |
pcl::PointCloud< pcl::PointXYZ >::Ptr | current_pc, | ||
pcl::PointCloud< pcl::PointXYZ >::Ptr & | rb_segment_depth, | ||
pcl::PointCloud< pcl::PointXYZ >::Ptr & | current_pc_extended_segment | ||
) | [protected, virtual] |
Definition at line 338 of file ShapeTracker.cpp.
ShapeTrackerPtr omip::ShapeTracker::clone | ( | ) | const [inline] |
Definition at line 85 of file ShapeTracker.h.
virtual ShapeTracker* omip::ShapeTracker::doClone | ( | ) | const [inline, protected, virtual] |
Clone function.
Definition at line 118 of file ShapeTracker.h.
void ShapeTracker::setCameraInfo | ( | const sensor_msgs::CameraInfo & | camera_info | ) | [virtual] |
Definition at line 163 of file ShapeTracker.cpp.
void ShapeTracker::setShapeModel | ( | const sensor_msgs::PointCloud2 & | model | ) | [virtual] |
Definition at line 327 of file ShapeTracker.cpp.
void ShapeTracker::step | ( | const sensor_msgs::PointCloud2ConstPtr & | pc_msg, |
const omip_msgs::RigidBodyPoseAndVelMsg & | tracked_rbm, | ||
omip_msgs::ShapeTrackerState & | st_state | ||
) | [virtual] |
Definition at line 186 of file ShapeTracker.cpp.
sensor_msgs::CameraInfo omip::ShapeTracker::_ci [protected] |
Definition at line 126 of file ShapeTracker.h.
cv::Mat omip::ShapeTracker::_current_dm [protected] |
Definition at line 135 of file ShapeTracker.h.
cv::Mat omip::ShapeTracker::_dilation_element [protected] |
Definition at line 138 of file ShapeTracker.h.
pcl::ExtractIndices<pcl::PointXYZ> omip::ShapeTracker::_extractor [protected] |
Definition at line 140 of file ShapeTracker.h.
pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> omip::ShapeTracker::_icp [protected] |
Definition at line 128 of file ShapeTracker.h.
bool omip::ShapeTracker::_new_model [protected] |
Definition at line 133 of file ShapeTracker.h.
ros::NodeHandle omip::ShapeTracker::_nh [protected] |
Definition at line 130 of file ShapeTracker.h.
omip::RB_id_t omip::ShapeTracker::_rb_id [protected] |
Definition at line 123 of file ShapeTracker.h.
pcl::PointCloud<pcl::PointXYZ >::Ptr omip::ShapeTracker::_rb_model [protected] |
Definition at line 124 of file ShapeTracker.h.
cv::Mat omip::ShapeTracker::_segment_of_current [protected] |
Definition at line 136 of file ShapeTracker.h.
cv::Mat omip::ShapeTracker::_segment_of_current_dilated [protected] |
Definition at line 137 of file ShapeTracker.h.
ros::Publisher omip::ShapeTracker::_segment_pub [protected] |
Definition at line 131 of file ShapeTracker.h.