RcsPySim
A robot control and simulation library
ECQuanserQube.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 "ExperimentConfig.h"
39 #include "observation/OMCombined.h"
44 #include "physics/PPDRodLength.h"
45 #include "physics/ForceDisturber.h"
46 #include "util/string_format.h"
47 
48 #include <Rcs_typedef.h>
49 #include <Rcs_macros.h>
50 
51 #ifdef GRAPHICS_AVAILABLE
52 
53 #include <RcsViewer.h>
54 
55 #endif
56 
57 #include <sstream>
58 #include <stdexcept>
59 #include <cmath>
60 #include <iomanip>
61 
62 
63 namespace Rcs
64 {
65 
67 {
69  {
70  std::string actionModelType = "unspecified";
71  properties->getProperty(actionModelType, "actionModelType");
72 
73  if (actionModelType == "joint_acc") {
74  /** V_m_max = 5 V and theta_dot_0 = 0 rad/s
75  * tau_max = k_m (V_m_max - k_m * theta_dot_0) / R_m = 0.04375 Nm
76  * J = m * l^2 / 12 = 0.000033282 kg m^2
77  * alpha_ddot_max = tau_max / J = 1314.52 rad/s^2 */
78  double max_action = 1314.52/10.; // divide by 10 since if seem unrealistic otherwise
79  properties->getProperty(max_action, "maxAction");
80  // By integrating the position command twice before applying it as action we command the acceleration
81  return new AMIntegrate2ndOrder(new AMJointControlPosition(graph), max_action);
82  // return new AMJointControlAcceleration(graph); // not working
83  }
84 
85  else {
86  std::ostringstream os;
87  os << "Unsupported action model type: " << actionModelType;
88  throw std::invalid_argument(os.str());
89  }
90  }
91 
93  {
94  auto fullState = new OMCombined();
95  fullState->addPart(OMJointState::observeAllJoints(graph));
96  return fullState;
97  }
98 
100  {
101  manager->addParam("Arm", new PPDRodLength());
102  manager->addParam("Arm", new PPDMassProperties());
103  manager->addParam("Arm", new PPDMaterialProperties());
104  manager->addParam("Pendulum", new PPDRodLength());
105  manager->addParam("Pendulum", new PPDMassProperties());
106  manager->addParam("Pendulum", new PPDMaterialProperties());
107  }
108 
110  {
111  return new ISSQuanserQube(graph);
112  }
113 
115  {
116  RcsBody* arm = RcsGraph_getBodyByName(graph, "Arm");
117  RcsBody* pendulum = RcsGraph_getBodyByName(graph, "Pendulum");
118  return new ForceDisturber(arm, pendulum);
119  }
120 
121  virtual void initViewer(Rcs::Viewer* viewer)
122  {
123 #ifdef GRAPHICS_AVAILABLE
124  viewer->setCameraHomePosition(osg::Vec3d(0.7, 0.7, 0.4),
125  osg::Vec3d(-0.2, -0.2, 0.0),
126  osg::Vec3d(0.0, 0.05, 1.0));
127 #endif
128  }
129 
131  std::vector<std::string>& linesOut, double currentTime, const MatNd* obs, const MatNd* currentAction,
132  PhysicsBase* simulator, PhysicsParameterManager* physicsManager, ForceDisturber* forceDisturber) override
133  {
134  // Obtain simulator name
135  const char* simName = "None";
136  if (simulator != NULL) {
137  simName = simulator->getClassName();
138  }
139 
140  // common stuff
141  linesOut.emplace_back(
142  string_format("physics engine: %s sim time: %2.3f s",
143  simName, currentTime));
144 
145  unsigned int numPosCtrlJoints = 0;
146  unsigned int numTrqCtrlJoints = 0;
147  // Iterate over unconstrained joints
148  RCSGRAPH_TRAVERSE_JOINTS(graph) {
149  if (JNT->jacobiIndex != -1) {
150  if (JNT->ctrlType == RCSJOINT_CTRL_TYPE::RCSJOINT_CTRL_POSITION) {
151  numPosCtrlJoints++;
152  }
153  else if (JNT->ctrlType == RCSJOINT_CTRL_TYPE::RCSJOINT_CTRL_TORQUE) {
154  numTrqCtrlJoints++;
155  }
156  }
157  }
158  linesOut.emplace_back(
159  string_format("num joints: %d total, %d pos ctrl, %d trq ctrl", graph->nJ, numPosCtrlJoints,
160  numTrqCtrlJoints));
161 
162  linesOut.emplace_back(
163  string_format(" pole angles: [% 3.2f,% 3.2f] deg",
164  RCS_RAD2DEG(obs->ele[0]), RCS_RAD2DEG(obs->ele[1])));
165 
166  const double* distForce = forceDisturber->getLastForce();
167  linesOut.emplace_back(
168  string_format("disturbances: [% 3.1f,% 3.1f,% 3.1f] N",
169  distForce[0], distForce[1], distForce[2]));
170 
171  std::stringstream ss;
172  ss << "actions: [";
173  for (unsigned int i = 0; i < currentAction->m - 1; i++) {
174  ss << std::fixed << std::setprecision(3) << MatNd_get(currentAction, i, 0) << ", ";
175  if (i == 6) {
176  ss << "\n ";
177  }
178  }
179  ss << std::fixed << std::setprecision(3) << MatNd_get(currentAction, currentAction->m - 1, 0) << "]";
180  linesOut.emplace_back(string_format(ss.str()));
181 
182  if (physicsManager != NULL) {
183  // Include physics parameters
184 
185  // Get bodies from graph
186  RcsBody* arm = RcsGraph_getBodyByName(graph, "Arm");
187  RcsBody* pendulum = RcsGraph_getBodyByName(graph, "Pendulum");
188 
189 
190  linesOut.emplace_back(string_format(
191  "arm mass: %1.3f kg pendulum mass: %1.3f kg",
192  arm->m, pendulum->m));
193 
194  linesOut.emplace_back(string_format(
195  "arm length: %1.3f m pendulum length: %1.3f m",
196  arm->shape[0]->extents[2], pendulum->shape[0]->extents[2]));
197 
198  linesOut.emplace_back(string_format(
199  "arm radius: %1.3f m pendulum radius: %1.3f m",
200  arm->shape[0]->extents[0], pendulum->shape[0]->extents[0]));
201  }
202  }
203 };
204 
205 // register
207 
208 }
virtual bool getProperty(std::string &out, const char *property)=0
virtual ObservationModel * createObservationModel()
void getHUDText(std::vector< std::string > &linesOut, double currentTime, const MatNd *obs, const MatNd *currentAction, PhysicsBase *simulator, PhysicsParameterManager *physicsManager, ForceDisturber *forceDisturber) override
virtual InitStateSetter * createInitStateSetter()
virtual void populatePhysicsParameters(PhysicsParameterManager *manager)
virtual ForceDisturber * createForceDisturber()
void addParam(const char *bodyName, PhysicsParameterDescriptor *desc)
const double * getLastForce() const
static ObservationModel * observeAllJoints(RcsGraph *graph)
virtual ActionModel * createActionModel()
virtual void initViewer(Rcs::Viewer *viewer)
std::string string_format(const std::string &format, Args ... args)
Definition: string_format.h:45
PropertySource * properties
Property source (owned)
static ExperimentConfigRegistration< ECQuanserQube > RegQuanserQube("QuanserQube")
RcsGraph * graph
Graph description.