Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
yocs::ARMarkerTracking Class Reference

#include <tracking.hpp>

Public Member Functions

 ARMarkerTracking ()
 
bool init ()
 
void spin ()
 
virtual ~ARMarkerTracking ()
 

Protected Member Functions

void arPoseMarkersCB (const ar_track_alvar_msgs::AlvarMarkers::ConstPtr &msg)
 
bool closest (double younger_than, double min_confidence, ar_track_alvar_msgs::AlvarMarker &closest_marker)
 
bool closest (const ar_track_alvar_msgs::AlvarMarkers &including, const ar_track_alvar_msgs::AlvarMarkers &excluding, ar_track_alvar_msgs::AlvarMarker &closest_marker)
 
bool closest (double younger_than, double min_confidence, ar_track_alvar_msgs::AlvarMarkers &excluding, ar_track_alvar_msgs::AlvarMarker &closest_marker)
 
virtual void customCB (const ar_track_alvar_msgs::AlvarMarkers &spotted_markers, const std::vector< TrackedMarker > &tracked_markers)
 
bool excluded (const uint32_t id, const ar_track_alvar_msgs::AlvarMarkers &v)
 
bool included (const uint32_t id, const ar_track_alvar_msgs::AlvarMarkers &v, ar_track_alvar_msgs::AlvarMarker *e=NULL)
 
void maintainTrackedMarker (TrackedMarker &marker, const ar_track_alvar_msgs::AlvarMarker &msgMarker, const int obs_list_max_size, const double max_valid_d_inc, const double max_valid_h_inc)
 
void maintainTrackedMarkers (const ar_track_alvar_msgs::AlvarMarkers::ConstPtr &msg, std::vector< TrackedMarker > &tracked_markers)
 
bool spotted (double younger_than, double min_confidence, ar_track_alvar_msgs::AlvarMarkers &spotted_markers)
 
bool spotted (double younger_than, const ar_track_alvar_msgs::AlvarMarkers &including, const ar_track_alvar_msgs::AlvarMarkers &excluding, ar_track_alvar_msgs::AlvarMarkers &spotted_markers)
 
bool spotted (double younger_than, double min_confidence, ar_track_alvar_msgs::AlvarMarkers &excluding, ar_track_alvar_msgs::AlvarMarkers &spotted)
 

Protected Attributes

double ar_tracker_freq_
 
double max_reliable_dist_
 
double max_reliable_head_
 
double max_tracking_time_
 
double max_valid_d_inc_
 
double max_valid_h_inc_
 
double min_penalized_dist_
 
double min_penalized_head_
 
ar_track_alvar_msgs::AlvarMarkers spotted_markers_
 
ros::Subscriber sub_ar_markers_
 
std::vector< TrackedMarkertracked_markers_
 

Detailed Description

Definition at line 121 of file tracking.hpp.

Constructor & Destructor Documentation

yocs::ARMarkerTracking::ARMarkerTracking ( )

Definition at line 17 of file tracking.cpp.

yocs::ARMarkerTracking::~ARMarkerTracking ( )
virtual

Definition at line 21 of file tracking.cpp.

Member Function Documentation

void yocs::ARMarkerTracking::arPoseMarkersCB ( const ar_track_alvar_msgs::AlvarMarkers::ConstPtr &  msg)
protected

Definition at line 51 of file tracking.cpp.

bool yocs::ARMarkerTracking::closest ( double  younger_than,
double  min_confidence,
ar_track_alvar_msgs::AlvarMarker &  closest_marker 
)
protected

Definition at line 122 of file utils.cpp.

bool yocs::ARMarkerTracking::closest ( const ar_track_alvar_msgs::AlvarMarkers &  including,
const ar_track_alvar_msgs::AlvarMarkers &  excluding,
ar_track_alvar_msgs::AlvarMarker &  closest_marker 
)
protected

Definition at line 46 of file utils.cpp.

bool yocs::ARMarkerTracking::closest ( double  younger_than,
double  min_confidence,
ar_track_alvar_msgs::AlvarMarkers &  excluding,
ar_track_alvar_msgs::AlvarMarker &  closest_marker 
)
protected

Definition at line 142 of file utils.cpp.

virtual void yocs::ARMarkerTracking::customCB ( const ar_track_alvar_msgs::AlvarMarkers &  spotted_markers,
const std::vector< TrackedMarker > &  tracked_markers 
)
inlineprotectedvirtual

