#include <action_layer.h>
Public Types | |
typedef std::vector < boost::function< void() > > | ActionCallbacksVector |
typedef std::map< std::string, size_t > | ActionIDMap |
typedef std::vector< std::size_t > | ActionIDVector |
typedef std::vector< std::string > | ActionNamesVector |
typedef std::vector< size_t > | ActionSizesVector |
Public Member Functions | |
ActionLayer () | |
ActionLayer (const FactoredSymbolMetadataConstPtr &action_metadata) | |
ActionLayer (ros::CallbackQueueInterface *queue) | |
void | actionMetadataCallback (const mdm_library::FactoredSymbolMetadataConstPtr &msg) |
void | actionSymbolCallback (const mdm_library::ActionSymbolConstPtr &msg) |
void | addAction (boost::function< void() > callback) |
void | addAction (boost::function< void() > callback, const std::string &action_name) |
uint32_t | jointToIndividualAction (const uint32_t joint_action) |
Private Attributes | |
ActionCallbacksVector | action_callbacks_ |
ActionIDVector | action_ids_ |
ros::Subscriber | action_metadata_sub_ |
ActionSizesVector | action_sizes_ |
ros::Subscriber | action_sub_ |
uint32_t | cached_sizes_prod_ |
ActionNamesVector | local_action_names_ |
int | mdm_agent_index_ |
ActionIDMap | named_action_ids_ |
ros::NodeHandle | nh_ |
ActionSymbolConstPtr | pending_action_ |
bool | using_named_actions_ |
The ActionLayer class provides the tools to abstract actions as generic functions. Each action that is received by an ActionLayer triggers an agent-specific "action callback". ActionLayers subscribe to the "action" and "action_metadata" topics in their node's namespace. The former contains the actual actions that should be performed by the agent, as integer values, while the latter specifies the number of actions of each agent and possibly their names. In most cases, a Control Layer running on the same namespace will be publishing to these input topics transparently.
Definition at line 53 of file action_layer.h.
typedef std::vector<boost::function<void () > > mdm_library::ActionLayer::ActionCallbacksVector |
Action callbacks do not return any values or accept any arguments (they should be bound, if needed).
Definition at line 59 of file action_layer.h.
typedef std::map<std::string, size_t> mdm_library::ActionLayer::ActionIDMap |
Definition at line 65 of file action_layer.h.
typedef std::vector<std::size_t> mdm_library::ActionLayer::ActionIDVector |
Definition at line 67 of file action_layer.h.
typedef std::vector<std::string> mdm_library::ActionLayer::ActionNamesVector |
Type for the set of action names.
Definition at line 63 of file action_layer.h.
typedef std::vector<size_t> mdm_library::ActionLayer::ActionSizesVector |
Type for the set containing the number of actions of each agent. This is necessary to convert joint action indexes into local action indexes.
Definition at line 74 of file action_layer.h.
The default Action Layer constructor, which doesn't take any arguments. It gets the action metadata from an associated Control Layer, through action_metadata_sub_.
Definition at line 37 of file action_layer.cpp.
ActionLayer::ActionLayer | ( | const FactoredSymbolMetadataConstPtr & | action_metadata | ) |
An optional Action Layer constructor that takes action metadata directly.
action_metadata | The action metadata (number of actions and respective names) for this MDM agent. See msg/ActionMetadata.msg for details. |
Definition at line 58 of file action_layer.cpp.
This constructor allows the action callback to be added to a custom queue. This is useful for multi-threaded nodes or those with custom spinning strategies.
Definition at line 80 of file action_layer.cpp.
void ActionLayer::actionMetadataCallback | ( | const mdm_library::FactoredSymbolMetadataConstPtr & | msg | ) |
Callback for action metadata coming from the Control Layer.
if not using named actions, the ID of each action is its position.
when using named actions, each action is paired with an ID that was specified when it was added to the Layer.
Definition at line 195 of file action_layer.cpp.
void ActionLayer::actionSymbolCallback | ( | const mdm_library::ActionSymbolConstPtr & | msg | ) |
Callback for actions coming from the Control Layer.
Definition at line 141 of file action_layer.cpp.
void ActionLayer::addAction | ( | boost::function< void() > | callback | ) |
Add an action to this Action Layer with the specified callback. Actions must be added before spinning the thread containing the declaration of this Action Layer. Actions are identified by the order in which they are added to the Action Layer.
callback | The function to be performed when this action is received in through action_sub_. |
Definition at line 104 of file action_layer.cpp.
void mdm_library::ActionLayer::addAction | ( | boost::function< void() > | callback, |
const std::string & | action_name | ||
) |
uint32_t ActionLayer::jointToIndividualAction | ( | const uint32_t | joint_action | ) |
Definition at line 266 of file action_layer.cpp.
The set of action callbacks
Definition at line 125 of file action_layer.h.
Definition at line 129 of file action_layer.h.
The subscriber to the "action_metadata" topic in the local (public) namespace, in which the action metadata will be received.
Definition at line 122 of file action_layer.h.
The ordered set containing the number of actions of each agent contemplated by the Control Layer.
Definition at line 132 of file action_layer.h.
The subscriber to the "action" topic in the local (public) namespace, in which the action information will be received.
Definition at line 118 of file action_layer.h.
uint32_t mdm_library::ActionLayer::cached_sizes_prod_ [private] |
Definition at line 134 of file action_layer.h.
The set of local action names.
Definition at line 127 of file action_layer.h.
int mdm_library::ActionLayer::mdm_agent_index_ [private] |
The index of this agent with respect to the Decision-Theoretic model represented by the Control Layer.
Definition at line 142 of file action_layer.h.
Definition at line 128 of file action_layer.h.
ros::NodeHandle mdm_library::ActionLayer::nh_ [private] |
Definition at line 113 of file action_layer.h.
ActionSymbolConstPtr mdm_library::ActionLayer::pending_action_ [private] |
A failsafe for situations in which an action is received -before- the metadata is known. That action is saved and executed once the metadata is received.
Definition at line 139 of file action_layer.h.
bool mdm_library::ActionLayer::using_named_actions_ [private] |
Definition at line 144 of file action_layer.h.