RcsPySim
A robot control and simulation library
Rcs::AMJointControlAcceleration Class Reference

#include <AMJointControlAcceleration.h>

Inheritance diagram for Rcs::AMJointControlAcceleration:
Collaboration diagram for Rcs::AMJointControlAcceleration:

Public Member Functions

 AMJointControlAcceleration (RcsGraph *graph)
 
virtual ~AMJointControlAcceleration ()
 
virtual ActionModelclone (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
 
- Public Member Functions inherited from Rcs::AMJointControl
 AMJointControl (RcsGraph *graph)
 
virtual ~AMJointControl ()
 
virtual unsigned int getDim () const
 
- Public Member Functions inherited from Rcs::ActionModel
 ActionModel (RcsGraph *graph)
 
virtual ~ActionModel ()
 
ActionModelclone () const
 
virtual void reset ()
 
RcsGraph * getGraph ()
 
void setGraph (RcsGraph *newGraph)
 
virtual ActionModelgetWrappedActionModel () const
 
const ActionModelunwrapAll () const
 
ActionModelunwrapAll ()
 
template<typename AM >
const AM * unwrap () const
 
template<typename AM >
AM * unwrap ()
 
- Public Member Functions inherited from Rcs::BoxSpaceProvider
 BoxSpaceProvider ()
 
virtual ~BoxSpaceProvider ()
 
 BoxSpaceProvider (const BoxSpaceProvider &)=delete
 
BoxSpaceProvideroperator= (const BoxSpaceProvider &)=delete
 
 BoxSpaceProvider (BoxSpaceProvider &&)=delete
 
BoxSpaceProvideroperator= (BoxSpaceProvider &&)=delete
 
const BoxSpacegetSpace () const
 
virtual std::vector< std::string > getNames () const
 

Private Attributes

MatNd * M
 
MatNd * h
 
MatNd * F_gravity
 

Additional Inherited Members

- Protected Attributes inherited from Rcs::ActionModel
RcsGraph * graph
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ AMJointControlAcceleration()

Rcs::AMJointControlAcceleration::AMJointControlAcceleration ( RcsGraph *  graph)
explicit

Constructor

Parameters
graphgraph being commanded

Definition at line 45 of file AMJointControlAcceleration.cpp.

◆ ~AMJointControlAcceleration()

Rcs::AMJointControlAcceleration::~AMJointControlAcceleration ( )
virtual

Definition at line 65 of file AMJointControlAcceleration.cpp.

Member Function Documentation

◆ clone()

ActionModel * Rcs::AMJointControlAcceleration::clone ( RcsGraph *  newGraph) const
virtual

Create a deep copy of this action model. The graph the action model operates on is replaced with newGraph.

Parameters
newGraphoptionally, replace the graph used with newGraph.
Returns
deep copy with new graph.

Implements Rcs::ActionModel.

Definition at line 111 of file AMJointControlAcceleration.cpp.

◆ computeCommand()

void Rcs::AMJointControlAcceleration::computeCommand ( MatNd *  q_des,
MatNd *  q_dot_des,
MatNd *  T_des,
const MatNd *  action,
double  dt 
)
virtual

Compute the joint commands from a specified action and the current state.

Parameters
[out]q_desdesired joint positions
[out]q_dot_desdesired joint velocities
[out]T_desdesired joint torques
[in]actioninput action values
dtdifference in time since the last call.

Implements Rcs::ActionModel.

Definition at line 73 of file AMJointControlAcceleration.cpp.

◆ getMinMax()

void Rcs::AMJointControlAcceleration::getMinMax ( double *  min,
double *  max 
) const
virtual

Provides minimum and maximum values for the space.

The passed arrays will be large enough to hold getDim() values.

Parameters
[out]minminimum value storage
[out]maxmaximum value storage

Implements Rcs::BoxSpaceProvider.

Definition at line 99 of file AMJointControlAcceleration.cpp.

◆ getStableAction()

void Rcs::AMJointControlAcceleration::getStableAction ( MatNd *  action) const
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.

Parameters
[out]actionmatrix to write the values into

Implements Rcs::ActionModel.

Definition at line 105 of file AMJointControlAcceleration.cpp.

Member Data Documentation

◆ F_gravity

MatNd* Rcs::AMJointControlAcceleration::F_gravity
private

Definition at line 67 of file AMJointControlAcceleration.h.

◆ h

MatNd* Rcs::AMJointControlAcceleration::h
private

Definition at line 66 of file AMJointControlAcceleration.h.

◆ M

MatNd* Rcs::AMJointControlAcceleration::M
private

Definition at line 65 of file AMJointControlAcceleration.h.


The documentation for this class was generated from the following files: