Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
mdm_library::ControlLayerBase Class Reference

#include <control_layer_base.h>

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

List of all members.

Public Types

enum  CONTROLLER_STATUS { STOPPED, STARTED }

Public Member Functions

 ControlLayerBase (const CONTROLLER_STATUS initial_status=STARTED)
uint32_t getDecisionEpisode ()
uint32_t getDecisionHorizon ()
CONTROLLER_STATUS getStatus ()
virtual void resetController ()
void resetDecisionEpisode ()
virtual void startController ()
virtual void stopController ()

Protected Member Functions

uint32_t incrementDecisionEpisode ()
void setStatus (const CONTROLLER_STATUS status)

Protected Attributes

ros::NodeHandle nh_

Private Member Functions

bool resetCallback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
bool startCallback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
bool stopCallback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)

Private Attributes

uint32_t decision_episode_
uint32_t decision_horizon_
ros::ServiceServer reset_srv_
ros::ServiceServer start_srv_
CONTROLLER_STATUS status_
ros::ServiceServer stop_srv_

Detailed Description

The ControlLayerBase class provides the functionalities that are common to all MDM controllers. These include:

Definition at line 56 of file control_layer_base.h.


Member Enumeration Documentation

A simple flag to identify whether a controller is active or not. All controllers should allow external stop / start / reset commands.

Enumerator:
STOPPED 
STARTED 

Definition at line 63 of file control_layer_base.h.


Constructor & Destructor Documentation

Default constructor.

Parameters:
initial_statusThe initial status of this controller. By default, Control Layers are auto-started. If the initial status is STOPPED, it must be started externally (this is desirable for lower-level controllers in hierarchical systems).

Definition at line 36 of file control_layer_base.cpp.


Member Function Documentation

Returns the current decision step number of this controller (mostly for logging purposes).

Definition at line 131 of file control_layer_base.cpp.

Returns the horizon of this controller. The MADP-defined MAXHORIZON should be interpreted as infinite.

Definition at line 149 of file control_layer_base.cpp.

Returns the current status of this controller.

Definition at line 140 of file control_layer_base.cpp.

Increments the decision step number. If the step number reaches the problem horizon, the controller is reset.

Definition at line 167 of file control_layer_base.cpp.

bool ControlLayerBase::resetCallback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
) [private]

The callback for the "reset" service (Empty service type).

See also:
reset_srv_

Definition at line 79 of file control_layer_base.cpp.

Stops and re-starts the controller.

See also:
stopController(), startController()

This is primarily meant for controllers with reimplemented stop/start functions.

Definition at line 110 of file control_layer_base.cpp.

Resets the decision step number of this controller back to 0.

Definition at line 158 of file control_layer_base.cpp.

void ControlLayerBase::setStatus ( const CONTROLLER_STATUS  status) [protected]

Allows direct access to the status of this controller. This can be used to reimplement the start / stop / reset functions by derived classes.

Definition at line 121 of file control_layer_base.cpp.

bool ControlLayerBase::startCallback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
) [private]

The callback for the "start" service (Empty service type).

See also:
start_srv_

Definition at line 69 of file control_layer_base.cpp.

Start this controller. The decision step number is set to 0 whenever a controller is started.

See also:
stopController, resetController()

Reimplemented in mdm_library::ControllerEventPOMDP, and mdm_library::ControllerTimedPOMDP.

Definition at line 100 of file control_layer_base.cpp.

bool ControlLayerBase::stopCallback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
) [private]

The callback for the "stop" service (Empty service type).

See also:
stop_srv_

Definition at line 59 of file control_layer_base.cpp.

Stop this controller. When stopped, a controller does not update internally, not does it output any actions. Be mindful that, for partially observable models, after stopping a controller, you may need to feed the correct initial belief state to the controller before starting it again.

See also:
startController(), resetController()

Definition at line 91 of file control_layer_base.cpp.


Member Data Documentation

The decision step number.

Definition at line 136 of file control_layer_base.h.

The decision horizon. While, typically, infinite-horizon policies are used for robotic agents, MDM also contemplates the possibility of using finite-horizon controllers.

Definition at line 140 of file control_layer_base.h.

Definition at line 114 of file control_layer_base.h.

The "reset" service server. This is an empty-type service in the namespace of the node containing the Control Layer, which can be used to reset (stop & start) the controller.

Definition at line 156 of file control_layer_base.h.

The "start" service server. This is an empty-type service in the namespace of the node containing the Control Layer, which can be used to start the controller.

Definition at line 151 of file control_layer_base.h.

The status of this controller.

Definition at line 134 of file control_layer_base.h.

The "stop" service server. This is an empty-type service in the namespace of the node containing the Control Layer, which can be used to stop the controller.

Definition at line 146 of file control_layer_base.h.


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