#include <ActionModelIK.h>
Public Member Functions | |
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 | getStableAction (MatNd *action) const |
![]() | |
ActionModelIK (RcsGraph *graph) | |
ActionModelIK (RcsGraph *graph, std::vector< Task *> tasks) | |
virtual | ~ActionModelIK () |
virtual void | reset () |
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 |
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 |
![]() | |
RcsGraph * | desiredGraph |
RcsCollisionMdl * | collisionMdl |
MatNd * | dx_des |
MatNd * | dH |
MatNd * | dq_ref |
![]() | |
RcsGraph * | graph |
Generic IK-based action model.
Here, the action is used directly as desired task space state for the IK. You need to add your tasks to the controller before using it:
AMIKGeneric* am = new AMIKGeneric(graph); am->addTask(new TaskXY(...)); am->reset(); // now it can be used, and no new tasks must be added.
Definition at line 167 of file ActionModelIK.h.
|
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 367 of file ActionModelIK.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.
Reimplemented in Rcs::AMIKControllerActivation.
Definition at line 338 of file ActionModelIK.cpp.
|
virtual |
Provides the number of elements in the space. Since the BoxSpace object will be cached, this must not change.
Implements Rcs::BoxSpaceProvider.
Reimplemented in Rcs::AMIKControllerActivation.
Definition at line 306 of file ActionModelIK.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.
Reimplemented in Rcs::AMIKControllerActivation.
Definition at line 311 of file ActionModelIK.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.
Reimplemented in Rcs::AMIKControllerActivation.
Definition at line 325 of file ActionModelIK.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.
Reimplemented in Rcs::AMIKControllerActivation.
Definition at line 354 of file ActionModelIK.cpp.