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

#include <RcsSimEnv.h>

Collaboration diagram for Rcs::RcsSimEnv:

Public Member Functions

 RcsSimEnv (PropertySource *propertySource)
 
virtual ~RcsSimEnv ()
 
 RcsSimEnv (const RcsSimEnv &)=delete
 
RcsSimEnvoperator= (const RcsSimEnv &)=delete
 
 RcsSimEnv (RcsSimEnv &&)=delete
 
RcsSimEnvoperator= (RcsSimEnv &&)=delete
 
virtual MatNd * reset (PropertySource *domainParam=PropertySource::empty(), const MatNd *initState=NULL)
 
virtual MatNd * step (const MatNd *action, const MatNd *disturbance=NULL)
 
virtual void render (std::string mode="human", bool close=false)
 
void toggleVideoRecording ()
 
const BoxSpaceobservationSpace ()
 
const BoxSpaceactionSpace ()
 
const BoxSpaceinitStateSpace ()
 
void setTransitionNoiseBuffer (const MatNd *tnb)
 
unsigned int getInternalStateDim ()
 
ExperimentConfiggetConfig ()
 
PhysicsParameterManagergetPhysicsManager ()
 
MatNd * getCurrentObservation () const
 
MatNd * getCurrentAction () const
 

Private Attributes

std::mutex graphLock
 
ExperimentConfigconfig
 
bool allJointsPosCtrl
 
PhysicsParameterManagerphysicsManager
 
PhysicsBase * physicsSim
 
ForceDisturberdisturber
 
InitStateSetterinitStateSetter
 
MatNd * q_ctrl
 
MatNd * qd_ctrl
 
MatNd * T_ctrl
 
unsigned int currentStep
 
double currentTime
 
MatNd * transitionNoiseBuffer
 
unsigned int tnbIndex
 
bool transitionNoiseIncludeVelocity
 
MatNd * currentObservation
 
MatNd * currentAction
 
Viewer * viewer
 
bool usePhysicsNode
 
HUD * hud
 

Detailed Description

Rcs-backed machine learning simulation environment. This class provides a user-driven update loop. It is started by reset(), and then updated by step().

Definition at line 61 of file RcsSimEnv.h.

Constructor & Destructor Documentation

◆ RcsSimEnv() [1/3]

Rcs::RcsSimEnv::RcsSimEnv ( PropertySource propertySource)
explicit

Create the environment from the given property source.

Parameters
propertySourceconfiguration

Definition at line 57 of file RcsSimEnv.cpp.

◆ ~RcsSimEnv()

Rcs::RcsSimEnv::~RcsSimEnv ( )
virtual

Definition at line 109 of file RcsSimEnv.cpp.

◆ RcsSimEnv() [2/3]

Rcs::RcsSimEnv::RcsSimEnv ( const RcsSimEnv )
delete

◆ RcsSimEnv() [3/3]

Rcs::RcsSimEnv::RcsSimEnv ( RcsSimEnv &&  )
delete

Member Function Documentation

◆ actionSpace()

const Rcs::BoxSpace * Rcs::RcsSimEnv::actionSpace ( )

Action space of this environment. All valid action values fit inside this. The actions provided from Python are not projected to this space, i.e. this must be done on the Python side.

Definition at line 451 of file RcsSimEnv.cpp.

◆ getConfig()

ExperimentConfig* Rcs::RcsSimEnv::getConfig ( )
inline

Configuration settings for the experiment

Definition at line 144 of file RcsSimEnv.h.

◆ getCurrentAction()

MatNd* Rcs::RcsSimEnv::getCurrentAction ( ) const
inline

Action from last step

Definition at line 162 of file RcsSimEnv.h.

◆ getCurrentObservation()

MatNd* Rcs::RcsSimEnv::getCurrentObservation ( ) const
inline

Observation from last step

Definition at line 156 of file RcsSimEnv.h.

◆ getInternalStateDim()

unsigned int Rcs::RcsSimEnv::getInternalStateDim ( )

Internal state dimension, required for the transition noise buffer.

Definition at line 487 of file RcsSimEnv.cpp.

◆ getPhysicsManager()

PhysicsParameterManager* Rcs::RcsSimEnv::getPhysicsManager ( )
inline

Physics parameter management

Definition at line 150 of file RcsSimEnv.h.

◆ initStateSpace()

const Rcs::BoxSpace * Rcs::RcsSimEnv::initStateSpace ( )

Initial state space of this environment. All valid initial state values fit inside this.

Definition at line 456 of file RcsSimEnv.cpp.

◆ observationSpace()

const Rcs::BoxSpace * Rcs::RcsSimEnv::observationSpace ( )

Observation space of this environment. All valid observation values fit inside this.

Definition at line 446 of file RcsSimEnv.cpp.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ render()

void Rcs::RcsSimEnv::render ( std::string  mode = "human",
bool  close = false 
)
virtual

Render the current state of the simulation.

Should be called after each step call. The RcsGraphics renderer runs mostly on it's own thread, so that isn't absolutely necessairy, but it is required to update the HUD.

