Public Member Functions | Private Member Functions
mdm_library::ControllerEventPOMDP Class Reference

#include <controller_event_pomdp.h>

Inheritance diagram for mdm_library::ControllerEventPOMDP:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 ControllerEventPOMDP (const std::string &problem_file, const std::string &value_function_file, const CONTROLLER_STATUS initial_status=STARTED)
void startController ()

Private Member Functions

void observationCallback (const WorldSymbolConstPtr &msg)

Detailed Description

ControllerEventPOMDP implements an asynchronous POMDP controller, driven by incoming observations.

Definition at line 39 of file controller_event_pomdp.h.


Constructor & Destructor Documentation

ControllerEventPOMDP::ControllerEventPOMDP ( const std::string &  problem_file,
const std::string &  value_function_file,
const CONTROLLER_STATUS  initial_status = STARTED 
)

Constructor. When using this form, the reward function of the MDP model is known to the controller, and so reward can be logged in real-time. Furthermore, the metadata of the model is parsed automatically and passed to the Action Layer.

Parameters:
problem_fileA file defining the MDP, in any MADP-compatible format.
q_value_function_fileA file defining the Q-value function of this MDP, as a whitespace-separated |S|x|A| matrix of floating point numbers. If you have an explicit policy instead, convert it to a matrix where the only non-zero entries exist in the specified (s,a) pairs.
initial_status(optional) The initial status of this controller.

Sparse JointBeliefEventDriven type NYI. Assign corresponding belief type then.

<0 means no false negative

this is only needed by the Planner, which is in turn required by the QAV

In the general case, we won't use it, but it does allow for forward-search planning.

only considering infinite-horizon models at the moment.

Sets initial belief to the loader's ISD;

Definition at line 37 of file controller_event_pomdp.cpp.


Member Function Documentation

void ControllerEventPOMDP::observationCallback ( const WorldSymbolConstPtr &  msg) [private, virtual]

Callback for observation data. A new decision step is taken whenever an observation is received.

Implements mdm_library::ControllerPOMDP.

Definition at line 90 of file controller_event_pomdp.cpp.

Start this controller. This reimplements ControlLayerBase::startController, since it must also reset the belief state of the process to the initial state distribution.

calling first decision at startup, observation is irrelevant.

Reimplemented from mdm_library::ControlLayerBase.

Definition at line 99 of file controller_event_pomdp.cpp.


The documentation for this class was generated from the following files:


mdm_library
Author(s): Joao Messias
autogenerated on Wed Aug 26 2015 12:28:41