#include <AMPlateAngPos.h>
Public Member Functions | |
AMPlateAngPos (RcsGraph *graph) | |
virtual | ~AMPlateAngPos () |
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 |
![]() | |
ActionModelIK (RcsGraph *graph) | |
ActionModelIK (RcsGraph *graph, std::vector< Task *> tasks) | |
virtual | ~ActionModelIK () |
const ControllerBase * | getController () const |
RcsGraph * | getDesiredGraph () const |
void | setDesiredGraph (RcsGraph *newGraph) |
void | setupCollisionModel (const RcsCollisionMdl *modelToCopy) |
void | computeIK (MatNd *q_des, MatNd *q_dot_des, MatNd *T_des, const MatNd *x_des, double dt) |
void | computeIKVel (MatNd *q_des, MatNd *q_dot_des, MatNd *T_des, const MatNd *x_dot_des, double dt) |
![]() | |
ActionModel (RcsGraph *graph) | |
virtual | ~ActionModel () |
ActionModel * | clone () const |
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 |
Protected Attributes | |
MatNd * | x_des |
![]() | |
RcsGraph * | desiredGraph |
RcsCollisionMdl * | collisionMdl |
MatNd * | dx_des |
MatNd * | dH |
MatNd * | dq_ref |
![]() | |
RcsGraph * | graph |
Additional Inherited Members | |
![]() | |
void | addTask (Task *task) |
void | addFixedTask (Task *task, MatNd *value) |
unsigned int | getNumActiveTasks () const |
void | ikFromDX (MatNd *q_des, MatNd *q_dot_des, double dt) const |
Action model controlling the plate's angular position in the ball-on-plate task. The action vector contains the angular position around the x and y axes. Produces joint position commands.
Definition at line 44 of file AMPlateAngPos.h.
|
explicit |
Constructor. The passed graph must contain a body named "Plate".
graph | graph being commanded |
Definition at line 41 of file AMPlateAngPos.cpp.
|
virtual |
Definition at line 55 of file AMPlateAngPos.cpp.
|
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 112 of file AMPlateAngPos.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 AMPlateAngPos.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 60 of file AMPlateAngPos.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 65 of file AMPlateAngPos.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 74 of file AMPlateAngPos.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 99 of file AMPlateAngPos.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 from Rcs::ActionModelIK.
Definition at line 91 of file AMPlateAngPos.cpp.
|
protected |
Definition at line 74 of file AMPlateAngPos.h.