RcsPySim
A robot control and simulation library
ECBoxShelving.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"
32 #include "action/ActionModelIK.h"
35 #include "observation/OMCombined.h"
40 #include "observation/OMPartial.h"
47 #include "physics/PPDBoxExtents.h"
50 #include "physics/ForceDisturber.h"
51 #include "util/string_format.h"
52 
53 #include <Rcs_macros.h>
54 #include <Rcs_typedef.h>
55 #include <Rcs_Vec3d.h>
56 #include <TaskPosition3D.h>
57 #include <TaskVelocity1D.h>
58 #include <TaskOmega1D.h>
59 #include <TaskEuler3D.h>
60 #include <TaskFactory.h>
61 
62 #ifdef GRAPHICS_AVAILABLE
63 
64 #include <RcsViewer.h>
65 
66 #endif
67 
68 #include <memory>
69 #include <iomanip>
70 
71 namespace Rcs
72 {
74 {
76  {
77  // Setup inner action model
78  RcsBody* leftGrasp = RcsGraph_getBodyByName(graph, "PowerGrasp_L");
79  RCHECK(leftGrasp);
80 
81  // Get reference frames (for now identical for all tasks)
82  std::string refFrameType = "world";
83  properties->getProperty(refFrameType, "refFrame");
84  RcsBody* refBody = nullptr;
85  RcsBody* refFrame = nullptr;
86  if (refFrameType == "world") {
87  // Keep nullptr
88  }
89  else if (refFrameType == "box") {
90  RcsBody* box = RcsGraph_getBodyByName(graph, "Box");
91  RCHECK(box);
92  refBody = box;
93  refFrame = box;
94  }
95  else if (refFrameType == "upperGoal") {
96  RcsBody* goalUpperShelve = RcsGraph_getBodyByName(graph, "GoalUpperShelve");
97  RCHECK(goalUpperShelve);
98  refBody = goalUpperShelve;
99  refFrame = goalUpperShelve;
100  }
101  else {
102  std::ostringstream os;
103  os << "Unsupported reference frame type: " << refFrame;
104  throw std::invalid_argument(os.str());
105  }
106 
107  // Initialize action model and tasks
108  std::unique_ptr<AMIKGeneric> innerAM(new AMIKGeneric(graph));
109  std::vector<std::unique_ptr<DynamicalSystem>> tasks;
110 
111  // Control effector positions and orientation
112  if (properties->getPropertyBool("positionTasks", true)) {
113  // Left
114  innerAM->addTask(new TaskPosition3D(graph, leftGrasp, refBody, refFrame));
115  innerAM->addTask(new TaskEuler3D(graph, leftGrasp, refBody, refFrame));
116  innerAM->addTask(TaskFactory::createTask(
117  R"(<Task name="Hand L Joints" controlVariable="Joints" jnts="fing1-knuck1_L tip1-fing1_L fing2-knuck2_L tip2-fing2_L fing3-knuck3_L tip3-fing3_L knuck1-base_L" tmc="0.1" vmax="1000" active="untrue"/>)",
118  graph)
119  );
120 
121  // Obtain task data
122  unsigned int i = 0;
123  std::vector<unsigned int> taskDimsLeft{3, 3, 3, 3, 3, 7};
124  std::vector<unsigned int> offsetsLeft{0, 0, 0, 3, 3, 6};
125  auto& tsLeft = properties->getChildList("tasksLeft");
126  for (auto tsk : tsLeft) {
127  DynamicalSystem* ds = DynamicalSystem::create(tsk, taskDimsLeft[i]);
128  tasks.emplace_back(new DSSlice(ds, offsetsLeft[i], taskDimsLeft[i]));
129  i++;
130  }
131  }
132  // Control effector velocity and orientation
133  else {
134  // Left
135  innerAM->addTask(new TaskVelocity1D("Xd", graph, leftGrasp, refBody, refFrame));
136  innerAM->addTask(new TaskVelocity1D("Yd", graph, leftGrasp, refBody, refFrame));
137  innerAM->addTask(new TaskVelocity1D("Zd", graph, leftGrasp, refBody, refFrame));
138  innerAM->addTask(new TaskOmega1D("Ad", graph, leftGrasp, nullptr, nullptr));
139  innerAM->addTask(new TaskOmega1D("Bd", graph, leftGrasp, nullptr, nullptr));
140  innerAM->addTask(TaskFactory::createTask(
141  R"(<Task name="Hand L Joints" controlVariable="Joints" jnts="fing1-knuck1_L tip1-fing1_L fing2-knuck2_L tip2-fing2_L fing3-knuck3_L tip3-fing3_L knuck1-base_L" tmc="0.1" vmax="1000" active="untrue"/>)",
142  graph)
143  );
144 
145  // Obtain task data
146  unsigned int i = 0;
147  std::vector<unsigned int> taskDimsLeft;
148  std::vector<unsigned int> offsetsLeft;
149  if (properties->getPropertyBool("bidirectionalMPs", true)) {
150  taskDimsLeft = {1, 1, 1, 1, 1, 7};
151  offsetsLeft = {0, 1, 2, 3, 4, 5};
152  }
153  else {
154  taskDimsLeft = {1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7};
155  offsetsLeft = {0, 0, 1, 1, 2, 2, 3, 3, 4, 4, 5};
156  }
157  auto& tsLeft = properties->getChildList("tasksLeft");
158  for (auto tsk : tsLeft) {
159  DynamicalSystem* ds = DynamicalSystem::create(tsk, taskDimsLeft[i]);
160  tasks.emplace_back(new DSSlice(ds, offsetsLeft[i], taskDimsLeft[i]));
161  i++;
162  }
163  }
164 
165  if (tasks.empty()) {
166  throw std::invalid_argument("No tasks specified!");
167  }
168 
169  // Incorporate collision costs into IK
170  if (properties->getPropertyBool("collisionAvoidanceIK", true)) {
171  REXEC(4) {
172  std::cout << "IK considers the provided collision model" << std::endl;
173  }
174  innerAM->setupCollisionModel(collisionMdl);
175  }
176 
177  // Setup task-based action model
178  std::vector<DynamicalSystem*> taskRel;
179  for (auto& task : tasks) {
180  taskRel.push_back(task.release());
181  }
182 
183  // Get the method how to combine the movement primitives / tasks given their activation
184  std::string taskCombinationMethod = "unspecified";
185  properties->getProperty(taskCombinationMethod, "taskCombinationMethod");
187 
188  return new AMDynamicalSystemActivation(innerAM.release(), taskRel, tcm);
189  }
190 
192  {
193  // Observe effector positions (and velocities)
194  std::unique_ptr<OMCombined> fullState(new OMCombined());
195 
196  if (properties->getPropertyBool("observeVelocities", true)) {
197  auto omLeftLin = new OMBodyStateLinear(graph, "PowerGrasp_L"); // in world coordinates
198  omLeftLin->setMinState({-0.2, -0.5, 0.7}); // [m]
199  omLeftLin->setMaxState({2.1, 0.8, 2.0}); // [m]
200  omLeftLin->setMaxVelocity(3.); // [m/s]
201  fullState->addPart(omLeftLin);
202  }
203  else {
204  auto omLeftLin = new OMBodyStateLinearPositions(graph, "PowerGrasp_L"); // in world coordinates
205  omLeftLin->setMinState({-0.2, -0.5, 0.7}); // [m]
206  omLeftLin->setMaxState({2.1, 0.8, 2.0}); // [m]
207  fullState->addPart(omLeftLin);
208  }
209 
210  // Observe box positions (and velocities)
211  if (properties->getPropertyBool("observeVelocities", true)) {
212  auto omBoxLin = new OMBodyStateLinear(graph, "Box", "GoalUpperShelve",
213  "GoalUpperShelve"); // in relative coordinates
214  omBoxLin->setMinState({-0.2, -0.6, -0.5}); // [m]
215  omBoxLin->setMaxState({1.8, 0.6, 1.0}); // [m]
216  omBoxLin->setMaxVelocity(5.); // [m/s]
217  fullState->addPart(omBoxLin);
218  }
219  else {
220  auto omBoxLin = new OMBodyStateLinearPositions(graph, "Box", "GoalUpperShelve",
221  "GoalUpperShelve"); // in relative coordinates
222  omBoxLin->setMinState({-0.2, -0.6, -0.5}); // [m]
223  omBoxLin->setMaxState({1.8, 0.6, 1.0}); // [m]
224  fullState->addPart(omBoxLin);
225  }
226 
227  // Observe box orientation in the world frame
228  if (properties->getPropertyBool("observeVelocities", true)) {
229  auto omBoxAng = new OMBodyStateAngular(graph, "Box");
230  omBoxAng->setMaxVelocity(RCS_DEG2RAD(360)); // [rad/s]
231  fullState->addPart(omBoxAng);
232  }
233  else {
234  auto omBoxAng = new OMBodyStateAngularPositions(graph, "Box");
235  fullState->addPart(omBoxAng);
236  }
237 
238  // Add goal distances
239  if (properties->getPropertyBool("observeDynamicalSystemGoalDistance", false)) {
241  RCHECK(amAct);
242  fullState->addPart(new OMDynamicalSystemGoalDistance(amAct));
243  }
244 
245  // Add force/torque measurements
246  if (properties->getPropertyBool("observeForceTorque", true)) {
247  RcsSensor* ftsL = RcsGraph_getSensorByName(graph, "WristLoadCellLBR_L");
248  if (ftsL) {
249  auto omForceTorque = new OMForceTorque(graph, ftsL->name, 1200);
250  fullState->addPart(OMPartial::fromMask(omForceTorque, {true, true, true, false, false, false}));
251  }
252  }
253 
254  // Add current collision cost
255  if (properties->getPropertyBool("observeCollisionCost", true) & (collisionMdl != nullptr)) {
256  // Add the collision cost observation model
257  auto omColl = new OMCollisionCost(collisionMdl);
258  fullState->addPart(omColl);
259  }
260 
261  // Add predicted collision cost
262  if (properties->getPropertyBool("observePredictedCollisionCost", false) & (collisionMdl != nullptr)) {
263  // Get the horizon from config
264  int horizon = 20;
265  properties->getChild("collisionConfig")->getProperty(horizon, "predCollHorizon");
266  // Add the collision cost observation model
267  auto omCollPred = new OMCollisionCostPrediction(graph, collisionMdl, actionModel, horizon);
268  fullState->addPart(omCollPred);
269  }
270 
271  // Add manipulability index
272  auto ikModel = actionModel->unwrap<ActionModelIK>();
273  if (properties->getPropertyBool("observeManipulabilityIndex", false) && ikModel) {
274  bool ocm = properties->getPropertyBool("observeCurrentManipulability", true);
275  fullState->addPart(new OMManipulabilityIndex(ikModel, ocm));
276  }
277 
278  // Add the dynamical system discrepancy observation model
279  if (properties->getPropertyBool("observeDynamicalSystemDiscrepancy", false) & (collisionMdl != nullptr)) {
280  auto castedAM = dynamic_cast<AMDynamicalSystemActivation*>(actionModel);
281  if (castedAM) {
282  auto omDSDescr = new OMDynamicalSystemDiscrepancy(castedAM);
283  fullState->addPart(omDSDescr);
284  }
285  else {
286  throw std::invalid_argument("The action model needs to be of type AMDynamicalSystemActivation!");
287  }
288  }
289 
290  // Add the task space discrepancy observation model
291  if (properties->getPropertyBool("observeTaskSpaceDiscrepancy", true)) {
292  auto wamIK = actionModel->unwrap<ActionModelIK>();
293  if (wamIK) {
294  auto omTSDescr = new OMTaskSpaceDiscrepancy("PowerGrasp_L", graph, wamIK->getController()->getGraph());
295  fullState->addPart(omTSDescr);
296  }
297  else {
298  throw std::invalid_argument("The action model needs to be of type ActionModelIK!");
299  }
300  }
301 
302  return fullState.release();
303  }
304 
306  {
307  manager->addParam("Box", new PPDMassProperties());
308  manager->addParam("Box", new PPDMaterialProperties());
309  manager->addParam("Box", new PPDBoxExtents(0, true, true, true));
310  }
311 
313  {
314  return new ISSBoxShelving(graph, properties->getPropertyBool("fixedInitState", false));
315  }
316 
318  {
319  RcsBody* box = RcsGraph_getBodyByName(graph, "Box");
320  RCHECK(box);
321  return new ForceDisturber(box, box);
322  }
323 
324  virtual void initViewer(Rcs::Viewer* viewer)
325  {
326 #ifdef GRAPHICS_AVAILABLE
327  // Set camera above plate
328  RcsBody* table = RcsGraph_getBodyByName(graph, "Table");
329  RCHECK(table);
330  std::string cameraView = "overLeftShoulder";
331  properties->getProperty(cameraView, "overLeftShoulder");
332 
333  // The camera center is 10cm above the the plate's center
334  double cameraCenter[3];
335  Vec3d_copy(cameraCenter, table->A_BI->org);
336  cameraCenter[2] += 0.1;
337 
338  // The camera location - not specified yet
339  double cameraLocation[3];
340  Vec3d_setZero(cameraLocation);
341 
342  // Camera up vector defaults to z
343  double cameraUp[3];
344  Vec3d_setUnitVector(cameraUp, 2);
345 
346  if (cameraView == "overLeftShoulder") {
347  RcsBody* leftShoulder = RcsGraph_getBodyByName(graph, "lbr_link_0_L");
348  // Shift camera behind the left shoulder
349  cameraLocation[0] = leftShoulder->A_BI->org[0] - 2.2;
350  cameraLocation[1] = leftShoulder->A_BI->org[1] + 1.2;
351  cameraLocation[2] = leftShoulder->A_BI->org[2] + 0.5;
352 
353  // Rotate to world frame
354  Vec3d_transformSelf(cameraLocation, table->A_BI);
355 
356  }
357  else {
358  RMSG("Unsupported camera view: %s", cameraView.c_str());
359  return;
360  }
361 
362  // Apply the camera position
363  viewer->setCameraHomePosition(osg::Vec3d(cameraLocation[0], cameraLocation[1], cameraLocation[2]),
364  osg::Vec3d(cameraCenter[0], cameraCenter[1], cameraCenter[2]),
365  osg::Vec3d(cameraUp[0], cameraUp[1], cameraUp[2]));
366 #endif
367  }
368 
369  void
371  std::vector<std::string>& linesOut,
372  double currentTime,
373  const MatNd* obs,
374  const MatNd* currentAction,
375  PhysicsBase* simulator,
376  PhysicsParameterManager* physicsManager,
377  ForceDisturber* forceDisturber) override
378  {
379  // Obtain simulator name
380  const char* simName = "None";
381  if (simulator != nullptr) {
382  simName = simulator->getClassName();
383  }
384  linesOut.emplace_back(
385  string_format("physics engine: %s sim time: %2.3f s", simName, currentTime));
386 
387  unsigned int numPosCtrlJoints = 0;
388  unsigned int numTrqCtrlJoints = 0;
389  // Iterate over unconstrained joints
390  RCSGRAPH_TRAVERSE_JOINTS(graph) {
391  if (JNT->jacobiIndex != -1) {
392  if (JNT->ctrlType == RCSJOINT_CTRL_TYPE::RCSJOINT_CTRL_POSITION) {
393  numPosCtrlJoints++;
394  }
395  else if (JNT->ctrlType == RCSJOINT_CTRL_TYPE::RCSJOINT_CTRL_TORQUE) {
396  numTrqCtrlJoints++;
397  }
398  }
399  }
400  linesOut.emplace_back(
401  string_format("num joints: %d total, %d pos ctrl, %d trq ctrl", graph->nJ, numPosCtrlJoints,
402  numTrqCtrlJoints));
403 
404  unsigned int sd = observationModel->getStateDim();
405 
406  auto omLeftLin = observationModel->findOffsets<OMBodyStateLinear>(); // there are two, we find the first
407  if (omLeftLin) {
408  linesOut.emplace_back(
409  string_format("left hand pg: [% 1.3f,% 1.3f,% 1.3f] m [% 1.3f,% 1.3f,% 1.3f] m/s",
410  obs->ele[omLeftLin.pos], obs->ele[omLeftLin.pos + 1], obs->ele[omLeftLin.pos + 2],
411  obs->ele[sd + omLeftLin.vel], obs->ele[sd + omLeftLin.vel + 1],
412  obs->ele[sd + omLeftLin.vel + 2]));
413  }
414 
415  auto omBoxAng = observationModel->findOffsets<OMBodyStateAngular>(); // assuming there is only the box one
416  if (omBoxAng && omLeftLin) {
417  linesOut.emplace_back(
418  string_format("box relative: [% 1.3f,% 1.3f,% 1.3f] m [% 3.0f,% 3.0f,% 3.0f] deg",
419  obs->ele[omLeftLin.pos + 3], obs->ele[omLeftLin.pos + 4], obs->ele[omLeftLin.pos + 5],
420  RCS_RAD2DEG(obs->ele[omBoxAng.pos]), RCS_RAD2DEG(obs->ele[omBoxAng.pos + 1]),
421  RCS_RAD2DEG(obs->ele[omBoxAng.pos + 2])));
422  }
423  else if (omLeftLin) {
424  linesOut.emplace_back(
425  string_format("box relative: [% 1.3f,% 1.3f,% 1.3f] m",
426  obs->ele[omLeftLin.pos + 3], obs->ele[omLeftLin.pos + 4], obs->ele[omLeftLin.pos + 5]));
427  }
428 
429  auto omFTS = observationModel->findOffsets<OMForceTorque>();
430  if (omFTS) {
431  linesOut.emplace_back(
432  string_format("forces: [% 3.1f, % 3.1f, % 3.1f] N ", obs->ele[omFTS.pos], obs->ele[omFTS.pos + 1],
433  obs->ele[omFTS.pos + 2]));
434  }
435 
436  auto omColl = observationModel->findOffsets<OMCollisionCost>();
438  if (omColl && omCollPred) {
439  linesOut.emplace_back(
440  string_format("coll cost: %3.2f pred coll cost: %3.2f", obs->ele[omColl.pos],
441  obs->ele[omCollPred.pos]));
442 
443  }
444  else if (omColl) {
445  linesOut.emplace_back(string_format("coll cost: %3.2f", obs->ele[omColl.pos]));
446  }
447  else if (omCollPred) {
448  linesOut.emplace_back(string_format("pred coll cost: %3.2f", obs->ele[omCollPred.pos]));
449  }
450 
452  if (omMI) {
453  linesOut.emplace_back(string_format("manip idx: %1.3f", obs->ele[omMI.pos]));
454  }
455 
457  if (omTSD) {
458  linesOut.emplace_back(
459  string_format("ts delta: [% 1.3f,% 1.3f,% 1.3f] m", obs->ele[omTSD.pos], obs->ele[omTSD.pos + 1],
460  obs->ele[omTSD.pos + 2]));
461  }
462 
463  std::stringstream ss;
464  ss << "actions: [";
465  for (unsigned int i = 0; i < currentAction->m - 1; i++) {
466  ss << std::fixed << std::setprecision(2) << MatNd_get(currentAction, i, 0) << ", ";
467  if (i == 6) {
468  ss << "\n ";
469  }
470  }
471  ss << std::fixed << std::setprecision(2) << MatNd_get(currentAction, currentAction->m - 1, 0) << "]";
472  linesOut.emplace_back(string_format(ss.str()));
473 
474  auto castedAM = dynamic_cast<AMDynamicalSystemActivation*>(actionModel);
475  if (castedAM) {
476  std::stringstream ss;
477  ss << "activations: [";
478  for (unsigned int i = 0; i < castedAM->getDim() - 1; i++) {
479  ss << std::fixed << std::setprecision(2) << MatNd_get(castedAM->getActivation(), i, 0) << ", ";
480  if (i == 6) {
481  ss << "\n ";
482  }
483  }
484  ss << std::fixed << std::setprecision(2) <<
485  MatNd_get(castedAM->getActivation(), castedAM->getDim() - 1, 0) << "]";
486  linesOut.emplace_back(string_format(ss.str()));
487 
488  linesOut.emplace_back(string_format("tcm: %s", castedAM->getTaskCombinationMethodName()));
489  }
490 
491  if (physicsManager != nullptr) {
492  // Get the parameters that are not stored in the Rcs graph
493  BodyParamInfo* box_bpi = physicsManager->getBodyInfo("Box");
494 
495  linesOut.emplace_back(string_format("box mass: %1.2f kg box frict coeff: %1.3f ",
496  box_bpi->body->m, box_bpi->material.getFrictionCoefficient()));
497  }
498  }
499 
500 };
501 
502 // Register
504 
505 }
virtual bool getProperty(std::string &out, const char *property)=0
virtual void initViewer(Rcs::Viewer *viewer)
virtual bool getPropertyBool(const char *property, bool def=false)=0
RcsBody * body
The body.
Definition: BodyParamInfo.h:64
virtual InitStateSetter * createInitStateSetter()
virtual PropertySource * getChild(const char *prefix)=0
void addParam(const char *bodyName, PhysicsParameterDescriptor *desc)
static TaskCombinationMethod checkTaskCombinationMethod(std::string tcmName)
void getHUDText(std::vector< std::string > &linesOut, double currentTime, const MatNd *obs, const MatNd *currentAction, PhysicsBase *simulator, PhysicsParameterManager *physicsManager, ForceDisturber *forceDisturber) override
virtual ObservationModel * createObservationModel()
TaskCombinationMethod
Definition: ActionModel.h:46
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)
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
virtual void populatePhysicsParameters(PhysicsParameterManager *manager)
ObservationModel * observationModel
Observation model (pluggable) used to create the observation which will be returned from step() ...
PropertySource * properties
Property source (owned)
const AM * unwrap() const
Definition: ActionModel.h:142
virtual ForceDisturber * createForceDisturber()
static ExperimentConfigRegistration< ECBoxShelving > RegBoxShelving("BoxShelving")
virtual ActionModel * createActionModel()
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.