RcsPySim
A robot control and simulation library
PhysicsSimulationComponent.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 
32 #include "PhysicsFactory.h"
33 
34 #include <Rcs_joint.h>
35 #include <Rcs_macros.h>
36 #include <Rcs_typedef.h>
37 #include <Rcs_timer.h>
38 
39 
40 /*!
41  * Constructor
42  */
44  RcsGraph* graphCurr,
45  const char* engine,
46  const char* cfgFile) :
47  Rcs::HardwareComponent(),
48  PeriodicCallback(),
49  currentGraph(graphCurr),
50  dt(0.0),
51  dtSim(0.0),
52  tStart(Timer_getSystemTime()),
53  sim(NULL),
54  mtx(NULL),
55  ffwd(false)
56 {
57  // setSynchronizationMode(Synchronize_Hard);
58  setClassName(getName());
59  this->sim = Rcs::PhysicsFactory::create(engine, graphCurr, cfgFile);
60  RCHECK(this->sim);
61  // sim->setMassAndInertiaFromPhysics(graph);
62  // sim->setJointLimits(false);
63  // sim->disableCollisions();
64  // setSchedulingPolicy(SCHED_RR);
65  setSynchronizationMode(Synchronize_Hard);
66 }
67 
68 /*******************************************************************************
69  * Constructor
70  ******************************************************************************/
72  Rcs::HardwareComponent(),
73  PeriodicCallback(),
74  currentGraph(const_cast<RcsGraph*>(sim->getGraph())),
75  dt(0.0),
76  dtSim(0.0),
77  tStart(Timer_getSystemTime()),
78  sim(sim),
79  mtx(NULL),
80  ffwd(false)
81 {
82  RCHECK(sim);
83  setClassName(getName());
84  setSynchronizationMode(Synchronize_Hard);
85 }
86 
87 /*******************************************************************************
88  * Destructor
89  ******************************************************************************/
91 {
92  stop();
93  delete this->sim;
94 }
95 
96 /*******************************************************************************
97  *
98  ******************************************************************************/
99 void Rcs::PhysicsSimulationComponent::start(double updateFreq, int prio)
100 {
101  this->dt = 1.0/updateFreq;
102  this->tStart = Timer_getSystemTime();
103  PeriodicCallback::start(updateFreq, prio);
104 }
105 
106 /*******************************************************************************
107  *
108  ******************************************************************************/
110 {
111  this->mtx = mtx;
112 }
113 
114 /*******************************************************************************
115  *
116  ******************************************************************************/
118 {
119  if (this->mtx != NULL) {
120  pthread_mutex_lock(this->mtx);
121  }
122 }
123 
124 /*******************************************************************************
125  *
126  ******************************************************************************/
128 {
129  if (this->mtx != NULL) {
130  pthread_mutex_unlock(this->mtx);
131  }
132 }
133 
134 /*******************************************************************************
135  *
136  ******************************************************************************/
138 {
139  double tmp = Timer_getSystemTime();
140 
141  lock();
142 
143  if (this->ffwd == true) {
144  sim->getLastPositionCommand(graph->q);
145  }
146  else {
147  if (this->dt > 0.0) {
148  sim->simulate(this->dt, graph, NULL, NULL, true);
149  }
150  }
151 
152  unlock();
153 
154  this->dtSim = Timer_getSystemTime() - tmp;
155 }
156 
157 /*******************************************************************************
158  *
159  ******************************************************************************/
161  const MatNd* q_des,
162  const MatNd* q_dot_des,
163  const MatNd* T_des)
164 {
165  sim->setControlInput(q_des, q_dot_des, T_des);
166 }
167 
168 /*******************************************************************************
169  *
170  ******************************************************************************/
172 {
173 }
174 
175 /*******************************************************************************
176  *
177  ******************************************************************************/
179 {
180  sim->setEnablePPS(enable);
181 }
182 
183 /*******************************************************************************
184  *
185  ******************************************************************************/
187 {
188  return "PhysicsSimulation";
189 }
190 
191 /*******************************************************************************
192  *
193  ******************************************************************************/
195 {
196  return this->dt;
197 }
198 
199 /*******************************************************************************
200  *
201  ******************************************************************************/
203 {
204  return 0.0;// TODO
205 }
206 
207 /*******************************************************************************
208  * Thread callback, periodically called.
209  ******************************************************************************/
211 {
212  callControlLayerCallbackIfConnected();
213 }
214 
215 /*******************************************************************************
216  *
217  ******************************************************************************/
219 {
220  sim->getLastPositionCommand(q_des);
221 }
222 
223 /*******************************************************************************
224  *
225  ******************************************************************************/
227 {
228  return this->sim;
229 }
230 
231 /*******************************************************************************
232  *
233  ******************************************************************************/
234 int Rcs::PhysicsSimulationComponent::sprint(char* str, size_t size) const
235 {
236  return snprintf(str, size, "Simulation time: %.3f (%.3f)\nStep took %.1f msec\n",
237  sim->time(), Timer_getSystemTime() - this->tStart, dtSim*1.0e3);
238 }
239 
240 /*******************************************************************************
241  *
242  ******************************************************************************/
244 {
245  this->ffwd = ffwd_;
246 }
247 
248 /*******************************************************************************
249  *
250  ******************************************************************************/
252 {
253  return this->tStart;
254 }
255 
257 {
258  start(getUpdateFrequency(), getThreadPriority());
259  return true;
260 }
261 
263 {
264  stop();
265  return true;
266 }
virtual void start(double updateFreq=10.0, int prio=50)
virtual void setMutex(pthread_mutex_t *mtx)
virtual void getLastPositionCommand(MatNd *q_des) const
virtual void setCommand(const MatNd *q_des, const MatNd *qp_des, const MatNd *T_des)
PhysicsSimulationComponent(RcsGraph *graph, const char *engine="Bullet", const char *physicsCfgFile=NULL)
virtual void updateGraph(RcsGraph *graph)
virtual PhysicsBase * getPhysicsSimulation() const
virtual int sprint(char *str, size_t size) const