RcsPySim
A robot control and simulation library
module.cpp
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 #include "RcsSimEnv.h"
34 #include "control/ControlPolicy.h"
35 #include "physics/vortex_log.h"
36 #include "util/BoxSpace.h"
37 #include "util/type_casters.h"
38 #include "util/pybind_dict_utils.h"
39 
40 #include <pybind11/stl.h>
41 
42 namespace py = pybind11;
43 
44 #include <Rcs_resourcePath.h>
45 #include <Rcs_macros.h>
46 #include <Rcs_MatNd.h>
47 #include <Rcs_Vec3d.h>
48 #include <PhysicsFactory.h>
49 
50 #include <SegFaultHandler.h>
51 #include <Rcs_typedef.h>
52 
53 RCS_INSTALL_ERRORHANDLERS
54 
55 /* Could be done in the future
56 void define_gui_classes(py::module& m);
57  */
58 
60 {
61  // define exceptions
62  py::register_exception<Rcs::JointLimitException>(m, "JointLimitException");
63 
64  // Define BoxSpace as class. It's not providing a constructor here, it's just meant to be passed to python for information
65  py::class_<Rcs::BoxSpace>(m, "BoxSpace")
66  .def_property_readonly("min", &Rcs::BoxSpace::getMin, py::return_value_policy::reference_internal)
67  .def_property_readonly("max", &Rcs::BoxSpace::getMax, py::return_value_policy::reference_internal)
68  .def_property_readonly("names", [](
69  const Rcs::BoxSpace& thiz) -> py::object {
70  auto& names = thiz.getNames();
71  if (names.empty()) {
72  return py::none();
73  }
74  return py::cast(names);
75  });
76 
77  // Define simulator base class
78  py::class_<Rcs::RcsSimEnv>(m, "RcsSimEnv")
79  .def(py::init([](py::kwargs kwargs) {
80  // Get properties from xml or python
81  Rcs::PropertySource* config;
82  std::string configFileName;
83  if (try_get(kwargs, "experimentConfigFile", configFileName)) {
84  config = new Rcs::PropertySourceXml(configFileName.c_str());
85  }
86  else {
87  config = new Rcs::PropertySourceDict(kwargs);
88  }
89  // Create config object, takes ownership of property source
90  return new Rcs::RcsSimEnv(config);
91  })
92  )
93  .def("step", &Rcs::RcsSimEnv::step, py::arg("action"), py::arg("disturbance") = py::none(),
94  py::call_guard<py::gil_scoped_release>())
95  .def("reset", [](Rcs::RcsSimEnv& self, py::object domainParam, const MatNd* initState) {
96  Rcs::PropertySource* domainParamSource = Rcs::PropertySource::empty();
97  if (!domainParam.is_none()) {
98  domainParamSource = new Rcs::PropertySourceDict(domainParam);
99  }
100  MatNd* result = self.reset(domainParamSource, initState);
101  if (!domainParam.is_none()) {
102  delete domainParamSource;
103  }
104  return result;
105  },
106  py::arg("domainParam").none(true) = py::none(), py::arg("initState").none(true) = py::none()
107  )
108  .def("render", &Rcs::RcsSimEnv::render, py::arg("mode") = "human", py::arg("close") = false)
109  .def("toggleVideoRecording", &Rcs::RcsSimEnv::toggleVideoRecording)
110  .def("setTransitionNoiseBuffer", &Rcs::RcsSimEnv::setTransitionNoiseBuffer)
111  .def("saveConfigXML", [](Rcs::RcsSimEnv& self, const char* fileName) {
112  self.getConfig()->properties->saveXML(fileName, "Experiment");
113  })
114  .def("getBodyPosition",
115  [](Rcs::RcsSimEnv& self, const char* bodyName, const char* refBodyName, const char* refFrameName) {
116  const RcsBody* body = RcsGraph_getBodyByName(self.getConfig()->graph, bodyName);
117  RCHECK(body);
118  const RcsBody* refBody = RcsGraph_getBodyByName(self.getConfig()->graph, refBodyName);
119  const RcsBody* refFrame = RcsGraph_getBodyByName(self.getConfig()->graph, refFrameName);
120  double I_r[3];
121 
122  // Effector-fixed reference point in world coordinates
123  Vec3d_copy(I_r, body->A_BI->org);
124 
125  // Transform to reference frame: ref_r = A_ref-I * (I_r - I_r_refBdy)
126  if (refBody != NULL) {
127  Vec3d_subSelf(I_r, refBody->A_BI->org); // I_r -= I_r_refBdy
128 
129  // refBody and refFrame, but they differ: refFrame_r = A_refFrame-I*I_r
130  if ((refFrame != NULL) && (refFrame != refBody)) {
131  Vec3d_rotateSelf(I_r, refFrame->A_BI->rot);
132  }
133  // refBody and refFrame are the same: refFrame_r = A_refBody-I*I_r
134  else {
135  Vec3d_rotateSelf(I_r, refBody->A_BI->rot);
136  }
137  }
138  // No refBody, but refFrame: Rotate into refFrame coordinates
139  else {
140  // Rotate into refFrame if it exists
141  if (refFrame != NULL) {
142  Vec3d_rotateSelf(I_r, refFrame->A_BI->rot);
143  }
144 
145  }
146  MatNd* pos = NULL;
147  pos = MatNd_create(3, 1);
148  for (unsigned int i = 0; i < 3; i++) {
149  MatNd_set(pos, i, 0, I_r[i]);
150  }
151  return pos;
152  },
153  py::arg("bodyName"), py::arg("refFrameName"), py::arg("refBodyName")
154  )
155  .def("getBodyExtents", [](Rcs::RcsSimEnv& self, const char* bodyName, const int shapeIdx) {
156  const RcsBody* body = RcsGraph_getBodyByName(self.getConfig()->graph, bodyName);
157  RCHECK(body);
158 
159  MatNd* extents = NULL;
160  extents = MatNd_create(3, 1);
161  for (unsigned int i = 0; i < 3; i++) {
162  MatNd_set(extents, i, 0, body->shape[shapeIdx]->extents[i]);
163  }
164  return extents;
165  },
166  py::arg("bodyName"), py::arg("shapeIdx")
167  )
168 
169  // Properties
170  .def_property_readonly("observationSpace", &Rcs::RcsSimEnv::observationSpace)
171  .def_property_readonly("actionSpace", &Rcs::RcsSimEnv::actionSpace)
172  .def_property_readonly("initStateSpace", &Rcs::RcsSimEnv::initStateSpace)
173  .def_property_readonly("domainParam", [](Rcs::RcsSimEnv& self) {
174  // Expose the domain parameters to the Python side
175  py::dict result;
176  Rcs::PropertySourceDict psink(result);
177  self.getPhysicsManager()->getValues(&psink);
178  return result;
179  })
180  .def_property_readonly("internalStateDim", &Rcs::RcsSimEnv::getInternalStateDim)
181  .def_property_readonly("dt", [](Rcs::RcsSimEnv& self) {
182  return self.getConfig()->dt;
183  })
184  .def_property_readonly("lastAction", &Rcs::RcsSimEnv::getCurrentAction, py::return_value_policy::copy)
185  .def_property_readonly("lastObservation", &Rcs::RcsSimEnv::getCurrentObservation,
186  py::return_value_policy::copy);
187 
188  // Define ControlPolicy for tests
189  py::class_<Rcs::ControlPolicy> controlPolicy(m, "ControlPolicy");
190  controlPolicy.def(py::init<Rcs::ControlPolicy* (*)(const char*, const char*)>(&Rcs::ControlPolicy::create));
191  controlPolicy.def("__call__", [](Rcs::ControlPolicy& self, const MatNd* input, unsigned int output_size) {
192  MatNd* output = MatNd_create(output_size, 1);
193  self.computeAction(output, input);
194  return output;
195  });
196  controlPolicy.def("reset", &Rcs::ControlPolicy::reset);
197  controlPolicy.def_property_readonly_static("types", [](py::handle /* self */) {
199  });
200 
201  // Expose the ControlPolicy classes to the Python side
202 // py::class_<Rcs::ActionModelIKPolicy>(m, "ActionModelIKPolicy", controlPolicy)
203 // .def(py::init(&Rcs::loadMLPPolicyFromXml));
204 
205 /* Could be done in the future
206 #ifdef GUI_AVAILABLE
207  // Define gui stuff if available
208  define_gui_classes(m);
209 #endif
210  */
211 
212  m.def("saveExperimentParams", [](py::dict& config, const char* filename){
213  std::unique_ptr<Rcs::PropertySource> ps(new Rcs::PropertySourceDict(config));
214  ps->saveXML(filename, "Experiment");
215  }, py::arg("config"), py::arg("filename"));
216 
217  // Sets the rcs log level
218  m.def("setLogLevel", [](int level) { RcsLogLevel = level; });
219 
220  // Adds a directory to the resource path
221  m.def("addResourcePath", [](const char* path) { return Rcs_addResourcePath(path); });
222 
223  // Check if physics engine is available (can't list, unfortunately)
224  m.def("supportsPhysicsEngine", &Rcs::PhysicsFactory::hasEngine);
225 
226  // Control vortex log level, setting it to warnings only by default (this avoids log spam)
227  Rcs::setVortexLogLevel("warn");
228  // Allow changing it if desired
229  m.def("setVortexLogLevel", &Rcs::setVortexLogLevel);
230 }
231 
232 
233 
void setTransitionNoiseBuffer(const MatNd *tnb)
Definition: RcsSimEnv.cpp:470
void setVortexLogLevel(const char *level)
Definition: vortex_log.cpp:80
static std::vector< std::string > getTypeNames()
List available policy names.
unsigned int getInternalStateDim()
Definition: RcsSimEnv.cpp:487
RCS_INSTALL_ERRORHANDLERS PYBIND11_MODULE(_rcsenv, m)
Definition: module.cpp:59
virtual void render(std::string mode="human", bool close=false)
Definition: RcsSimEnv.cpp:349
const BoxSpace * actionSpace()
Definition: RcsSimEnv.cpp:451
const MatNd * getMin() const
Definition: BoxSpace.h:129
const BoxSpace * observationSpace()
Definition: RcsSimEnv.cpp:446
MatNd * getCurrentAction() const
Definition: RcsSimEnv.h:162
virtual void reset()
void toggleVideoRecording()
Definition: RcsSimEnv.cpp:425
const MatNd * getMax() const
Definition: BoxSpace.h:137
static PropertySource * empty()
MatNd * getCurrentObservation() const
Definition: RcsSimEnv.h:156
bool try_get(const py::dict &dict, const char *key, T &var)
static ControlPolicy * create(const char *name, const char *dataFile)
virtual MatNd * step(const MatNd *action, const MatNd *disturbance=NULL)
Definition: RcsSimEnv.cpp:202
const std::vector< std::string > & getNames() const
Definition: BoxSpace.h:147
const BoxSpace * initStateSpace()
Definition: RcsSimEnv.cpp:456