RcsPySim
A robot control and simulation library
ExperimentConfig.h
Go to the documentation of this file.
1 /*******************************************************************************
2  Copyright (c) 2020, Fabio Muratore, Honda Research Institute Europe GmbH, and
3  Technical University of Darmstadt.
4  All rights reserved.
5 
6  Redistribution and use in source and binary forms, with or without
7  modification, are permitted provided that the following conditions are met:
8  1. Redistributions of source code must retain the above copyright
9  notice, this list of conditions and the following disclaimer.
10  2. Redistributions in binary form must reproduce the above copyright
11  notice, this list of conditions and the following disclaimer in the
12  documentation and/or other materials provided with the distribution.
13  3. Neither the name of Fabio Muratore, Honda Research Institute Europe GmbH,
14  or Technical University of Darmstadt, nor the names of its contributors may
15  be used to endorse or promote products derived from this software without
16  specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
19  ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
20  WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21  DISCLAIMED. IN NO EVENT SHALL FABIO MURATORE, HONDA RESEARCH INSTITUTE EUROPE GMBH,
22  OR TECHNICAL UNIVERSITY OF DARMSTADT BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
23  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
24  PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
25  OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
26  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  POSSIBILITY OF SUCH DAMAGE.
29 *******************************************************************************/
30 
31 #ifndef _EXPERIMENTCONFIG_H_
32 #define _EXPERIMENTCONFIG_H_
33 
34 #include "config/PropertySource.h"
35 #include "util/nocopy.h"
36 
37 #include <Rcs_graph.h>
38 
39 namespace Rcs
40 {
41 
42 class ActionModel;
43 
44 class ObservationModel;
45 
46 class InitStateSetter;
47 
48 class PhysicsParameterManager;
49 
50 class PhysicsBase;
51 
52 class ForceDisturber;
53 
54 class HUD;
55 
56 class Viewer;
57 
58 /**
59  * Create a collision model using the settings from the given RcsPySim config.
60  *
61  * @param graph graph to observe
62  * @param config collision configuration
63  * @return new collision model
64  * @throw std::invalid_argument if the collision model could not be created.
65  */
66 RcsCollisionMdl* RcsCollisionModel_createFromConfig(RcsGraph* graph, Rcs::PropertySource* config);
67 
68 /**
69  * Defines the experiment setup.
70  * There should be one subclass per experiment type, IE BallOnPlate or QuanserQube.
71  */
73 {
74  // experiment catalog management
75 public:
76 
77  typedef ExperimentConfig* (* ExperimentConfigCreateFunction)();
78 
79  /**
80  * Register a named experiment.
81  * @param name experiment name
82  * @param creator ExperimentConfig factory function
83  */
84  static void registerType(const char* name, ExperimentConfigCreateFunction creator);
85 
86  /**
87  * Create the experiment configuration from the given property source.
88  * This will load the "type" property, use that to select a ExperimentConfig implementation, and then call init()
89  * to populate it.
90  * @param properties property source to read configuration from. Takes ownership, even on error.
91  * @return a new experiment config object.
92  */
94 
95 
96 public:
98 
99  virtual ~ExperimentConfig();
100 
101  // not copy- or movable RCSPYSIM_NOCOPY_NOMOVE(ExperimentConfig)
102 
103 protected:
104  /**
105  * Called to load data from the given properties.
106  * You can override this to load additional data, but be sure to call the parent implementation.
107  * @param properties property source to read configuration from. Takes ownership.
108  */
109  virtual void load(PropertySource* properties);
110 
111 public:
112  /**
113  * Create the action model. Read any configuration from this->properties.
114  * @return the new action model
115  */
116  virtual ActionModel* createActionModel() = 0;
117 
118  /**
119  * Create the observation model. Read any configuration from this->properties.
120  * @return the new observation model
121  */
123 
124  /**
125  * Create the init state setter. Read any configuration from this->properties.
126  * Since the init state setter is only needed for the simulation, it is not stored in the ExperimentConfig.
127  * Instead, the simulation calls this method and manages the object on it's own.
128  * The default implementation returns NULL to use the state from the graph file.
129  * @return the new init state setter
130  */
132 
133  /**
134  * Create a model for artificial external disturbing forces.
135  * The default implementation returns NULL to ignore this.
136  * @return the new force disturber
137  */
139 
140  /**
141  * Create the physics parameter manager. Read any configuration from this->properties.
142  * Since the physics parameter manager is only needed for the simulation, it is not stored in the ExperimentConfig.
143  * Instead, the simulation calls this method and manages the object on it's own.
144  * This method calls populatePhysicsParameters to populate the parameter descriptors.
145  * @return the new physics parameter manager
146  */
148 
149  /**
150  * Add the physics parameter descriptors to the given physics parameter manager.
151  * @param manager parameter manager to populate.
152  */
153  virtual void populatePhysicsParameters(PhysicsParameterManager* manager);
154 
155  /**
156  * Called to update the HUD text for the viewer.
157  * The default implementation will show the physics engine name, the current time.
158  *
159  * @param[out] linesOut vector of HUD lines. initially empty.
160  * @param[in] currentTime simulation time
161  * @param[in] currentObservation latest observation
162  * @param[in] currentAction latest action
163  * @param[in] simulator physics simulator or NULL if none
164  * @param[in] physicsManager physics parameter manager or NULL if none
165  * @param[in] forceDisturber distruber which applies the forces to a given body
166  * @return concatenated HUD lines
167  */
168  virtual void getHUDText(
169  std::vector<std::string>& linesOut, double currentTime, const MatNd* currentObservation,
170  const MatNd* currentAction, PhysicsBase* simulator,
171  PhysicsParameterManager* physicsManager, ForceDisturber* forceDisturber);
172 
173  /**
174  * Returns the concatenated HUD lines.
175  * @param[in] currentTime simulation time
176  * @param[in] currentObservation latest observation
177  * @param[in] currentAction latest action
178  * @param[in] simulator physics simulator or NULL if none
179  * @param[in] physicsManager physics parameter manager or NULL if none
180  * @param[in] forceDisturber distruber which applies the forces to a given body
181  * @return concatenated HUD lines
182  */
183  std::string getHUDText(
184  double currentTime, const MatNd* currentObservation, const MatNd* currentAction,
185  PhysicsBase* simulator, PhysicsParameterManager* physicsManager,
186  ForceDisturber* forceDisturber);
187 
188  /**
189  * Perform additional initialization on the viewer.
190  * This could, for example, change the camera position or add additional visualization.
191  * The default implementation does nothing.
192  */
193  virtual void initViewer(Rcs::Viewer* viewer);
194 
195 public:
196  //! Property source (owned)
198 
199  //! Graph description
200  RcsGraph* graph;
201 
202  //! Action model (pluggable)
204 
205  //! Observation model (pluggable) used to create the observation which will be returned from step()
207 
208  //! Collision model to use. Is based on the graph, so take care when using with IK etc.
209  RcsCollisionMdl* collisionMdl;
210 
211  //! The time step [s]
212  double dt;
213 
214  //! Flag to enable joint limit checking
216 };
217 
218 
219 /**
220  * Create a static field of this type to register an experiment config type.
221  */
222 template<class Config>
224 {
225 public:
226  /**
227  * Register the template type under the given name.
228  * @param name experiment name
229  */
230  explicit ExperimentConfigRegistration(const char* name)
231  {
233  }
234 
235  /**
236  * Creator function passed to ExperimentConfig::registerType.
237  */
239  {
240  return new Config();
241  }
242 
243 };
244 
245 } /* namespace Rcs */
246 
247 #endif /* _EXPERIMENTCONFIG_H_ */
static ExperimentConfig * create()
virtual void initViewer(Rcs::Viewer *viewer)
virtual ActionModel * createActionModel()=0
virtual ForceDisturber * createForceDisturber()
bool checkJointLimits
Flag to enable joint limit checking.
double dt
The time step [s].
virtual ObservationModel * createObservationModel()=0
virtual void load(PropertySource *properties)
virtual InitStateSetter * createInitStateSetter()
static ExperimentConfig * create(PropertySource *properties)
ObservationModel * observationModel
Observation model (pluggable) used to create the observation which will be returned from step() ...
PropertySource * properties
Property source (owned)
virtual void getHUDText(std::vector< std::string > &linesOut, double currentTime, const MatNd *currentObservation, const MatNd *currentAction, PhysicsBase *simulator, PhysicsParameterManager *physicsManager, ForceDisturber *forceDisturber)
RcsCollisionMdl * RcsCollisionModel_createFromConfig(RcsGraph *graph, PropertySource *config)
ExperimentConfig *(* ExperimentConfigCreateFunction)()
ExperimentConfigRegistration(const char *name)
ActionModel * actionModel
Action model (pluggable)
RcsCollisionMdl * collisionMdl
Collision model to use. Is based on the graph, so take care when using with IK etc.
virtual void populatePhysicsParameters(PhysicsParameterManager *manager)
static void registerType(const char *name, ExperimentConfigCreateFunction creator)
RcsGraph * graph
Graph description.
PhysicsParameterManager * createPhysicsParameterManager()