evart.hh
Go to the documentation of this file.
00001 #ifndef EVART_ROS_EVART_HH
00002 # define EVART_ROS_EVART_HH
00003 # include <string>
00004 # include <vector>
00005 
00006 # include <boost/optional.hpp>
00007 
00008 # include <ros/ros.h>
00009 # include <tf/transform_broadcaster.h>
00010 
00011 # include "tracker.hh"
00012 
00013 # include "evart_bridge/List.h"
00014 # include "evart_bridge/TrackSegment.h"
00015 
00016 namespace evart
00017 {
00018   class Evart
00019   {
00020   public:
00021     Evart();
00022     virtual ~Evart();
00023 
00024     void spin();
00025 
00026     bool trackSegments(evart_bridge::TrackSegment::Request& req,
00027                        evart_bridge::TrackSegment::Response& res);
00028     bool listSegments(evart_bridge::List::Request& req,
00029                       evart_bridge::List::Response& res);
00030     void trackAllSegments();
00031 
00032   private:
00033     ros::NodeHandle nodeHandle_;
00034 
00035     std::vector<TrackerShPtr> trackers_;
00036 
00037     std::string evartHost_;
00038     int evartPort_;
00039     bool enableTfBroadcast_;
00040     std::string tfReferenceFrameName_;
00041 
00042     ros::ServiceServer trackSegmentsSrv_;
00043     ros::ServiceServer listSegmentsSrv_;
00044 
00045     tf::TransformBroadcaster transformBroadcaster_;
00046 
00047     double updateRate_;
00048     bool trackAllSegments_;
00049   };
00050 
00051 } // end of namespace evart.
00052 
00053 #endif //! EVART_ROS_EVART_HH


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