#include <RcsSimEnv.h>
Public Member Functions | |
RcsSimEnv (PropertySource *propertySource) | |
virtual | ~RcsSimEnv () |
RcsSimEnv (const RcsSimEnv &)=delete | |
RcsSimEnv & | operator= (const RcsSimEnv &)=delete |
RcsSimEnv (RcsSimEnv &&)=delete | |
RcsSimEnv & | operator= (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 BoxSpace * | observationSpace () |
const BoxSpace * | actionSpace () |
const BoxSpace * | initStateSpace () |
void | setTransitionNoiseBuffer (const MatNd *tnb) |
unsigned int | getInternalStateDim () |
ExperimentConfig * | getConfig () |
PhysicsParameterManager * | getPhysicsManager () |
MatNd * | getCurrentObservation () const |
MatNd * | getCurrentAction () const |
Private Attributes | |
std::mutex | graphLock |
ExperimentConfig * | config |
bool | allJointsPosCtrl |
PhysicsParameterManager * | physicsManager |
PhysicsBase * | physicsSim |
ForceDisturber * | disturber |
InitStateSetter * | initStateSetter |
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 |
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.
|
explicit |
Create the environment from the given property source.
propertySource | configuration |
Definition at line 57 of file RcsSimEnv.cpp.
|
virtual |
Definition at line 109 of file RcsSimEnv.cpp.
|
delete |
|
delete |
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.
|
inline |
Configuration settings for the experiment
Definition at line 144 of file RcsSimEnv.h.
|
inline |
Action from last step
Definition at line 162 of file RcsSimEnv.h.
|
inline |
Observation from last step
Definition at line 156 of file RcsSimEnv.h.
unsigned int Rcs::RcsSimEnv::getInternalStateDim | ( | ) |
Internal state dimension, required for the transition noise buffer.
Definition at line 487 of file RcsSimEnv.cpp.
|
inline |
Physics parameter management
Definition at line 150 of file RcsSimEnv.h.
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.
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.
|
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.
mode | only 'human' is supported at the moment, is also the default |
close | true to close the render window |
Definition at line 349 of file RcsSimEnv.cpp.
|
virtual |
Reset the internal state in order to start a new rollout.
domainParam | physics params to use for this rollout |
initState | initial state for this rollout |
Definition at line 128 of file RcsSimEnv.cpp.
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.
tnb | transition noise buffer |
Definition at line 470 of file RcsSimEnv.cpp.
|
virtual |
Perform one environment step.
action | action vector |
disturbance | disturbance vector, e.g. a 3-dim force |
JointLimitException | if the joint limits were violated |
Definition at line 202 of file RcsSimEnv.cpp.
void Rcs::RcsSimEnv::toggleVideoRecording | ( | ) |
Start/stop video recording.
Definition at line 425 of file RcsSimEnv.cpp.
|
private |
Definition at line 173 of file RcsSimEnv.h.
|
private |
Experiment configuration.
Definition at line 172 of file RcsSimEnv.h.
|
private |
Definition at line 201 of file RcsSimEnv.h.
|
private |
Observation and action at last step.
Definition at line 200 of file RcsSimEnv.h.
|
private |
Counters.
Definition at line 191 of file RcsSimEnv.h.
|
private |
Definition at line 192 of file RcsSimEnv.h.
|
private |
Disturbance force simulator.
Definition at line 180 of file RcsSimEnv.h.
|
private |
Guards for parallel access to graph (can happen from gui)
Definition at line 169 of file RcsSimEnv.h.
|
private |
Definition at line 206 of file RcsSimEnv.h.
|
private |
Initial state setter.
Definition at line 183 of file RcsSimEnv.h.
|
private |
Physics simulator factory.
Definition at line 176 of file RcsSimEnv.h.
|
private |
Physics simulator.
Definition at line 178 of file RcsSimEnv.h.
|
private |
Temporary matrices.
Definition at line 186 of file RcsSimEnv.h.
|
private |
Definition at line 187 of file RcsSimEnv.h.
|
private |
Definition at line 188 of file RcsSimEnv.h.
|
private |
Definition at line 196 of file RcsSimEnv.h.
|
private |
Transition noise values (every column is one set of noise values for every state variable)
Definition at line 195 of file RcsSimEnv.h.
|
private |
Definition at line 197 of file RcsSimEnv.h.
|
private |
Definition at line 205 of file RcsSimEnv.h.
|
private |
Visualization.
Definition at line 204 of file RcsSimEnv.h.