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

#include <AMIntegrate2ndOrder.h>

Inheritance diagram for Rcs::AMIntegrate2ndOrder:
Collaboration diagram for Rcs::AMIntegrate2ndOrder:

Public Member Functions

 AMIntegrate2ndOrder (ActionModel *wrapped, double maxAction)
 
 AMIntegrate2ndOrder (ActionModel *wrapped, MatNd *maxAction)
 
virtual ~AMIntegrate2ndOrder ()
 
 AMIntegrate2ndOrder (const AMIntegrate2ndOrder &)=delete
 
AMIntegrate2ndOrderoperator= (const AMIntegrate2ndOrder &)=delete
 
 AMIntegrate2ndOrder (AMIntegrate2ndOrder &&)=delete
 
AMIntegrate2ndOrderoperator= (AMIntegrate2ndOrder &&)=delete
 
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 reset ()
 
virtual void getStableAction (MatNd *action) const
 
virtual ActionModelgetWrappedActionModel () const
 
- Public Member Functions inherited from Rcs::ActionModel
 ActionModel (RcsGraph *graph)
 
virtual ~ActionModel ()
 
ActionModelclone () const
 
RcsGraph * getGraph ()
 
void setGraph (RcsGraph *newGraph)
 
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
 

Private Attributes

ActionModelwrapped
 
MatNd * maxAction
 
MatNd * integrated_action
 
MatNd * integrated_action_dot
 

Additional Inherited Members

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

Detailed Description

Integrates action values once and passes them to a wrapped action model.

This allows to use a position based action model like the inverse kinematics, but command it velocities instead.

Definition at line 45 of file AMIntegrate2ndOrder.h.

Constructor & Destructor Documentation

◆ AMIntegrate2ndOrder() [1/4]

Rcs::AMIntegrate2ndOrder::AMIntegrate2ndOrder ( ActionModel wrapped,
double  maxAction 
)

Constructor.

Takes ownership of the passed inner action model.

Parameters
wrappedinner action model
maxActionmaximum action value, reported in the action space.

Definition at line 42 of file AMIntegrate2ndOrder.cpp.

◆ AMIntegrate2ndOrder() [2/4]

Rcs::AMIntegrate2ndOrder::AMIntegrate2ndOrder ( ActionModel wrapped,
MatNd *  maxAction 
)

Constructor.

Takes ownership of the passed inner action model.

Parameters
wrappedinner action model
maxActionmaximum action values, size must match wrapped->getDim(). Does not take ownership, values are copied.

Definition at line 55 of file AMIntegrate2ndOrder.cpp.

◆ ~AMIntegrate2ndOrder()

Rcs::AMIntegrate2ndOrder::~AMIntegrate2ndOrder ( )
virtual

Definition at line 69 of file AMIntegrate2ndOrder.cpp.

◆ AMIntegrate2ndOrder() [3/4]

Rcs::AMIntegrate2ndOrder::AMIntegrate2ndOrder ( const AMIntegrate2ndOrder )
delete

◆ AMIntegrate2ndOrder() [4/4]

Rcs::AMIntegrate2ndOrder::AMIntegrate2ndOrder ( AMIntegrate2ndOrder &&  )
delete

Member Function Documentation

◆ clone()

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

◆ computeCommand()

void Rcs::AMIntegrate2ndOrder::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 98 of file AMIntegrate2ndOrder.cpp.

◆ getDim()

unsigned int Rcs::AMIntegrate2ndOrder::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 77 of file AMIntegrate2ndOrder.cpp.

◆ getMinMax()

void Rcs::AMIntegrate2ndOrder::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 82 of file AMIntegrate2ndOrder.cpp.

◆ getNames()

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

◆ getStableAction()

void Rcs::AMIntegrate2ndOrder::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 115 of file AMIntegrate2ndOrder.cpp.

◆ getWrappedActionModel()

ActionModel * Rcs::AMIntegrate2ndOrder::getWrappedActionModel ( ) const
virtual

If this ActionModel is a wrapper for another action model, return the wrapped action model. Otherwise, return NULL.

Returns
wrapped action model or NULL if none.

Reimplemented from Rcs::ActionModel.

Definition at line 121 of file AMIntegrate2ndOrder.cpp.

◆ operator=() [1/2]

AMIntegrate2ndOrder& Rcs::AMIntegrate2ndOrder::operator= ( const AMIntegrate2ndOrder )
delete

◆ operator=() [2/2]

AMIntegrate2ndOrder& Rcs::AMIntegrate2ndOrder::operator= ( AMIntegrate2ndOrder &&  )
delete

◆ reset()

void Rcs::AMIntegrate2ndOrder::reset ( )
virtual

Called at the start of a rollout to reset any state modified by computeCommand(). This allows to reuse the ActionModel for a new simulation rollout. The graph state will already be reset, so it can be used safely. It will be called before the first rollout too, so it can also be used to setup internals that depend on operations in subclass constructors.

Reimplemented from Rcs::ActionModel.

Definition at line 107 of file AMIntegrate2ndOrder.cpp.

Member Data Documentation

◆ integrated_action

MatNd* Rcs::AMIntegrate2ndOrder::integrated_action
private

Definition at line 54 of file AMIntegrate2ndOrder.h.

◆ integrated_action_dot

MatNd* Rcs::AMIntegrate2ndOrder::integrated_action_dot
private

Definition at line 55 of file AMIntegrate2ndOrder.h.

◆ maxAction

MatNd* Rcs::AMIntegrate2ndOrder::maxAction
private

Definition at line 51 of file AMIntegrate2ndOrder.h.

◆ wrapped

ActionModel* Rcs::AMIntegrate2ndOrder::wrapped
private

Definition at line 49 of file AMIntegrate2ndOrder.h.


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