#include <tracker.hh>
Public Member Functions | |
unsigned | bodyId () const |
void | callback (const evas_body_segments_t &msg) |
const std::string & | childFrameName () const |
const std::string & | objectName () const |
unsigned | segmentId () const |
Tracker (ros::NodeHandle &nh, const std::string &objectName, const std::string &segmentName, const std::string &topicName, const std::string &referenceFrameName, const std::string &childFrameName, boost::optional< tf::TransformBroadcaster & > transformBroadcaster) | |
virtual | ~Tracker () |
Static Public Attributes | |
static const int | queueSize = 5 |
Private Attributes | |
uint32_t | bodyId_ |
std::string | childFrameName_ |
std::string | objectName_ |
ros::Publisher | publisher_ |
const std::string & | referenceFrameName_ |
uint32_t | segmentId_ |
std::string | segmentName_ |
uint32_t | seq_ |
boost::optional < tf::TransformBroadcaster & > | transformBroadcaster_ |
Definition at line 13 of file tracker.hh.
evart::Tracker::Tracker | ( | ros::NodeHandle & | nh, |
const std::string & | objectName, | ||
const std::string & | segmentName, | ||
const std::string & | topicName, | ||
const std::string & | referenceFrameName, | ||
const std::string & | childFrameName, | ||
boost::optional< tf::TransformBroadcaster & > | transformBroadcaster | ||
) | [explicit] |
Definition at line 53 of file tracker.cpp.
evart::Tracker::~Tracker | ( | ) | [virtual] |
Definition at line 79 of file tracker.cpp.
unsigned evart::Tracker::bodyId | ( | ) | const [inline] |
Definition at line 35 of file tracker.hh.
void evart::Tracker::callback | ( | const evas_body_segments_t & | msg | ) |
Definition at line 87 of file tracker.cpp.
const std::string& evart::Tracker::childFrameName | ( | ) | const [inline] |
Definition at line 45 of file tracker.hh.
const std::string& evart::Tracker::objectName | ( | ) | const [inline] |
Definition at line 40 of file tracker.hh.
unsigned evart::Tracker::segmentId | ( | ) | const [inline] |
Definition at line 30 of file tracker.hh.
uint32_t evart::Tracker::bodyId_ [private] |
Definition at line 59 of file tracker.hh.
std::string evart::Tracker::childFrameName_ [private] |
Definition at line 57 of file tracker.hh.
std::string evart::Tracker::objectName_ [private] |
Definition at line 54 of file tracker.hh.
ros::Publisher evart::Tracker::publisher_ [private] |
Definition at line 51 of file tracker.hh.
const int evart::Tracker::queueSize = 5 [static] |
Definition at line 16 of file tracker.hh.
const std::string& evart::Tracker::referenceFrameName_ [private] |
Definition at line 56 of file tracker.hh.
uint32_t evart::Tracker::segmentId_ [private] |
Definition at line 60 of file tracker.hh.
std::string evart::Tracker::segmentName_ [private] |
Definition at line 55 of file tracker.hh.
uint32_t evart::Tracker::seq_ [private] |
Definition at line 52 of file tracker.hh.
boost::optional<tf::TransformBroadcaster&> evart::Tracker::transformBroadcaster_ [private] |
Definition at line 61 of file tracker.hh.