RcsPySim
A robot control and simulation library
Rcs::ActionModel Class Referenceabstract

#include <ActionModel.h>

Inheritance diagram for Rcs::ActionModel:
Collaboration diagram for Rcs::ActionModel:

Public Member Functions

 ActionModel (RcsGraph *graph)
 
virtual ~ActionModel ()
 
ActionModelclone () const
 
virtual ActionModelclone (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 ActionModelgetWrappedActionModel () const
 
const ActionModelunwrapAll () const
 
ActionModelunwrapAll ()
 
template<typename AM >
const AM * unwrap () const
 
template<typename AM >
AM * unwrap ()
 
- Public Member Functions inherited from Rcs::BoxSpaceProvider
 BoxSpaceProvider ()
 
virtual ~BoxSpaceProvider ()
 
 BoxSpaceProvider (const BoxSpaceProvider &)=delete
 
BoxSpaceProvideroperator= (const BoxSpaceProvider &)=delete
 
 BoxSpaceProvider (BoxSpaceProvider &&)=delete
 
BoxSpaceProvideroperator= (BoxSpaceProvider &&)=delete
 
const BoxSpacegetSpace () 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
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ActionModel()

Rcs::ActionModel::ActionModel ( RcsGraph *  graph)
explicit

Constructor

Parameters
graphgraph being commanded

Definition at line 39 of file ActionModel.cpp.

◆ ~ActionModel()

Rcs::ActionModel::~ActionModel ( )
virtual

Definition at line 44 of file ActionModel.cpp.

Member Function Documentation

◆ clone() [1/2]

ActionModel* Rcs::ActionModel::clone ( ) const
inline

Create a deep copy of this action model.

Returns
deep copy.

Definition at line 72 of file ActionModel.h.

◆ clone() [2/2]

virtual ActionModel* Rcs::ActionModel::clone ( RcsGraph *  newGraph) const
pure virtual

Create a deep copy of this action model. The graph the action model operates on is replaced with newGraph.

Parameters
newGraphoptionally, replace the graph used with newGraph.
Returns
deep copy with new graph.

Implemented in Rcs::AMIKGeneric, Rcs::AMIntegrate2ndOrder, Rcs::AMIntegrate1stOrder, Rcs::AMDynamicalSystemActivation, Rcs::AMNormalized, Rcs::AMPlateAngPos, Rcs::AMJointControlAcceleration, Rcs::AMJointControlPosition, and Rcs::AMPlatePos5D.

◆ computeCommand()

virtual void Rcs::ActionModel::computeCommand ( MatNd *  q_des,
MatNd *  q_dot_des,
MatNd *  T_des,
const MatNd *  action,
double  dt 
)
pure virtual

Compute the joint commands from a specified action and the current state.

Parameters
[out]q_desdesired joint positions
[out]q_dot_desdesired joint velocities
[out]T_desdesired joint torques
[in]actioninput action values
dtdifference 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.

◆ getGraph()

RcsGraph* Rcs::ActionModel::getGraph ( )
inline

Get the graph this action model operates on.

Definition at line 111 of file ActionModel.h.

◆ getStableAction()

virtual void Rcs::ActionModel::getStableAction ( MatNd *  action) const
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.

Parameters
[out]actionmatrix 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.

◆ getWrappedActionModel()

ActionModel * Rcs::ActionModel::getWrappedActionModel ( ) const
virtual

If this ActionModel is a wrapper for another action model, return the wrapped action model. Otherwise, return NULL.

Returns
wrapped action model or NULL if none.

Reimplemented in Rcs::AMIntegrate2ndOrder, Rcs::AMIntegrate1stOrder, Rcs::AMDynamicalSystemActivation, and Rcs::AMNormalized.

Definition at line 54 of file ActionModel.cpp.

◆ reset()

void Rcs::ActionModel::reset ( )
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.

◆ setGraph()

void Rcs::ActionModel::setGraph ( RcsGraph *  newGraph)
inline

Definition at line 113 of file ActionModel.h.

◆ unwrap() [1/2]

template<typename AM >
const AM* Rcs::ActionModel::unwrap ( ) const
inline

Find action model of a specific type in the wrapper chain.

Template Parameters
AMtype of action model to locate
Returns
typed action model or if not found.

Definition at line 142 of file ActionModel.h.

◆ unwrap() [2/2]

template<typename AM >
AM* Rcs::ActionModel::unwrap ( )
inline

Find action model of a specific type in the wrapper chain.

Template Parameters
AMtype of action model to locate
Returns
typed action model or if not found.

Definition at line 170 of file ActionModel.h.

◆ unwrapAll() [1/2]

const ActionModel * Rcs::ActionModel::unwrapAll ( ) const

Descend the wrapper chain to it's end. Returns this action model if unwrap() returns NULL.

Returns
innermost action model

Definition at line 60 of file ActionModel.cpp.

◆ unwrapAll() [2/2]

ActionModel * Rcs::ActionModel::unwrapAll ( )

Descend the wrapper chain to it's end. Returns this action model if unwrap() returns NULL.

Returns
innermost action model

Definition at line 76 of file ActionModel.cpp.

Member Data Documentation

◆ graph

RcsGraph* Rcs::ActionModel::graph
protected

Definition at line 194 of file ActionModel.h.


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