tracker.hh
Go to the documentation of this file.
00001 #ifndef EVART_ROS_TRACKER_HH
00002 # define EVART_ROS_TRACKER_HH
00003 # include <string>
00004 # include <boost/optional.hpp>
00005 # include <boost/shared_ptr.hpp>
00006 # include <ros/ros.h>
00007 # include <tf/transform_broadcaster.h>
00008 
00009 # include <evart-client.h>
00010 
00011 namespace evart
00012 {
00013   class Tracker
00014   {
00015   public:
00016     static const int queueSize = 5;
00017 
00018     explicit Tracker(ros::NodeHandle& nh,
00019                      const std::string& objectName,
00020                      const std::string& segmentName,
00021                      const std::string& topicName,
00022                      const std::string& referenceFrameName,
00023                      const std::string& childFrameName,
00024                      boost::optional<tf::TransformBroadcaster&>
00025                      transformBroadcaster);
00026     virtual ~Tracker();
00027 
00028     void callback (const evas_body_segments_t& msg);
00029 
00030     unsigned segmentId () const
00031     {
00032       return segmentId_;
00033     }
00034 
00035     unsigned bodyId () const
00036     {
00037       return bodyId_;
00038     }
00039 
00040     const std::string& objectName () const
00041     {
00042       return objectName_;
00043     }
00044 
00045     const std::string& childFrameName () const
00046     {
00047       return childFrameName_;
00048     }
00049 
00050   private:
00051     ros::Publisher publisher_;
00052     uint32_t seq_;
00053 
00054     std::string objectName_;
00055     std::string segmentName_;
00056     const std::string& referenceFrameName_;
00057     std::string childFrameName_;
00058 
00059     uint32_t bodyId_;
00060     uint32_t segmentId_;
00061     boost::optional<tf::TransformBroadcaster&> transformBroadcaster_;
00062   };
00063 
00064   typedef boost::shared_ptr<Tracker> TrackerShPtr;
00065 
00066 } // end of namespace evart.
00067 
00068 #endif //! EVART_ROS_TRACKER_HH


evart_bridge
Author(s): Thomas Moulard/thomas.moulard@gmail.com
autogenerated on Fri Jan 3 2014 11:30:22