RcsPySim
A robot control and simulation library
ECMPBlending.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"
35 #include "action/ActionModelIK.h"
38 #include "observation/OMCombined.h"
39 #include "observation/OMPartial.h"
43 #include "physics/ForceDisturber.h"
44 #include "util/string_format.h"
45 
46 #include <Rcs_Mat3d.h>
47 #include <Rcs_Vec3d.h>
48 #include <Rcs_typedef.h>
49 #include <Rcs_macros.h>
50 
51 #include <TaskPosition1D.h>
52 #include <TaskVelocity1D.h>
53 
54 #ifdef GRAPHICS_AVAILABLE
55 
56 #include <RcsViewer.h>
57 
58 #endif
59 
60 #include <sstream>
61 #include <stdexcept>
62 #include <cmath>
63 #include <memory>
64 
65 namespace Rcs
66 {
67 
69 {
71  {
72  std::string actionModelType = "unspecified";
73  properties->getProperty(actionModelType, "actionModelType");
74 
75  // Get the method how to combine the movement primitives / tasks given their activation
76  std::string taskCombinationMethod = "unspecified";
77  properties->getProperty(taskCombinationMethod, "taskCombinationMethod");
79 
80  RcsBody* effector = RcsGraph_getBodyByName(graph, "Effector");
81  RCHECK(effector);
82 
83  if (actionModelType == "ds_activation") {
84  // Obtain the inner action model
85  std::unique_ptr<AMIKGeneric> innerAM(new AMIKGeneric(graph));
86 
87  // Check if the MPs are defined on position or velocity level
88  if (properties->getPropertyBool("positionTasks", true)) {
89  innerAM->addTask(new TaskPosition1D("X", graph, effector, nullptr, nullptr));
90  innerAM->addTask(new TaskPosition1D("Y", graph, effector, nullptr, nullptr));
91  }
92  else {
93  innerAM->addTask(new TaskVelocity1D("Xd", graph, effector, nullptr, nullptr));
94  innerAM->addTask(new TaskVelocity1D("Yd", graph, effector, nullptr, nullptr));
95  }
96 
97  // Obtain the task data
98  auto& taskSpec = properties->getChildList("tasks");
99  if (taskSpec.empty()) {
100  throw std::invalid_argument("No tasks specified!");
101  }
102  std::vector<std::unique_ptr<DynamicalSystem>> tasks;
103  for (auto ts : taskSpec) {
104  // All tasks cover the x and y coordinate
105  tasks.emplace_back(DynamicalSystem::create(ts, innerAM->getDim()));
106  }
107 
108  // Setup task-based action model
109  std::vector<DynamicalSystem*> taskRel;
110  for (auto& task : tasks) {
111  taskRel.push_back(task.release());
112  }
113 
114  // Create the action model
115  return new AMDynamicalSystemActivation(innerAM.release(), taskRel, tcm);
116  }
117 
118  else if (actionModelType == "ik_activation") {
119  // Create the action model
120  auto amIK = new AMIKControllerActivation(graph, tcm);
121  std::vector<Task*> tasks;
122 
123  // Check if the tasks are defined on position or velocity level. Adapt their parameters if desired.
124  if (properties->getPropertyBool("positionTasks", true)) {
125  RcsBody* goalLL = RcsGraph_getBodyByName(graph, "GoalLL");
126  RcsBody* goalUL = RcsGraph_getBodyByName(graph, "GoalUL");
127  RcsBody* goalLR = RcsGraph_getBodyByName(graph, "GoalLR");
128  RcsBody* goalUR = RcsGraph_getBodyByName(graph, "GoalUR");
129  RCHECK(goalLL);
130  RCHECK(goalUL);
131  RCHECK(goalLR);
132  RCHECK(goalUR);
133  int i = 0;
134 
135  tasks.emplace_back(new TaskPosition3D(graph, effector, goalLL, nullptr));
136  tasks.emplace_back(new TaskPosition3D(graph, effector, goalUL, nullptr));
137  tasks.emplace_back(new TaskPosition3D(graph, effector, goalLR, nullptr));
138  tasks.emplace_back(new TaskPosition3D(graph, effector, goalUR, nullptr));
139  for (auto task : tasks) {
140  std::stringstream taskName;
141  taskName << " Position " << i++ << " [m]";
142  task->resetParameter(
143  Task::Parameters(-1.2, 1.2, 1.0, static_cast<std::string>("X") + taskName.str()));
144  task->addParameter(
145  Task::Parameters(-1.2, 1.2, 1.0, static_cast<std::string>("Y") + taskName.str()));
146  task->addParameter(Task::Parameters(0.1, 0.2, 1.0, static_cast<std::string>("Z") + taskName.str()));
147  }
148  }
149  else {
150  throw std::invalid_argument("The combination of velocity-based tasks and AMIKControllerActivation is"
151  "not supported!");
152  }
153 
154  // Add the tasks
155  for (auto t : tasks) { amIK->addTask(t); }
156 
157  // Set the tasks' desired states
158  std::vector<PropertySource*> taskSpec = properties->getChildList("taskSpecIK");
159  amIK->setXdesFromTaskSpec(taskSpec);
160 
161  return amIK;
162  }
163 
164  else {
165  std::ostringstream os;
166  os << "Unsupported action model type: " << actionModelType;
167  throw std::invalid_argument(os.str());
168  }
169  }
170 
172  {
173  auto fullState = new OMCombined();
174 
175  // Observe effector position
176  auto omLin = new OMBodyStateLinear(graph, "Effector", "GroundPlane");
177  fullState->addPart(OMPartial::fromMask(omLin, {true, true, false})); // mask out z axis
178 
179  return fullState;
180  }
181 
183  {
184  manager->addParam("Effector", new PPDMassProperties()); // not necessary
185  }
186 
188  {
189  return new ISSMPBlending(graph);
190  }
191 
193  {
194  RcsBody* eff = RcsGraph_getBodyByName(graph, "Effector");
195  RCHECK(eff);
196  return new ForceDisturber(eff, NULL);
197  }
198 
199  virtual void initViewer(Rcs::Viewer* viewer)
200  {
201 #ifdef GRAPHICS_AVAILABLE
202  // Set camera next to base
203  RcsBody* base = RcsGraph_getBodyByName(graph, "Effector");
204  double cameraCenter[3];
205  Vec3d_copy(cameraCenter, base->A_BI->org);
206 
207  // Set the camera position
208  double cameraLocation[3];
209  cameraLocation[0] = 1.5;
210  cameraLocation[1] = -2.5;
211  cameraLocation[2] = 4.;
212 
213  // Camera up vector defaults to z
214  double cameraUp[3];
215  Vec3d_setUnitVector(cameraUp, 2);
216 
217  // Apply camera position
218  viewer->setCameraHomePosition(osg::Vec3d(cameraLocation[0], cameraLocation[1], cameraLocation[2]),
219  osg::Vec3d(cameraCenter[0], cameraCenter[1], cameraCenter[2]),
220  osg::Vec3d(cameraUp[0], cameraUp[1], cameraUp[2]));
221 #endif
222  }
223 
224  void
226  std::vector<std::string>& linesOut,
227  double currentTime,
228  const MatNd* obs,
229  const MatNd* currentAction,
230  PhysicsBase* simulator,
231  PhysicsParameterManager* physicsManager,
232  ForceDisturber* forceDisturber) override
233  {
234  // Obtain simulator name
235  const char* simName = "None";
236  if (simulator != nullptr) {
237  simName = simulator->getClassName();
238  }
239 
240  linesOut.emplace_back(
241  string_format("physics engine: %s sim time: %2.3f s", simName, currentTime));
242 
243  unsigned int sd = observationModel->getStateDim();
244 
245  linesOut.emplace_back(
246  string_format("end-eff pos: [% 1.3f,% 1.3f] m end-eff vel: [% 1.2f,% 1.2f] m/s",
247  obs->ele[0], obs->ele[1], obs->ele[sd], obs->ele[sd + 1]));
248 
249  linesOut.emplace_back(
250  string_format("actions: [% 1.3f,% 1.3f,% 1.3f,% 1.3f]", currentAction->ele[0], currentAction->ele[1],
251  currentAction->ele[2], currentAction->ele[3]));
252 
253  const double* distForce = forceDisturber->getLastForce();
254  linesOut.emplace_back(
255  string_format("disturbances: [% 3.1f,% 3.1f,% 3.1f] N", distForce[0], distForce[1], distForce[2]));
256 
257  if (physicsManager != nullptr) {
258  // Get the parameters that are not stored in the Rcs graph
259  BodyParamInfo* eff_bpi = physicsManager->getBodyInfo("Effector");
260  linesOut.emplace_back(string_format("effector mass: % 1.3f kg", eff_bpi->body->m));
261  }
262  }
263 };
264 
265 // Register
267 
268 }
virtual bool getProperty(std::string &out, const char *property)=0
virtual bool getPropertyBool(const char *property, bool def=false)=0
RcsBody * body
The body.
Definition: BodyParamInfo.h:64
virtual ActionModel * createActionModel()
void addParam(const char *bodyName, PhysicsParameterDescriptor *desc)
void getHUDText(std::vector< std::string > &linesOut, double currentTime, const MatNd *obs, const MatNd *currentAction, PhysicsBase *simulator, PhysicsParameterManager *physicsManager, ForceDisturber *forceDisturber) override
const double * getLastForce() const
static ExperimentConfigRegistration< ECMPblending > RegMPBlending("MPBlending")
static TaskCombinationMethod checkTaskCombinationMethod(std::string tcmName)
virtual InitStateSetter * createInitStateSetter()
virtual void populatePhysicsParameters(PhysicsParameterManager *manager)
virtual void initViewer(Rcs::Viewer *viewer)
TaskCombinationMethod
Definition: ActionModel.h:46
virtual const std::vector< PropertySource * > & getChildList(const char *prefix)=0
virtual unsigned int getStateDim() const =0
virtual ForceDisturber * createForceDisturber()
BodyParamInfo * getBodyInfo(const char *bodyName)
static DynamicalSystem * create(PropertySource *properties, unsigned int innerTaskDim)
static OMPartial * fromMask(ObservationModel *wrapped, const std::vector< bool > &mask, bool exclude=false)
Definition: OMPartial.cpp:116
std::string string_format(const std::string &format, Args ... args)
Definition: string_format.h:45
ObservationModel * observationModel
Observation model (pluggable) used to create the observation which will be returned from step() ...
PropertySource * properties
Property source (owned)
virtual ObservationModel * createObservationModel()
RcsGraph * graph
Graph description.