Public Member Functions | Private Member Functions | Private Attributes
blort_ros::GLTracker Class Reference

#include <gltracker.h>

Inheritance diagram for blort_ros::GLTracker:
Inheritance graph
[legend]

List of all members.

Public Member Functions

const geometry_msgs::Pose getCameraReferencePose ()
 Get the constant camera reference of Blort.
TrackerConfidences getConfidences ()
 Get some statistics of the actual tracking state.
const std::vector
< geometry_msgs::Pose > & 
getDetections ()
 Get the results of the latest detections.
cv::Mat getImage ()
 Get the rendered image for visualization.
std::string getStatusString ()
 Get a status string describing the current state of the tracker.
 GLTracker (const sensor_msgs::CameraInfo camera_info, const std::string &config_root, bool visualize_obj_pose=false)
void reconfigure (blort_ros::TrackerConfig config)
 Control the tracker using a ROS reconfigure_gui node.
virtual void recovery ()
 Method to run and handle recovery state.
void reset ()
void resetParticleFilter ()
void resetWithPose (const geometry_msgs::Pose &new_pose)
void setPublisMode (TrackerPublishMode mode)
void setVisualizeObjPose (bool enable)
virtual void track ()
 Method to run and handle tracking.
void trackerControl (int code, int param=-1)
 Control the tracker with a single int code.
 ~GLTracker ()

Private Member Functions

void update ()
 Update confidences and state based on the state and confidences of the encapsulated tracker. Also pose result is updated if the state is apropriate.
void updatePoseResult ()
 Assemble pose result to be published based on class variables. The result is put in the corresponding variable.

Private Attributes

TomGine::tgPose cam_pose
double conf_threshold
std::string config_root_
geometry_msgs::Pose fixed_cam_pose
IplImage * image
bool last_reset
int model_id
std::string model_name
Tracking::movement_state movement
std::string ply_model_
std::string pose_cal
int publish_mode
Tracking::quality_state quality
float recovery_conf_threshold
std::vector< geometry_msgs::Poseresult
std::string sift_file
TomGine::tgCamera::Parameter tgcam_params
TomGine::tgTimer timer
Tracking::Tracker::Parameter track_params
Tracking::TextureTracker tracker
Tracking::confidence_state tracker_confidence
TrackerConfidences tracker_confidences
TomGine::tgPose trPose
bool visualize_obj_pose

Detailed Description

Definition at line 66 of file gltracker.h.


Constructor & Destructor Documentation

GLTracker::GLTracker ( const sensor_msgs::CameraInfo  camera_info,
const std::string &  config_root,
bool  visualize_obj_pose = false 
)

Definition at line 51 of file gltracker.cpp.

Definition at line 346 of file gltracker.cpp.


Member Function Documentation

Get the constant camera reference of Blort.

Definition at line 139 of file gltracker.h.

Get some statistics of the actual tracking state.

Definition at line 133 of file gltracker.h.

Get the results of the latest detections.

Definition at line 136 of file gltracker.h.

cv::Mat GLTracker::getImage ( )

Get the rendered image for visualization.

Definition at line 259 of file gltracker.cpp.

std::string GLTracker::getStatusString ( )

Get a status string describing the current state of the tracker.

Definition at line 246 of file gltracker.cpp.

void GLTracker::reconfigure ( blort_ros::TrackerConfig  config)

Control the tracker using a ROS reconfigure_gui node.

Parameters:
Reconfigure_guimessagetype

Definition at line 195 of file gltracker.cpp.

virtual void blort_ros::GLTracker::recovery ( ) [inline, virtual]

Method to run and handle recovery state.

Implements blort_ros::TrackerInterface.

Definition at line 113 of file gltracker.h.

void GLTracker::reset ( ) [virtual]

Reimplemented from blort_ros::TrackerInterface.

Definition at line 340 of file gltracker.cpp.

Definition at line 110 of file gltracker.cpp.

void GLTracker::resetWithPose ( const geometry_msgs::Pose new_pose)

Definition at line 175 of file gltracker.cpp.

Definition at line 149 of file gltracker.h.

Definition at line 147 of file gltracker.h.

void GLTracker::track ( ) [virtual]

Method to run and handle tracking.

Implements blort_ros::TrackerInterface.

Definition at line 119 of file gltracker.cpp.

void GLTracker::trackerControl ( int  code,
int  param = -1 
)

Control the tracker with a single int code.

Parameters:
codeinteger code associated with command, can be used with enums.
paramparameter of the command

Definition at line 211 of file gltracker.cpp.

void GLTracker::update ( void  ) [private]

Update confidences and state based on the state and confidences of the encapsulated tracker. Also pose result is updated if the state is apropriate.

Definition at line 297 of file gltracker.cpp.

void GLTracker::updatePoseResult ( ) [private]

Assemble pose result to be published based on class variables. The result is put in the corresponding variable.

Definition at line 277 of file gltracker.cpp.


Member Data Documentation

Definition at line 79 of file gltracker.h.

Definition at line 70 of file gltracker.h.

std::string blort_ros::GLTracker::config_root_ [private]

Definition at line 85 of file gltracker.h.

Definition at line 101 of file gltracker.h.

IplImage* blort_ros::GLTracker::image [private]

Definition at line 97 of file gltracker.h.

Definition at line 105 of file gltracker.h.

Definition at line 91 of file gltracker.h.

std::string blort_ros::GLTracker::model_name [private]

Definition at line 86 of file gltracker.h.

Definition at line 92 of file gltracker.h.

std::string blort_ros::GLTracker::ply_model_ [private]

Definition at line 85 of file gltracker.h.

std::string blort_ros::GLTracker::pose_cal [private]

Definition at line 87 of file gltracker.h.

Definition at line 72 of file gltracker.h.

Definition at line 93 of file gltracker.h.

Definition at line 74 of file gltracker.h.

Definition at line 102 of file gltracker.h.

std::string blort_ros::GLTracker::sift_file [private]

Definition at line 86 of file gltracker.h.

Definition at line 77 of file gltracker.h.

Definition at line 78 of file gltracker.h.

Definition at line 80 of file gltracker.h.

Definition at line 82 of file gltracker.h.

Definition at line 94 of file gltracker.h.

Definition at line 100 of file gltracker.h.

Definition at line 90 of file gltracker.h.

Definition at line 71 of file gltracker.h.


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


blort_ros
Author(s): Bence Magyar
autogenerated on Thu Jan 2 2014 11:39:13