#include <AMJointControlPosition.h>
Public Member Functions | |
AMJointControlPosition (RcsGraph *graph) | |
virtual | ~AMJointControlPosition () |
virtual ActionModel * | clone (RcsGraph *newGraph) const |
virtual void | computeCommand (MatNd *q_des, MatNd *q_dot_des, MatNd *T_des, const MatNd *action, double dt) |
virtual void | getMinMax (double *min, double *max) const |
virtual void | getStableAction (MatNd *action) const |
virtual std::vector< std::string > | getNames () const |
![]() | |
AMJointControl (RcsGraph *graph) | |
virtual | ~AMJointControl () |
virtual unsigned int | getDim () const |
![]() | |
ActionModel (RcsGraph *graph) | |
virtual | ~ActionModel () |
ActionModel * | clone () const |
virtual void | reset () |
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 |
Additional Inherited Members | |
![]() | |
RcsGraph * | graph |
Directly controls joints of the graph by position. Produces joint position commands.
Definition at line 42 of file AMJointControlPosition.h.
|
explicit |
Constructor
graph | graph being commanded |
Definition at line 42 of file AMJointControlPosition.cpp.
|
virtual |
Definition at line 61 of file AMJointControlPosition.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 101 of file AMJointControlPosition.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 67 of file AMJointControlPosition.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 72 of file AMJointControlPosition.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 89 of file AMJointControlPosition.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 83 of file AMJointControlPosition.cpp.