#include <ActionModel.h>
Public Member Functions | |
ActionModel (RcsGraph *graph) | |
virtual | ~ActionModel () |
ActionModel * | clone () const |
virtual ActionModel * | clone (RcsGraph *newGraph) const =0 |
virtual void | computeCommand (MatNd *q_des, MatNd *q_dot_des, MatNd *T_des, const MatNd *action, double dt)=0 |
virtual void | reset () |
virtual void | getStableAction (MatNd *action) const =0 |
RcsGraph * | getGraph () |
void | setGraph (RcsGraph *newGraph) |
virtual ActionModel * | getWrappedActionModel () const |
const ActionModel * | unwrapAll () const |
ActionModel * | unwrapAll () |
template<typename AM > | |
const AM * | unwrap () const |
template<typename AM > | |
AM * | unwrap () |
![]() | |
BoxSpaceProvider () | |
virtual | ~BoxSpaceProvider () |
BoxSpaceProvider (const BoxSpaceProvider &)=delete | |
BoxSpaceProvider & | operator= (const BoxSpaceProvider &)=delete |
BoxSpaceProvider (BoxSpaceProvider &&)=delete | |
BoxSpaceProvider & | operator= (BoxSpaceProvider &&)=delete |
const BoxSpace * | getSpace () const |
virtual unsigned int | getDim () const =0 |
virtual void | getMinMax (double *min, double *max) const =0 |
virtual std::vector< std::string > | getNames () const |
Protected Attributes | |
RcsGraph * | graph |
The ActionModel component encapsulates the translation from the generic action passed from Python to actual joint space commands required by the physics simulation or the robot. Inherits from BoxSpaceProvider to provide a space for valid action values.
Definition at line 57 of file ActionModel.h.
|
explicit |
|
virtual |
Definition at line 44 of file ActionModel.cpp.
|
inline |
Create a deep copy of this action model.
Definition at line 72 of file ActionModel.h.
|
pure virtual |
Create a deep copy of this action model. The graph the action model operates on is replaced with newGraph.
newGraph | optionally, replace the graph used with newGraph. |
Implemented in Rcs::AMIKGeneric, Rcs::AMIntegrate2ndOrder, Rcs::AMIntegrate1stOrder, Rcs::AMDynamicalSystemActivation, Rcs::AMNormalized, Rcs::AMPlateAngPos, Rcs::AMJointControlAcceleration, Rcs::AMJointControlPosition, and Rcs::AMPlatePos5D.
|
pure virtual |
Compute the joint commands from a specified action and the current state.
[out] | q_des | desired joint positions |
[out] | q_dot_des | desired joint velocities |
[out] | T_des | desired joint torques |
[in] | action | input action values |
dt | difference in time since the last call. |
Implemented in Rcs::AMIKGeneric, Rcs::AMIntegrate2ndOrder, Rcs::AMIntegrate1stOrder, Rcs::AMIKControllerActivation, Rcs::AMDynamicalSystemActivation, Rcs::AMNormalized, Rcs::AMPlateAngPos, Rcs::AMJointControlAcceleration, Rcs::AMPlatePos5D, and Rcs::AMJointControlPosition.
|
inline |
Get the graph this action model operates on.
Definition at line 111 of file ActionModel.h.
|
pure virtual |
Obtain action values which would keep the system in the current state. For action variables which are velocities or accelerations, this should be 0. For action variables which are positions, this should be the current position.
[out] | action | matrix to write the values into |
Implemented in Rcs::AMIKGeneric, Rcs::AMIntegrate2ndOrder, Rcs::AMIntegrate1stOrder, Rcs::AMNormalized, Rcs::AMDynamicalSystemActivation, Rcs::AMIKControllerActivation, Rcs::AMPlateAngPos, Rcs::AMJointControlAcceleration, Rcs::AMPlatePos5D, and Rcs::AMJointControlPosition.
|
virtual |
If this ActionModel is a wrapper for another action model, return the wrapped action model. Otherwise, return NULL.
Reimplemented in Rcs::AMIntegrate2ndOrder, Rcs::AMIntegrate1stOrder, Rcs::AMDynamicalSystemActivation, and Rcs::AMNormalized.
Definition at line 54 of file ActionModel.cpp.
|
virtual |
Called at the start of a rollout to reset any state modified by computeCommand(). This allows to reuse the ActionModel for a new simulation rollout. The graph state will already be reset, so it can be used safely. It will be called before the first rollout too, so it can also be used to setup internals that depend on operations in subclass constructors.
Reimplemented in Rcs::AMIntegrate2ndOrder, Rcs::AMIntegrate1stOrder, Rcs::AMNormalized, Rcs::AMDynamicalSystemActivation, Rcs::ActionModelIK, Rcs::AMIKControllerActivation, and Rcs::AMPlateAngPos.
Definition at line 49 of file ActionModel.cpp.
|
inline |
Definition at line 113 of file ActionModel.h.
|
inline |
Find action model of a specific type in the wrapper chain.
AM | type of action model to locate |
Definition at line 142 of file ActionModel.h.
|
inline |
Find action model of a specific type in the wrapper chain.
AM | type of action model to locate |
Definition at line 170 of file ActionModel.h.
const ActionModel * Rcs::ActionModel::unwrapAll | ( | ) | const |
Descend the wrapper chain to it's end. Returns this action model if unwrap() returns NULL.
Definition at line 60 of file ActionModel.cpp.
ActionModel * Rcs::ActionModel::unwrapAll | ( | ) |
Descend the wrapper chain to it's end. Returns this action model if unwrap() returns NULL.
Definition at line 76 of file ActionModel.cpp.
|
protected |
Definition at line 194 of file ActionModel.h.