Definition at line 136 of file tracking.hpp.

bool yocs::ARMarkerTracking::excluded ( const uint32_t  id,
const ar_track_alvar_msgs::AlvarMarkers &  v 
)
protected

Definition at line 181 of file utils.cpp.

bool yocs::ARMarkerTracking::included ( const uint32_t  id,
const ar_track_alvar_msgs::AlvarMarkers &  v,
ar_track_alvar_msgs::AlvarMarker *  e = NULL 
)
protected

Definition at line 164 of file utils.cpp.

bool yocs::ARMarkerTracking::init ( )

Definition at line 23 of file tracking.cpp.

void yocs::ARMarkerTracking::maintainTrackedMarker ( TrackedMarker marker,
const ar_track_alvar_msgs::AlvarMarker &  msgMarker,
const int  obs_list_max_size,
const double  max_valid_d_inc,
const double  max_valid_h_inc 
)
protected

Definition at line 94 of file tracking.cpp.

void yocs::ARMarkerTracking::maintainTrackedMarkers ( const ar_track_alvar_msgs::AlvarMarkers::ConstPtr &  msg,
std::vector< TrackedMarker > &  tracked_markers 
)
protected

Definition at line 69 of file tracking.cpp.

void yocs::ARMarkerTracking::spin ( )

Definition at line 143 of file tracking.cpp.

bool yocs::ARMarkerTracking::spotted ( double  younger_than,
double  min_confidence,
ar_track_alvar_msgs::AlvarMarkers &  spotted_markers 
)
protected

Return spotted markers satisfying the constraints specified by the parameters

Parameters
younger_thanElapsed time between now and markers timestamp must be below this limit.
min_confidence
exclude_globals
spotted_markers
Returns

Definition at line 66 of file utils.cpp.

bool yocs::ARMarkerTracking::spotted ( double  younger_than,
const ar_track_alvar_msgs::AlvarMarkers &  including,
const ar_track_alvar_msgs::AlvarMarkers &  excluding,
ar_track_alvar_msgs::AlvarMarkers &  spotted_markers 
)
protected

Definition at line 19 of file utils.cpp.

bool yocs::ARMarkerTracking::spotted ( double  younger_than,
double  min_confidence,
ar_track_alvar_msgs::AlvarMarkers &  excluding,
ar_track_alvar_msgs::AlvarMarkers &  spotted 
)
protected

Definition at line 93 of file utils.cpp.

Member Data Documentation

double yocs::ARMarkerTracking::ar_tracker_freq_
protected

AR tracker frequency; unless changed with setTrackerFreq, it must be the same value configured on ar_track_alvar node

Definition at line 171 of file tracking.hpp.

double yocs::ARMarkerTracking::max_reliable_dist_
protected

Definition at line 165 of file tracking.hpp.

double yocs::ARMarkerTracking::max_reliable_head_
protected

Definition at line 167 of file tracking.hpp.

double yocs::ARMarkerTracking::max_tracking_time_
protected

Maximum time tacking a marker to ensure that it's a stable observation

Definition at line 168 of file tracking.hpp.

double yocs::ARMarkerTracking::max_valid_d_inc_
protected

Maximum valid distance increment per second to consider stable tracking

Definition at line 169 of file tracking.hpp.

double yocs::ARMarkerTracking::max_valid_h_inc_
protected

Maximum valid heading increment per second to consider stable tracking

Definition at line 170 of file tracking.hpp.

double yocs::ARMarkerTracking::min_penalized_dist_
protected

Definition at line 164 of file tracking.hpp.

double yocs::ARMarkerTracking::min_penalized_head_
protected

Definition at line 166 of file tracking.hpp.

ar_track_alvar_msgs::AlvarMarkers yocs::ARMarkerTracking::spotted_markers_
protected

Definition at line 175 of file tracking.hpp.

ros::Subscriber yocs::ARMarkerTracking::sub_ar_markers_
protected

Definition at line 176 of file tracking.hpp.

std::vector<TrackedMarker> yocs::ARMarkerTracking::tracked_markers_
protected

Definition at line 174 of file tracking.hpp.


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


yocs_ar_marker_tracking
Author(s): Daniel Stonier, Jorge Santos
autogenerated on Mon Jun 10 2019 15:53:43