#include <AMNormalized.h>
Public Member Functions | |
AMNormalized (ActionModel *wrapped) | |
virtual | ~AMNormalized () |
AMNormalized (const AMNormalized &)=delete | |
AMNormalized & | operator= (const AMNormalized &)=delete |
AMNormalized (AMNormalized &&)=delete | |
AMNormalized & | operator= (AMNormalized &&)=delete |
virtual ActionModel * | clone (RcsGraph *newGraph) const |
virtual unsigned int | getDim () const |
virtual void | getMinMax (double *min, double *max) const |
virtual std::vector< std::string > | getNames () const |
virtual void | computeCommand (MatNd *q_des, MatNd *q_dot_des, MatNd *T_des, const MatNd *action, double dt) |
virtual void | reset () |
virtual void | getStableAction (MatNd *action) const |
virtual ActionModel * | getWrappedActionModel () const |
![]() | |
ActionModel (RcsGraph *graph) | |
virtual | ~ActionModel () |
ActionModel * | clone () const |
RcsGraph * | getGraph () |
void | setGraph (RcsGraph *newGraph) |
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 |
Private Attributes | |
ActionModel * | wrapped |
MatNd * | scale |
MatNd * | shift |
Additional Inherited Members | |
![]() | |
RcsGraph * | graph |
Wraps another action model to accept normalized action values in the range [-1, 1]. The passed action values are denormalized and then passed to the wrapped action model.
Definition at line 43 of file AMNormalized.h.
Rcs::AMNormalized::AMNormalized | ( | ActionModel * | wrapped | ) |
Definition at line 39 of file AMNormalized.cpp.
|
virtual |
Definition at line 59 of file AMNormalized.cpp.
|
delete |
|
delete |
|
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. |
Implements Rcs::ActionModel.
Definition at line 122 of file AMNormalized.cpp.
|
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. |
Implements Rcs::ActionModel.
Definition at line 80 of file AMNormalized.cpp.
|
virtual |
Provides the number of elements in the space. Since the BoxSpace object will be cached, this must not change.
Implements Rcs::BoxSpaceProvider.
Definition at line 64 of file AMNormalized.cpp.
|
virtual |
Provides minimum and maximum values for the space.
The passed arrays will be large enough to hold getDim() values.
[out] | min | minimum value storage |
[out] | max | maximum value storage |
Implements Rcs::BoxSpaceProvider.
Definition at line 69 of file AMNormalized.cpp.
|
virtual |
Provides names for each entry of the space.
These are intended for use in python, i.e., for pandas dataframe column names.
Reimplemented from Rcs::BoxSpaceProvider.
Definition at line 75 of file AMNormalized.cpp.
|
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 |
Implements Rcs::ActionModel.
Definition at line 107 of file AMNormalized.cpp.
|
virtual |
If this ActionModel is a wrapper for another action model, return the wrapped action model. Otherwise, return NULL.
Reimplemented from Rcs::ActionModel.
Definition at line 117 of file AMNormalized.cpp.
|
delete |
|
delete |
|
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 from Rcs::ActionModel.
Definition at line 102 of file AMNormalized.cpp.
|
private |
Definition at line 49 of file AMNormalized.h.
|
private |
Definition at line 51 of file AMNormalized.h.
|
private |
Definition at line 47 of file AMNormalized.h.