00001 /* 00002 * ExternalObsPoint.hpp 00003 * 00004 * Created on: Dec 16, 2011 00005 * Author: mriedel 00006 */ 00007 00008 #ifndef EXTERNALOBSPOINT_HPP_ 00009 #define EXTERNALOBSPOINT_HPP_ 00010 00011 #include <telekyb_defines/telekyb_defines.hpp> 00012 #include <obs_detection/ObstacleProvider.hpp> 00013 #include <telekyb_base/Options.hpp> 00014 #include <geometry_msgs/PoseStamped.h> 00015 #include <boost/thread/mutex.hpp> 00016 #include <telekyb_base/ROS/GenericSubscriber.hpp> 00017 00018 using namespace TELEKYB_NAMESPACE; 00019 00020 namespace telekyb_obs { 00021 00022 class ExternalObsPointOptions : public OptionContainer { 00023 public: 00024 Option< std::vector<std::string> >* tObsTransformTopicNames; 00025 Option< std::vector<double> >* tObsRadius; 00026 Option<Eigen::Matrix3d>* tObsTranformConvMatrix; 00027 ExternalObsPointOptions(); 00028 }; 00029 00030 class ExternalObsPoint : public ObstacleProvider { 00031 protected: 00032 ExternalObsPointOptions options; 00033 // ros::Subscriber obsTranformSub; 00034 std::vector<std::string> transformTopicNames; 00035 std::vector<double> obstacleRadii; 00036 std::vector< GenericSubscriber<geometry_msgs::PoseStamped>* > subscribers; 00037 00038 // Position3D obsPoint; 00039 // mutable boost::mutex obsPointMutex; 00040 00041 public: 00042 ExternalObsPoint(); 00043 virtual ~ExternalObsPoint(); 00044 00045 // called directly after Creation 00046 virtual void initialize(); 00047 00048 // called right before destruction 00049 virtual void destroy(); 00050 00051 virtual void getObstaclePoints(const TKState& lastState, std::vector<Position3D>& obstaclePoints) const; 00052 00053 // TransformCB 00054 // void obsPointCB(const geometry_msgs::TransformStamped::ConstPtr& msg); 00055 }; 00056 00057 } /* namespace telekyb_obs */ 00058 #endif /* EXTERNALOBSPOINT_HPP_ */