RcsPySim
A robot control and simulation library
ECPlanarInsert.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"
39 #include "observation/OMCombined.h"
40 #include "observation/OMPartial.h"
51 #include "physics/ForceDisturber.h"
53 #include "util/string_format.h"
54 
55 #include <Rcs_Mat3d.h>
56 #include <Rcs_Vec3d.h>
57 #include <Rcs_typedef.h>
58 #include <Rcs_macros.h>
59 #include <TaskVelocity1D.h>
60 #include <TaskOmega1D.h>
61 
62 #ifdef GRAPHICS_AVAILABLE
63 
64 #include <RcsViewer.h>
65 
66 #endif
67 
68 #include <sstream>
69 #include <iomanip>
70 #include <stdexcept>
71 #include <cmath>
72 #include <memory>
73 
74 namespace Rcs
75 {
76 
78 {
80  {
81  std::string actionModelType = "unspecified";
82  properties->getProperty(actionModelType, "actionModelType");
83 
84  // Get the method how to combine the movement primitives / tasks given their activation
85  std::string taskCombinationMethod = "unspecified";
86  properties->getProperty(taskCombinationMethod, "taskCombinationMethod");
88 
89  // Common for the action models
90  RcsBody* effector = RcsGraph_getBodyByName(graph, "Effector");
91  RCHECK(effector);
92 
93  if (actionModelType == "ik_activation") {
94  // Create the action model
95  auto amIK = new AMIKControllerActivation(graph, tcm);
96  std::vector<Task*> tasks;
97 
98  // Check if the tasks are defined on position or velocity level. Adapt their parameters if desired.
99  if (properties->getPropertyBool("positionTasks", false)) {
100  throw std::invalid_argument("Position tasks based are not implemented for PlanarInsert!");
101  }
102  else {
103  tasks.emplace_back(new TaskVelocity1D("Xd", graph, effector, nullptr, nullptr));
104  tasks.emplace_back(new TaskVelocity1D("Zd", graph, effector, nullptr, nullptr));
105  tasks.emplace_back(new TaskOmega1D("Bd", graph, effector, nullptr, nullptr));
106  tasks[0]->resetParameter(Task::Parameters(-0.5, 0.5, 1.0, "X Velocity [m/s]"));
107  tasks[1]->resetParameter(Task::Parameters(-0.5, 0.5, 1.0, "Z Velocity [m/s]"));
108  }
109 
110  // Add the tasks
111  for (auto t : tasks) { amIK->addTask(t); }
112 
113  // Set the tasks' desired states
114  std::vector<PropertySource*> taskSpec = properties->getChildList("taskSpecIK");
115  amIK->setXdesFromTaskSpec(taskSpec);
116 
117  // Incorporate collision costs into IK
118  if (properties->getPropertyBool("collisionAvoidanceIK", true)) {
119  REXEC(4) {
120  std::cout << "IK considers the provided collision model" << std::endl;
121  }
122  amIK->setupCollisionModel(collisionMdl);
123  }
124 
125  return amIK;
126  }
127 
128  else if (actionModelType == "ds_activation") {
129  // Obtain the inner action model
130  std::unique_ptr<AMIKGeneric> innerAM(new AMIKGeneric(graph));
131  innerAM->addTask(new TaskVelocity1D("Xd", graph, effector, nullptr, nullptr));
132  innerAM->addTask(new TaskVelocity1D("Zd", graph, effector, nullptr, nullptr));
133  innerAM->addTask(new TaskOmega1D("Bd", graph, effector, nullptr, nullptr));
134 
135  // Obtain task data
136  unsigned int i = 0;
137  std::vector<unsigned int> offsets{0, 0, 1, 1, 2, 2}; // depends on the order of the MPs coming from python
138  std::vector<std::unique_ptr<DynamicalSystem>> tasks;
139  auto& taskSpec = properties->getChildList("tasks");
140  for (auto tsk : taskSpec) {
141  // Positive and negative linear velocity tasks separately
143  tasks.emplace_back(new DSSlice(ds, offsets[i], 1));
144  i++;
145  }
146  if (tasks.empty()) {
147  throw std::invalid_argument("No tasks specified!");
148  }
149 
150  // Incorporate collision costs into IK
151  if (properties->getPropertyBool("collisionAvoidanceIK", true)) {
152  REXEC(4) {
153  std::cout << "IK considers the provided collision model" << std::endl;
154  }
155  innerAM->setupCollisionModel(collisionMdl);
156  }
157 
158  // Setup task-based action model
159  std::vector<DynamicalSystem*> taskRel;
160  for (auto& task : tasks) {
161  taskRel.push_back(task.release());
162  }
163 
164  // Create the action model
165  return new AMDynamicalSystemActivation(innerAM.release(), taskRel, tcm);
166  }
167 
168  else {
169  std::ostringstream os;
170  os << "Unsupported action model type: " << actionModelType;
171  throw std::invalid_argument(os.str());
172  }
173  }
174 
176  {
177  auto fullState = new OMCombined();
178 
179  // Observe effector position
180  auto omLin = new OMBodyStateLinear(graph, "Effector", "GroundPlane"); // Base center is above ground level
181  omLin->setMinState(-1.7); // [m]
182  omLin->setMaxState(1.7); // [m]
183  omLin->setMaxVelocity(5.); // [m/s]
184  fullState->addPart(OMPartial::fromMask(omLin, {true, false, true})); // mask out y axis
185 
186  auto omAng = new OMBodyStateAngular(graph, "Effector", "GroundPlane"); // Base center is above ground level
187  omAng->setMaxVelocity(20.); // [rad/s]
188  fullState->addPart(OMPartial::fromMask(omAng, {false, true, false})); // only y axis
189 
190  std::string actionModelType = "unspecified";
191  properties->getProperty(actionModelType, "actionModelType");
192  if (actionModelType == "ds_activation") {
193  if (properties->getPropertyBool("observeDynamicalSystemGoalDistance", false)) {
194  // Add goal distances
195  auto castedAM = actionModel->unwrap<AMDynamicalSystemActivation>();
196  if (castedAM) {
197  auto omGoalDist = new OMDynamicalSystemGoalDistance(castedAM);
198  fullState->addPart(omGoalDist);
199  }
200  else {
201  delete fullState;
202  std::ostringstream os;
203  os << "The action model needs to be of type AMDynamicalSystemActivation but is: " << castedAM;
204  throw std::invalid_argument(os.str());
205  }
206  }
207 
208  if (properties->getPropertyBool("observeDynamicalSystemDiscrepancy", false)) {
209  // Add the discrepancies between commanded and executed the task space changes
210  auto castedAM = dynamic_cast<AMDynamicalSystemActivation*>(actionModel);
211  if (castedAM) {
212  auto omDescr = new OMDynamicalSystemDiscrepancy(castedAM);
213  fullState->addPart(omDescr);
214  }
215  else {
216  delete fullState;
217  std::ostringstream os;
218  os << "The action model needs to be of type AMDynamicalSystemActivation but is: " << castedAM;
219  throw std::invalid_argument(os.str());
220  }
221  }
222  }
223 
224  // Add force/torque measurements
225  if (properties->getPropertyBool("observeForceTorque", true)) {
226  RcsSensor* fts = RcsGraph_getSensorByName(graph, "EffectorLoadCell");
227  if (fts) {
228  auto omForceTorque = new OMForceTorque(graph, fts->name, 300);
229  fullState->addPart(OMPartial::fromMask(omForceTorque, {true, false, true, false, false, false}));
230  }
231  }
232 
233  // Add current collision cost
234  if (properties->getPropertyBool("observeCollisionCost", false) & (collisionMdl != nullptr)) {
235  // Add the collision cost observation model
236  auto omColl = new OMCollisionCost(collisionMdl);
237  fullState->addPart(omColl);
238  }
239 
240  // Add predicted collision cost
241  if (properties->getPropertyBool("observePredictedCollisionCost", false) && collisionMdl != nullptr) {
242  // Get horizon from config
243  int horizon = 20;
244  properties->getChild("collisionConfig")->getProperty(horizon, "predCollHorizon");
245  // Add collision model
246  auto omCollisionCost = new OMCollisionCostPrediction(graph, collisionMdl, actionModel, 50);
247  fullState->addPart(omCollisionCost);
248  }
249 
250  // Add manipulability index
251  auto ikModel = actionModel->unwrap<ActionModelIK>();
252  if (properties->getPropertyBool("observeManipulabilityIndex", false) && ikModel) {
253  bool ocm = properties->getPropertyBool("observeCurrentManipulability", true);
254  fullState->addPart(new OMManipulabilityIndex(ikModel, ocm));
255  }
256 
257  // Add the task space discrepancy observation model
258  if (properties->getPropertyBool("observeTaskSpaceDiscrepancy", false)) {
259  auto wamIK = actionModel->unwrap<ActionModelIK>();
260  if (wamIK) {
261  auto omTSDescr = new OMTaskSpaceDiscrepancy("Effector", graph, wamIK->getController()->getGraph());
262  fullState->addPart(OMPartial::fromMask(omTSDescr, {true, false, true}));
263  }
264  else {
265  delete fullState;
266  throw std::invalid_argument("The action model needs to be of type ActionModelIK!");
267  }
268  }
269 
270  return fullState;
271  }
272 
274  {
275  manager->addParam("Link1", new PPDMassProperties());
276  manager->addParam("Link2", new PPDMassProperties());
277  manager->addParam("Link3", new PPDMassProperties());
278  manager->addParam("Link4", new PPDMassProperties());
279  manager->addParam("Effector", new PPDMaterialProperties());
280  manager->addParam("UpperWall", new PPDBodyPosition(false, false, true)); // only z position
281  manager->addParam("UpperWall", new PPDMaterialProperties());
282  }
283 
285  {
286  return new ISSPlanarInsert(graph);
287  }
288 
290  {
291  RcsBody* effector = RcsGraph_getBodyByName(graph, "Effector");
292  RCHECK(effector);
293  return new ForceDisturber(effector, effector);
294  }
295 
296  virtual void initViewer(Rcs::Viewer* viewer)
297  {
298 #ifdef GRAPHICS_AVAILABLE
299  // Set camera next to base
300  RcsBody* base = RcsGraph_getBodyByName(graph, "Base");
301  double cameraCenter[3];
302  Vec3d_copy(cameraCenter, base->A_BI->org);
303  cameraCenter[1] -= 0.5;
304  cameraCenter[2] += 0.3;
305 
306  // Set the camera position
307  double cameraLocation[3];
308  cameraLocation[0] = 0.;
309  cameraLocation[1] = 4.;
310  cameraLocation[2] = 2.5;
311 
312  // Camera up vector defaults to z
313  double cameraUp[3];
314  Vec3d_setUnitVector(cameraUp, 2);
315 
316  // Apply camera position
317  viewer->setCameraHomePosition(osg::Vec3d(cameraLocation[0], cameraLocation[1], cameraLocation[2]),
318  osg::Vec3d(cameraCenter[0], cameraCenter[1], cameraCenter[2]),
319  osg::Vec3d(cameraUp[0], cameraUp[1], cameraUp[2]));
320 #endif
321  }
322 
323  void
325  std::vector<std::string>& linesOut, double currentTime, const MatNd* obs, const MatNd* currentAction,
326  PhysicsBase* simulator, PhysicsParameterManager* physicsManager, ForceDisturber* forceDisturber) override
327  {
328  // Obtain simulator name
329  const char* simName = "None";
330  if (simulator != nullptr) {
331  simName = simulator->getClassName();
332  }
333 
334  linesOut.emplace_back(
335  string_format("physics engine: %s sim time: %2.3f s", simName, currentTime));
336 
337  unsigned int numPosCtrlJoints = 0;
338  unsigned int numTrqCtrlJoints = 0;
339  // Iterate over unconstrained joints
340  RCSGRAPH_TRAVERSE_JOINTS(graph) {
341  if (JNT->jacobiIndex != -1) {
342  if (JNT->ctrlType == RCSJOINT_CTRL_TYPE::RCSJOINT_CTRL_POSITION) {
343  numPosCtrlJoints++;
344  }
345  else if (JNT->ctrlType == RCSJOINT_CTRL_TYPE::RCSJOINT_CTRL_TORQUE) {
346  numTrqCtrlJoints++;
347  }
348  }
349  }
350  linesOut.emplace_back(
351  string_format("num joints: %d total, %d pos ctrl, %d trq ctrl", graph->nJ, numPosCtrlJoints,
352  numTrqCtrlJoints));
353 
354  unsigned int sd = observationModel->getStateDim();
355 
358  if (omLin && omAng) {
359 
360  linesOut.emplace_back(string_format("end-eff pos: [% 1.3f,% 1.3f,% 1.3f] m, m, deg",
361  obs->ele[omLin.pos], obs->ele[omLin.pos + 1],
362  RCS_RAD2DEG(obs->ele[omAng.pos])));
363 
364  linesOut.emplace_back(string_format("end-eff vel: [% 1.3f,% 1.3f,% 1.3f] m/s, m/s, deg/s",
365  obs->ele[sd + omLin.vel],
366  obs->ele[sd + omLin.vel + 1],
367  RCS_RAD2DEG(obs->ele[sd + omAng.vel])));
368  }
369 
371  if (omFT) {
372  linesOut.emplace_back(
373  string_format("forces: [% 3.1f,% 3.1f] N", obs->ele[omFT.pos], obs->ele[omFT.pos + 1]));
374  }
375 
377  if (omTSD) {
378  linesOut.emplace_back(
379  string_format("ts delta: [% 1.3f,% 1.3f] m", obs->ele[omTSD.pos], obs->ele[omTSD.pos + 1]));
380  }
381 
382  std::stringstream ss;
383  ss << "actions: [";
384  for (unsigned int i = 0; i < currentAction->m - 1; i++) {
385  ss << std::fixed << std::setprecision(3) << MatNd_get(currentAction, i, 0) << ", ";
386  if (i == 6) {
387  ss << "\n ";
388  }
389  }
390  ss << std::fixed << std::setprecision(3) << MatNd_get(currentAction, currentAction->m - 1, 0) << "]";
391  linesOut.emplace_back(string_format(ss.str()));
392 
393  auto castedAM = dynamic_cast<AMDynamicalSystemActivation*>(actionModel);
394  if (castedAM) {
395  std::stringstream ss;
396  ss << "activations: [";
397  for (unsigned int i = 0; i < castedAM->getDim() - 1; i++) {
398  ss << std::fixed << std::setprecision(3) << MatNd_get(castedAM->getActivation(), i, 0) << ", ";
399  if (i == 6) {
400  ss << "\n ";
401  }
402  }
403  ss << std::fixed << std::setprecision(3) <<
404  MatNd_get(castedAM->getActivation(), castedAM->getDim() - 1, 0) << "]";
405  linesOut.emplace_back(string_format(ss.str()));
406 
407  linesOut.emplace_back(string_format("tcm: %s", castedAM->getTaskCombinationMethodName()));
408  }
409 
410  if (forceDisturber) {
411  const double* distForce = forceDisturber->getLastForce();
412  linesOut.emplace_back(
413  string_format("disturbances: [% 3.1f,% 3.1f,% 3.1f] N", distForce[0], distForce[1], distForce[2]));
414  }
415 
416  if (physicsManager != nullptr) {
417  // Get the parameters that are not stored in the Rcs graph
418  BodyParamInfo* link1_bpi = physicsManager->getBodyInfo("Link1");
419  BodyParamInfo* link2_bpi = physicsManager->getBodyInfo("Link2");
420  BodyParamInfo* link3_bpi = physicsManager->getBodyInfo("Link3");
421  BodyParamInfo* link4_bpi = physicsManager->getBodyInfo("Link4");
422  BodyParamInfo* uWall_bpi = physicsManager->getBodyInfo("UpperWall");
423  BodyParamInfo* lWall_bpi = physicsManager->getBodyInfo("LowerWall");
424  BodyParamInfo* eff_bpi = physicsManager->getBodyInfo("Effector");
425 
426  linesOut.emplace_back(
427  string_format("link masses: [%1.2f, %1.2f, %1.2f, %1.2f] kg wall Z pos: %1.3f m",
428  link1_bpi->body->m, link2_bpi->body->m, link3_bpi->body->m, link4_bpi->body->m,
429  uWall_bpi->body->A_BP->org[2]));
430  linesOut.emplace_back(string_format("wall friction: [%1.3f, %1.3f] l/u effector friction: %1.3f",
431  lWall_bpi->material.getFrictionCoefficient(),
432  uWall_bpi->material.getFrictionCoefficient(),
433  eff_bpi->material.getFrictionCoefficient()));
434  }
435  }
436 };
437 
438 // Register
440 
441 }
virtual bool getProperty(std::string &out, const char *property)=0
virtual ObservationModel * createObservationModel()
virtual bool getPropertyBool(const char *property, bool def=false)=0
RcsBody * body
The body.
Definition: BodyParamInfo.h:64
virtual ActionModel * createActionModel()
virtual PropertySource * getChild(const char *prefix)=0
virtual void initViewer(Rcs::Viewer *viewer)
void addParam(const char *bodyName, PhysicsParameterDescriptor *desc)
const double * getLastForce() const
static TaskCombinationMethod checkTaskCombinationMethod(std::string tcmName)
TaskCombinationMethod
Definition: ActionModel.h:46
virtual InitStateSetter * createInitStateSetter()
virtual const std::vector< PropertySource * > & getChildList(const char *prefix)=0
virtual unsigned int getStateDim() const =0
BodyParamInfo * getBodyInfo(const char *bodyName)
static DynamicalSystem * create(PropertySource *properties, unsigned int innerTaskDim)
virtual ForceDisturber * createForceDisturber()
void getHUDText(std::vector< std::string > &linesOut, double currentTime, const MatNd *obs, const MatNd *currentAction, PhysicsBase *simulator, PhysicsParameterManager *physicsManager, ForceDisturber *forceDisturber) override
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)
static ExperimentConfigRegistration< ECPlanarInsert > RegPlanarInsert("PlanarInsert")
const AM * unwrap() const
Definition: ActionModel.h:142
virtual void populatePhysicsParameters(PhysicsParameterManager *manager)
ActionModel * actionModel
Action model (pluggable)
RcsCollisionMdl * collisionMdl
Collision model to use. Is based on the graph, so take care when using with IK etc.
PhysicsMaterial material
Material of the body&#39;s first shape.
Definition: BodyParamInfo.h:70
RcsGraph * graph
Graph description.