Parameters
modeonly 'human' is supported at the moment, is also the default
closetrue to close the render window

Definition at line 349 of file RcsSimEnv.cpp.

◆ reset()

MatNd * Rcs::RcsSimEnv::reset ( PropertySource domainParam = PropertySource::empty(),
const MatNd *  initState = NULL 
)
virtual

Reset the internal state in order to start a new rollout.

Parameters
domainParamphysics params to use for this rollout
initStateinitial state for this rollout
Returns
observation of the initial state

Definition at line 128 of file RcsSimEnv.cpp.

◆ setTransitionNoiseBuffer()

void Rcs::RcsSimEnv::setTransitionNoiseBuffer ( const MatNd *  tnb)

Set the transition noise buffer. In order to avoid heavy stochastic computation in every step, the transition noise values are pregenerated. The buffer should have a row count equal to getInternalStateDim(). Every column is a set of noise values applied in one step. In the next step, the next column is used. If the last column is reached, the next step will use the first column again.

Parameters
tnbtransition noise buffer

Definition at line 470 of file RcsSimEnv.cpp.

◆ step()

MatNd * Rcs::RcsSimEnv::step ( const MatNd *  action,
const MatNd *  disturbance = NULL 
)
virtual

Perform one environment step.

Parameters
actionaction vector
disturbancedisturbance vector, e.g. a 3-dim force
Returns
observation after the step was processed
Exceptions
JointLimitExceptionif the joint limits were violated

Definition at line 202 of file RcsSimEnv.cpp.

◆ toggleVideoRecording()

void Rcs::RcsSimEnv::toggleVideoRecording ( )

Start/stop video recording.

Definition at line 425 of file RcsSimEnv.cpp.

Member Data Documentation

◆ allJointsPosCtrl

bool Rcs::RcsSimEnv::allJointsPosCtrl
private

Definition at line 173 of file RcsSimEnv.h.

◆ config

ExperimentConfig* Rcs::RcsSimEnv::config
private

Experiment configuration.

Definition at line 172 of file RcsSimEnv.h.

◆ currentAction

MatNd* Rcs::RcsSimEnv::currentAction
private

Definition at line 201 of file RcsSimEnv.h.

◆ currentObservation

MatNd* Rcs::RcsSimEnv::currentObservation
private

Observation and action at last step.

Definition at line 200 of file RcsSimEnv.h.

◆ currentStep

unsigned int Rcs::RcsSimEnv::currentStep
private

Counters.

Definition at line 191 of file RcsSimEnv.h.

◆ currentTime

double Rcs::RcsSimEnv::currentTime
private

Definition at line 192 of file RcsSimEnv.h.

◆ disturber

ForceDisturber* Rcs::RcsSimEnv::disturber
private

Disturbance force simulator.

Definition at line 180 of file RcsSimEnv.h.

◆ graphLock

std::mutex Rcs::RcsSimEnv::graphLock
private

Guards for parallel access to graph (can happen from gui)

Definition at line 169 of file RcsSimEnv.h.

◆ hud

HUD* Rcs::RcsSimEnv::hud
private

Definition at line 206 of file RcsSimEnv.h.

◆ initStateSetter

InitStateSetter* Rcs::RcsSimEnv::initStateSetter
private

Initial state setter.

Definition at line 183 of file RcsSimEnv.h.

◆ physicsManager

PhysicsParameterManager* Rcs::RcsSimEnv::physicsManager
private

Physics simulator factory.

Definition at line 176 of file RcsSimEnv.h.

◆ physicsSim

PhysicsBase* Rcs::RcsSimEnv::physicsSim
private

Physics simulator.

Definition at line 178 of file RcsSimEnv.h.

◆ q_ctrl

MatNd* Rcs::RcsSimEnv::q_ctrl
private

Temporary matrices.

Definition at line 186 of file RcsSimEnv.h.

◆ qd_ctrl

MatNd* Rcs::RcsSimEnv::qd_ctrl
private

Definition at line 187 of file RcsSimEnv.h.

◆ T_ctrl

MatNd* Rcs::RcsSimEnv::T_ctrl
private

Definition at line 188 of file RcsSimEnv.h.

◆ tnbIndex

unsigned int Rcs::RcsSimEnv::tnbIndex
private

Definition at line 196 of file RcsSimEnv.h.

◆ transitionNoiseBuffer

MatNd* Rcs::RcsSimEnv::transitionNoiseBuffer
private

Transition noise values (every column is one set of noise values for every state variable)

Definition at line 195 of file RcsSimEnv.h.

◆ transitionNoiseIncludeVelocity

bool Rcs::RcsSimEnv::transitionNoiseIncludeVelocity
private

Definition at line 197 of file RcsSimEnv.h.

◆ usePhysicsNode

bool Rcs::RcsSimEnv::usePhysicsNode
private

Definition at line 205 of file RcsSimEnv.h.

◆ viewer

Viewer* Rcs::RcsSimEnv::viewer
private

Visualization.

Definition at line 204 of file RcsSimEnv.h.


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