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

#include <AMPlatePos5D.h>

Inheritance diagram for Rcs::AMPlatePos5D:
Collaboration diagram for Rcs::AMPlatePos5D:

Public Member Functions

 AMPlatePos5D (RcsGraph *graph)
 
virtual ~AMPlatePos5D ()
 
virtual ActionModelclone (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
 
- Public Member Functions inherited from Rcs::ActionModelIK
 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)
 
- Public Member Functions inherited from Rcs::ActionModel
 ActionModel (RcsGraph *graph)
 
virtual ~ActionModel ()
 
ActionModelclone () const
 
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 Member Functions inherited from Rcs::ActionModelIK
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
 
- Protected Attributes inherited from Rcs::ActionModelIK
RcsGraph * desiredGraph
 
RcsCollisionMdl * collisionMdl
 
MatNd * dx_des
 
MatNd * dH
 
MatNd * dq_ref
 
- Protected Attributes inherited from Rcs::ActionModel
RcsGraph * graph
 

Detailed Description

Controls X, Y, Z position and X, Y rotation of the Plate body relative to it's initial position.

Definition at line 43 of file AMPlatePos5D.h.

Constructor & Destructor Documentation

◆ AMPlatePos5D()

Rcs::AMPlatePos5D::AMPlatePos5D ( RcsGraph *  graph)

Definition at line 46 of file AMPlatePos5D.cpp.

◆ ~AMPlatePos5D()

Rcs::AMPlatePos5D::~AMPlatePos5D ( )
virtual

Definition at line 65 of file AMPlatePos5D.cpp.

Member Function Documentation

◆ clone()

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

◆ computeCommand()

void Rcs::AMPlatePos5D::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 100 of file AMPlatePos5D.cpp.

◆ getDim()

unsigned int Rcs::AMPlatePos5D::getDim ( ) const
virtual

Provides the number of elements in the space. Since the BoxSpace object will be cached, this must not change.

Returns
number of elements for the space.

Implements Rcs::BoxSpaceProvider.

Definition at line 69 of file AMPlatePos5D.cpp.

◆ getMinMax()

void Rcs::AMPlatePos5D::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 74 of file AMPlatePos5D.cpp.

◆ getNames()

std::vector< std::string > Rcs::AMPlatePos5D::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 95 of file AMPlatePos5D.cpp.

◆ getStableAction()

void Rcs::AMPlatePos5D::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 111 of file AMPlatePos5D.cpp.


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