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

void enableAllTracking (bool enable)
const geometry_msgs::Pose getCameraReferencePose ()
 Get the constant camera reference of Blort.
std::map< std::string,
geometry_msgs::Pose > & 
getDetections ()
 Get some statistics of the actual tracking state.
cv::Mat getImage ()
 Get the rendered image for visualization.
const std::string & getModelName (size_t i)
 Return model names.
const std::vector
< blort::ObjectEntry > & 
getObjects () const
TrackerPublishMode getPublishMode ()
 GLTracker (const sensor_msgs::CameraInfo camera_info, const std::string &config_root, bool visualize_obj_pose=false)
bool isTracked (const std::string &id)
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 (const std::vector< std::string > &params=std::vector< std::string >())
void resetWithPose (std::string obj_id, const geometry_msgs::Pose &new_pose)
void setPublishMode (TrackerPublishMode mode)
void setTracked (const std::string &id, bool tracked)
void setVisualizeObjPose (bool enable)
virtual void switchToRecovery (const std::string &id)
virtual void switchToTracking (const std::string &id)
virtual void switchTracking (const std::vector< std::string > &params)
virtual void track ()
 Method to run and handle tracking.
void trackerControl (uint8_t code, const std::vector< std::string > &params)
 Control the tracker with a single int code.
 ~GLTracker ()

Private Member Functions

blort::ObjectEntrygetObjEntryByName (const std::string &name)
void resetParticleFilter (std::string id)
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 (std::string i)
 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
std::map< std::string, int > model_ids
boost::mutex models_mutex
std::vector< blort::ObjectEntryobjects_
std::string pose_cal
int publish_mode
float recovery_conf_threshold
std::map< std::string,
geometry_msgs::Pose
result
TomGine::tgCamera::Parameter tgcam_params
TomGine::tgTimer timer
Tracking::Tracker::Parameter track_params
Tracking::TextureTracker tracker
bool visualize_obj_pose

Detailed Description

Definition at line 68 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 449 of file gltracker.cpp.


Member Function Documentation

void GLTracker::enableAllTracking ( bool  enable)

Definition at line 480 of file gltracker.cpp.

Get the constant camera reference of Blort.

Definition at line 140 of file gltracker.h.

std::map<std::string, geometry_msgs::Pose>& blort_ros::GLTracker::getDetections ( ) [inline]

Get some statistics of the actual tracking state.

Get the results of the latest detections.

Definition at line 137 of file gltracker.h.

cv::Mat GLTracker::getImage ( )

Get the rendered image for visualization.

Definition at line 313 of file gltracker.cpp.

const std::string& blort_ros::GLTracker::getModelName ( size_t  i) [inline]

Return model names.

Definition at line 146 of file gltracker.h.

const std::vector< blort::ObjectEntry > & GLTracker::getObjects ( ) const

Definition at line 465 of file gltracker.cpp.

blort::ObjectEntry & GLTracker::getObjEntryByName ( const std::string &  name) [private]

Definition at line 453 of file gltracker.cpp.

TrackerPublishMode blort_ros::GLTracker::getPublishMode ( ) [inline]

Definition at line 152 of file gltracker.h.

bool GLTracker::isTracked ( const std::string &  id)

Definition at line 470 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 235 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 114 of file gltracker.h.

void GLTracker::reset ( const std::vector< std::string > &  params = std::vector<std::string>())

Definition at line 411 of file gltracker.cpp.

void GLTracker::resetParticleFilter ( std::string  id) [private]

Definition at line 122 of file gltracker.cpp.

void GLTracker::resetWithPose ( std::string  obj_id,
const geometry_msgs::Pose new_pose 
)

Definition at line 221 of file gltracker.cpp.

void blort_ros::GLTracker::setPublishMode ( TrackerPublishMode  mode) [inline]

Definition at line 150 of file gltracker.h.

void GLTracker::setTracked ( const std::string &  id,
bool  tracked 
)

Definition at line 475 of file gltracker.cpp.

void blort_ros::GLTracker::setVisualizeObjPose ( bool  enable) [inline]

Definition at line 148 of file gltracker.h.

void GLTracker::switchToRecovery ( const std::string &  id) [virtual]

Definition at line 437 of file gltracker.cpp.

void GLTracker::switchToTracking ( const std::string &  id) [virtual]

Definition at line 431 of file gltracker.cpp.

void GLTracker::switchTracking ( const std::vector< std::string > &  params) [virtual]

Definition at line 294 of file gltracker.cpp.

void GLTracker::track ( ) [virtual]

Method to run and handle tracking.

Implements blort_ros::TrackerInterface.

Definition at line 142 of file gltracker.cpp.

void GLTracker::trackerControl ( uint8_t  code,
const std::vector< std::string > &  params 
)

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 251 of file gltracker.cpp.

void GLTracker::update ( ) [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 364 of file gltracker.cpp.

void GLTracker::updatePoseResult ( std::string  i) [private]

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

Definition at line 345 of file gltracker.cpp.


Member Data Documentation

Definition at line 81 of file gltracker.h.

Definition at line 72 of file gltracker.h.

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

Definition at line 87 of file gltracker.h.

Definition at line 102 of file gltracker.h.

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

Definition at line 98 of file gltracker.h.

Definition at line 106 of file gltracker.h.

std::map<std::string, int> blort_ros::GLTracker::model_ids [private]

Definition at line 92 of file gltracker.h.

boost::mutex blort_ros::GLTracker::models_mutex [private]

Definition at line 95 of file gltracker.h.

Definition at line 91 of file gltracker.h.

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

Definition at line 88 of file gltracker.h.

Definition at line 74 of file gltracker.h.

Definition at line 76 of file gltracker.h.

std::map<std::string, geometry_msgs::Pose> blort_ros::GLTracker::result [private]

Definition at line 103 of file gltracker.h.

Definition at line 79 of file gltracker.h.

Definition at line 80 of file gltracker.h.

Definition at line 82 of file gltracker.h.

Definition at line 84 of file gltracker.h.

Definition at line 73 of file gltracker.h.


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


blort_ros
Author(s): Bence Magyar
autogenerated on Wed Aug 26 2015 15:24:39