#include <AMIntegrate1stOrder.h>
Public Member Functions | |
AMIntegrate1stOrder (ActionModel *wrapped, double maxAction) | |
virtual | ~AMIntegrate1stOrder () |
AMIntegrate1stOrder (const AMIntegrate1stOrder &)=delete | |
AMIntegrate1stOrder & | operator= (const AMIntegrate1stOrder &)=delete |
AMIntegrate1stOrder (AMIntegrate1stOrder &&)=delete | |
AMIntegrate1stOrder & | operator= (AMIntegrate1stOrder &&)=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 * | maxAction |
MatNd * | integrated_action |
Additional Inherited Members | |
![]() | |
RcsGraph * | graph |
Integrates action values twice and passes them to a wrapped action model.
This allows to use a position based action model like the inverse kinematics, but command it accelerations instead.
Definition at line 45 of file AMIntegrate1stOrder.h.
|
explicit |
Constructor.
Takes ownership of the passed inner action model.
wrapped | inner action model using the integrated action values |
maxAction | maximum action value, reported in action space |
Definition at line 40 of file AMIntegrate1stOrder.cpp.
|
virtual |
Definition at line 52 of file AMIntegrate1stOrder.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 106 of file AMIntegrate1stOrder.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 79 of file AMIntegrate1stOrder.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 58 of file AMIntegrate1stOrder.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 63 of file AMIntegrate1stOrder.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 69 of file AMIntegrate1stOrder.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 95 of file AMIntegrate1stOrder.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 101 of file AMIntegrate1stOrder.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 88 of file AMIntegrate1stOrder.cpp.
|
private |
Definition at line 54 of file AMIntegrate1stOrder.h.
|
private |
Definition at line 51 of file AMIntegrate1stOrder.h.
|
private |
Definition at line 49 of file AMIntegrate1stOrder.h.