#include <AMJointControlAcceleration.h>
Public Member Functions | |
AMJointControlAcceleration (RcsGraph *graph) | |
virtual | ~AMJointControlAcceleration () |
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 |
![]() | |
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 |
virtual std::vector< std::string > | getNames () const |
Private Attributes | |
MatNd * | M |
MatNd * | h |
MatNd * | F_gravity |
Additional Inherited Members | |
![]() | |
RcsGraph * | graph |
Directly controls the acceleration of unconstrained joints of the graph.
The action acceleration commands are converted to joint torques using inverse dynamics and augmented with gravity compensation.
Definition at line 45 of file AMJointControlAcceleration.h.
|
explicit |
Constructor
graph | graph being commanded |
Definition at line 45 of file AMJointControlAcceleration.cpp.
|
virtual |
Definition at line 65 of file AMJointControlAcceleration.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 111 of file AMJointControlAcceleration.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 73 of file AMJointControlAcceleration.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 99 of file AMJointControlAcceleration.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 105 of file AMJointControlAcceleration.cpp.
|
private |
Definition at line 67 of file AMJointControlAcceleration.h.
|
private |
Definition at line 66 of file AMJointControlAcceleration.h.
|
private |
Definition at line 65 of file AMJointControlAcceleration.h.