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

#include <AMJointControlPosition.h>

Inheritance diagram for Rcs::AMJointControlPosition:
Collaboration diagram for Rcs::AMJointControlPosition:

Public Member Functions

 AMJointControlPosition (RcsGraph *graph)
 
virtual ~AMJointControlPosition ()
 
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
 
virtual std::vector< std::string > getNames () 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
 

Additional Inherited Members

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

Detailed Description

Directly controls joints of the graph by position. Produces joint position commands.

Definition at line 42 of file AMJointControlPosition.h.

Constructor & Destructor Documentation

◆ AMJointControlPosition()

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

Constructor

Parameters
graphgraph being commanded

Definition at line 42 of file AMJointControlPosition.cpp.

◆ ~AMJointControlPosition()

Rcs::AMJointControlPosition::~AMJointControlPosition ( )
virtual

Definition at line 61 of file AMJointControlPosition.cpp.

Member Function Documentation

◆ clone()

ActionModel * Rcs::AMJointControlPosition::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 101 of file AMJointControlPosition.cpp.

◆ computeCommand()

void Rcs::AMJointControlPosition::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 67 of file AMJointControlPosition.cpp.

◆ getMinMax()

void Rcs::AMJointControlPosition::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 72 of file AMJointControlPosition.cpp.

◆ getNames()

std::vector< std::string > Rcs::AMJointControlPosition::getNames ( ) const
virtual

Provides names for each entry of the space.

These are intended for use in python, i.e., for pandas dataframe column names.

Returns
a vector of name strings. Must be of length getDim() or empty.

Reimplemented from Rcs::BoxSpaceProvider.

Definition at line 89 of file AMJointControlPosition.cpp.

◆ getStableAction()

void Rcs::AMJointControlPosition::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 83 of file AMJointControlPosition.cpp.


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