ObstacleProviderController.hpp
Go to the documentation of this file.
00001 /*
00002  * ObstacleProviderController.hpp
00003  *
00004  *  Created on: Dec 14, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef OBSTACLEPROVIDERCONTROLLER_HPP_
00009 #define OBSTACLEPROVIDERCONTROLLER_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 
00013 #include <obs_detection/ObstacleProviderControllerOptions.hpp>
00014 #include <obs_detection/ObstacleProviderContainer.hpp>
00015 
00016 #include <ros/ros.h>
00017 
00018 namespace TELEKYB_NAMESPACE {
00019 
00020 class ObstacleProviderController {
00021 protected:
00022         ObstacleProviderControllerOptions options;
00023         // Container
00024         ObstacleProviderContainer obsContainer;
00025 
00026         // ROS
00027         // NodeHandle
00028         ros::NodeHandle nodeHandle;
00029         // State Subscription
00030         ros::Subscriber tStateSub;
00031         // PointArray Publisher
00032         ros::Publisher tObsPointsPub;
00033 
00034         // Callback
00035         TKState lastState;
00036         boost::mutex lastStateMutex;
00037         void tkStateCB(const telekyb_msgs::TKState::ConstPtr& tkStateMsg);
00038         bool recvFirstTKState;
00039 
00040         // Helper Functions
00041         void loadObstacleProviders();
00042         void obstacleProviderStep();
00043 
00044         std::vector< Position3D > allObstaclePositions;
00045 
00046 public:
00047         ObstacleProviderController();
00048         virtual ~ObstacleProviderController();
00049 
00050         void spin();
00051 };
00052 
00053 } /* namespace telekyb */
00054 #endif /* OBSTACLEPROVIDERCONTROLLER_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


tk_obstacle
Author(s): Martin Riedel
autogenerated on Mon Nov 11 2013 11:13:22