#include <observation_dep.h>
Public Types | |
typedef boost::unordered_map < std::string, uint32_t > | DepIndexMap |
typedef std::vector< std::string > | ObsFactorGlobalDeps |
typedef std::vector < predicate_manager::NameID > | ObsFactorLocalDeps |
Public Member Functions | |
ObservationDep | add (uint32_t pm_id, std::string event_name) |
ObservationDep | add (std::string event_name) |
uint32_t | getDependencyIndex (const std::string &event_name) |
const ObsFactorGlobalDeps | getGlobalDependencies () const |
const ObsFactorLocalDeps | getLocalDependencies () const |
uint32_t | getNumberOfValues () const |
Private Member Functions | |
void | registerDependencyName (const std::string &event_name) |
Private Attributes | |
DepIndexMap | dep_index_map_ |
ObsFactorGlobalDeps | global_deps_ |
ObsFactorLocalDeps | local_deps_ |
ros::NodeHandle | nh_ |
Definition at line 39 of file observation_dep.h.
typedef boost::unordered_map< std::string, uint32_t > mdm_library::ObservationDep::DepIndexMap |
Definition at line 44 of file observation_dep.h.
typedef std::vector< std::string > mdm_library::ObservationDep::ObsFactorGlobalDeps |
Definition at line 43 of file observation_dep.h.
typedef std::vector< predicate_manager::NameID > mdm_library::ObservationDep::ObsFactorLocalDeps |
Definition at line 42 of file observation_dep.h.
ObservationDep mdm_library::ObservationDep::add | ( | uint32_t | pm_id, |
std::string | event_name | ||
) | [inline] |
Definition at line 47 of file observation_dep.h.
ObservationDep mdm_library::ObservationDep::add | ( | std::string | event_name | ) | [inline] |
Definition at line 56 of file observation_dep.h.
uint32_t mdm_library::ObservationDep::getDependencyIndex | ( | const std::string & | event_name | ) | [inline] |
Definition at line 72 of file observation_dep.h.
const ObsFactorGlobalDeps mdm_library::ObservationDep::getGlobalDependencies | ( | ) | const [inline] |
Definition at line 68 of file observation_dep.h.
const ObsFactorLocalDeps mdm_library::ObservationDep::getLocalDependencies | ( | ) | const [inline] |
Definition at line 64 of file observation_dep.h.
uint32_t mdm_library::ObservationDep::getNumberOfValues | ( | ) | const [inline] |
Definition at line 82 of file observation_dep.h.
void mdm_library::ObservationDep::registerDependencyName | ( | const std::string & | event_name | ) | [inline, private] |
Definition at line 87 of file observation_dep.h.
Definition at line 102 of file observation_dep.h.
Definition at line 100 of file observation_dep.h.
Definition at line 99 of file observation_dep.h.
Definition at line 97 of file observation_dep.h.