00001 /* -*- mode: C++ -*- 00002 * 00003 * Copyright (C) 2011 Austin Robot Technology 00004 * License: Modified BSD Software License Agreement 00005 * 00006 * $Id: observer.h 1909 2011-12-05 23:31:31Z jack.oquin $ 00007 */ 00008 00017 #ifndef _ART_OBSERVER_H_ 00018 #define _ART_OBSERVER_H_ 00019 00020 #include <limits> 00021 #include <art_msgs/ArtLanes.h> 00022 #include <art_msgs/Observation.h> 00023 #include <art_observers/ObserversConfig.h> 00024 #include <art_map/PolyOps.h> 00025 00026 namespace observers 00027 { 00028 00030 class Observer 00031 { 00032 public: 00033 00035 typedef art_msgs::Observation::_oid_type Oid_t; 00036 00043 Observer(art_observers::ObserversConfig &config, 00044 Oid_t id, const std::string &name): 00045 config_(config) 00046 { 00047 observation_.oid = id; 00048 observation_.name = name; 00049 observation_.applicable = false; 00050 observation_.clear = false; 00051 observation_.time = std::numeric_limits<float>::infinity(); 00052 observation_.distance = std::numeric_limits<float>::infinity(); 00053 observation_.velocity = std::numeric_limits<float>::quiet_NaN(); 00054 observation_.nobjects = 0; 00055 } 00056 ~Observer(); 00057 00070 virtual art_msgs::Observation 00071 update(const art_msgs::ArtLanes &local_map, 00072 const art_msgs::ArtLanes &obstacles, 00073 MapPose pose) = 0; 00074 00079 bool pointInLane(float x, float y, art_msgs::ArtLanes lane); 00080 art_msgs::ArtLanes getObstaclesInLane(art_msgs::ArtLanes obstacles, 00081 art_msgs::ArtLanes lane_quads); 00082 00083 protected: 00084 art_msgs::Observation observation_; 00085 art_observers::ObserversConfig config_; 00086 }; 00087 00088 }; // namespace observers 00089 00090 #endif // _ART_OBSERVER_H_