#include <controller_mdp.h>
Public Member Functions | |
void | act (const uint32_t state) |
ControllerMDP (const std::string &policy_file_path, const CONTROLLER_STATUS initial_status=STARTED) | |
size_t | getNumberOfActions () |
size_t | getNumberOfStates () |
void | loadPolicyVector (const std::string &policy_vector_path) |
void | loadRewardMatrix (const std::string &reward_matrix_path) |
virtual void | stateCallback (const WorldSymbolConstPtr &msg)=0 |
Protected Member Functions | |
void | publishAction (uint32_t a) |
void | publishReward (uint32_t s, uint32_t a) |
Protected Attributes | |
ros::Publisher | action_pub_ |
boost::shared_ptr< DecPOMDPLoader > | loader_ |
size_t | number_of_actions_ |
size_t | number_of_states_ |
boost::shared_ptr< MDPPolicy > | policy_ptr_ |
boost::shared_ptr< RewardModel > | R_ptr_ |
ros::Publisher | reward_pub_ |
ros::Subscriber | state_sub_ |
ControllerMDP is a base class for Control Layers based on MDPs. This is an abstract class. You must implement the state callback behavior depending on the particular requirements of your system.
Definition at line 48 of file controller_mdp.h.
ControllerMDP::ControllerMDP | ( | const std::string & | policy_file_path, |
const CONTROLLER_STATUS | initial_status = STARTED |
||
) |
This constructor will not publish problem metadata or reward (you will have to do it manually).
Definition at line 73 of file controller_mdp.cpp.
void ControllerMDP::act | ( | const uint32_t | state | ) |
A step of the decision making process. Selects the best action at the current state, and publishes it to the "action" topic on the namespace of the respective node. Also publishes the reward for this state-action pair, if it is available, to the "reward" topic.
Definition at line 177 of file controller_mdp.cpp.
size_t ControllerMDP::getNumberOfActions | ( | ) |
Returns the number of actions of this MDP.
Definition at line 239 of file controller_mdp.cpp.
size_t ControllerMDP::getNumberOfStates | ( | ) |
Returns the number of states of this MDP.
Definition at line 248 of file controller_mdp.cpp.
void ControllerMDP::loadPolicyVector | ( | const std::string & | policy_vector_path | ) |
We need to look at the size of the policy to figure out if it is deterministic or stochastic
Definition at line 93 of file controller_mdp.cpp.
void ControllerMDP::loadRewardMatrix | ( | const std::string & | reward_matrix_path | ) |
Definition at line 147 of file controller_mdp.cpp.
void ControllerMDP::publishAction | ( | uint32_t | a | ) | [protected] |
Publishes an action.
Definition at line 211 of file controller_mdp.cpp.
void ControllerMDP::publishReward | ( | uint32_t | s, |
uint32_t | a | ||
) | [protected] |
Publishes the reward of a state-action pair.
no reward info available.
Definition at line 223 of file controller_mdp.cpp.
virtual void mdm_library::ControllerMDP::stateCallback | ( | const WorldSymbolConstPtr & | msg | ) | [pure virtual] |
Pure virtual callback to state information. Derived classes can define an execution strategy (synchronous or event-driven) by implementing this method accordingly.
Implemented in mdm_library::ControllerEventMDP, and mdm_library::ControllerTimedMDP.
Publisher to the "action" topic, where the action information will be passed on to an Action Layer.
Definition at line 109 of file controller_mdp.h.
boost::shared_ptr<DecPOMDPLoader> mdm_library::ControllerMDP::loader_ [protected] |
The parser for the MDP problem file.
Definition at line 100 of file controller_mdp.h.
size_t mdm_library::ControllerMDP::number_of_actions_ [protected] |
The number of actions of this MDP.
Definition at line 104 of file controller_mdp.h.
size_t mdm_library::ControllerMDP::number_of_states_ [protected] |
The number of states of this MDP.
Definition at line 102 of file controller_mdp.h.
boost::shared_ptr<MDPPolicy> mdm_library::ControllerMDP::policy_ptr_ [protected] |
Definition at line 98 of file controller_mdp.h.
boost::shared_ptr<RewardModel> mdm_library::ControllerMDP::R_ptr_ [protected] |
Definition at line 97 of file controller_mdp.h.
Publisher to the "reward" topic, where reward information can be acessed for reinforcement learning or logging purposes.
Definition at line 111 of file controller_mdp.h.
Subscriber to the "state" topic, where the state information will be published by a State Layer.
Definition at line 107 of file controller_mdp.h.