MBDyn-1.7.3
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups
module-minmaxdrive.cc
Go to the documentation of this file.
1 /* $Header: /var/cvs/mbdyn/mbdyn/mbdyn-1.0/modules/module-minmaxdrive/module-minmaxdrive.cc,v 1.6 2017/07/04 18:21:05 masarati Exp $ */
2 /*
3  * MBDyn (C) is a multibody analysis code.
4  * http://www.mbdyn.org
5  *
6  * Copyright (C) 1996-2017
7  *
8  * Pierangelo Masarati <masarati@aero.polimi.it>
9  * Paolo Mantegazza <mantegazza@aero.polimi.it>
10  *
11  * Dipartimento di Ingegneria Aerospaziale - Politecnico di Milano
12  * via La Masa, 34 - 20156 Milano, Italy
13  * http://www.aero.polimi.it
14  *
15  * Changing this copyright notice is forbidden.
16  *
17  * This program is free software; you can redistribute it and/or modify
18  * it under the terms of the GNU General Public License as published by
19  * the Free Software Foundation (version 2 of the License).
20  *
21  *
22  * This program is distributed in the hope that it will be useful,
23  * but WITHOUT ANY WARRANTY; without even the implied warranty of
24  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
25  * GNU General Public License for more details.
26  *
27  * You should have received a copy of the GNU General Public License
28  * along with this program; if not, write to the Free Software
29  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
30  */
31 
32 /*
33  AUTHOR: Reinhard Resch <r.resch@secop.com>
34  Copyright (C) 2015(-2017) all rights reserved.
35 
36  The copyright of this code is transferred
37  to Pierangelo Masarati and Paolo Mantegazza
38  for use in the software MBDyn as described
39  in the GNU Public License version 2.1
40 */
41 
42 #ifdef HAVE_CONFIG_H
43 #include "mbconfig.h"
44 #endif
45 
46 #include <vector>
47 #include <drive.h>
48 
49 #include <myassert.h>
50 #include <except.h>
51 #include <mynewmem.h>
52 #include <dataman.h>
53 #include "module-minmaxdrive.h"
54 
56 {
57 protected:
58  MinMaxDriveCaller(const std::vector<DriveOwner>& drives);
59 public:
60  virtual ~MinMaxDriveCaller();
61  bool bIsDifferentiable(void) const;
62  virtual std::ostream& Restart(std::ostream& out) const;
63  doublereal dGet(void) const;
64  doublereal dGetP(void) const;
65  doublereal dGet(const doublereal& dVar) const;
66  virtual doublereal dGetP(const doublereal& dVar) const;
67 
68 protected:
69  virtual bool bCompare(doublereal lhs, doublereal rhs) const = 0;
70  virtual const char *c_str(void) const = 0;
71  typedef std::vector<DriveOwner>::const_iterator iterator;
72  const std::vector<DriveOwner> drives;
73 };
74 
76 {
77 public:
78  MinDriveCaller(const std::vector<DriveOwner>& drives);
79  virtual ~MinDriveCaller(void);
80  virtual DriveCaller* pCopy(void) const;
81 
82 protected:
83  virtual bool bCompare(doublereal lhs, doublereal rhs) const;
84  virtual const char *c_str(void) const;
85 };
86 
88 {
89 public:
90  MaxDriveCaller(const std::vector<DriveOwner>& drives);
91  virtual ~MaxDriveCaller(void);
92  virtual DriveCaller* pCopy(void) const;
93 
94 protected:
95  virtual bool bCompare(doublereal lhs, doublereal rhs) const;
96  virtual const char *c_str(void) const;
97 };
98 
100  const enum Type {
103  } eType;
104 
105  const char *c_str(void) const;
106 
107  explicit MinMaxDriveDCR(enum Type type);
108  DriveCaller *
109  Read(const DataManager* pDM, MBDynParser& HP, bool bDeferred);
110 };
111 
112 MinMaxDriveCaller::MinMaxDriveCaller(const std::vector<DriveOwner>& drives)
113 : DriveCaller(0),
114  drives(drives)
115 {
116  NO_OP;
117 }
118 
120 {
121  NO_OP;
122 }
123 
126 {
127  iterator i = drives.begin();
128  doublereal dVal = i++->dGet();
129 
130  for ( ; i != drives.end(); ++i) {
131  const doublereal dTmp = i->dGet();
132 
133  if (bCompare(dTmp, dVal)) {
134  dVal = dTmp;
135  }
136  }
137 
138  return dVal;
139 }
140 
142 {
143  iterator i = drives.begin();
144  iterator iMin = i;
145  doublereal dVal = i++->dGet();
146 
147  for ( ; i != drives.end(); ++i) {
148  const doublereal dTmp = i->dGet();
149 
150  if (bCompare(dTmp, dVal)) {
151  dVal = dTmp;
152  iMin = i;
153  }
154  }
155 
156  return iMin->dGetP();
157 }
158 
161 {
162  iterator i = drives.begin();
163  doublereal dVal = i++->dGet(dVar);
164 
165  for ( ; i != drives.end(); ++i) {
166  const doublereal dTmp = i->dGet(dVar);
167 
168  if (bCompare(dTmp, dVal)) {
169  dVal = dTmp;
170  }
171  }
172 
173  return dVal;
174 }
175 
177 {
178  iterator i = drives.begin();
179  iterator iMin = i;
180  doublereal dVal = i++->dGet(dVar);
181 
182  for ( ; i != drives.end(); ++i) {
183  const doublereal dTmp = i->dGet(dVar);
184 
185  if (bCompare(dTmp, dVal)) {
186  dVal = dTmp;
187  iMin = i;
188  }
189  }
190 
191  return iMin->dGetP(dVar);
192 }
193 
195 {
196  for (iterator i = drives.begin(); i != drives.end(); ++i) {
197  if (!i->bIsDifferentiable()) {
198  return false;
199  }
200  }
201 
202  return true;
203 }
204 
205 /* Restart */
206 std::ostream&
207 MinMaxDriveCaller::Restart(std::ostream& out) const
208 {
209  out << c_str() << ", "
210  << drives.size() << ", ";
211 
212  for (iterator i = drives.begin(); i != drives.end(); ++i) {
213  i->pGetDriveCaller()->Restart(out);
214 
215  if (drives.end() - i > 1) {
216  out << ", ";
217  }
218  }
219 
220  return out;
221 }
222 
223 MinDriveCaller::MinDriveCaller(const std::vector<DriveOwner>& drives)
224 : MinMaxDriveCaller(drives)
225 {
226  NO_OP;
227 };
228 
230 {
231  NO_OP;
232 }
233 
236 {
237  DriveCaller* pDC = 0;
238 
242 
243  return pDC;
244 }
245 
247 {
248  return lhs < rhs;
249 }
250 
251 const char *MinDriveCaller::c_str(void) const
252 {
253  return "min";
254 }
255 
256 MaxDriveCaller::MaxDriveCaller(const std::vector<DriveOwner>& drives)
257 : MinMaxDriveCaller(drives)
258 {
259  NO_OP;
260 };
261 
263 {
264  NO_OP;
265 }
266 
269 {
270  DriveCaller* pDC = 0;
271 
275 
276  return pDC;
277 }
278 
280 {
281  return lhs > rhs;
282 }
283 
284 const char *MaxDriveCaller::c_str(void) const
285 {
286  return "max";
287 }
288 
290 : eType(type)
291 {
292  NO_OP;
293 }
294 
295 const char *
297 {
298  switch (eType) {
299  case MMD_MIN:
300  return "min";
301  case MMD_MAX:
302  return "max";
303  }
304 
305  ASSERT(0);
307 }
308 
309 DriveCaller *
310 MinMaxDriveDCR::Read(const DataManager* pDM, MBDynParser& HP, bool bDeferred)
311 {
312  DriveCaller *pDC = 0;
313 
314  const integer iNumDrives = HP.GetInt();
315 
316  if (iNumDrives < 1) {
317  silent_cerr("at least one drive caller expected at line " << HP.GetLineData() << std::endl);
319  }
320 
321  std::vector<DriveOwner> drives;
322 
323  drives.reserve(iNumDrives);
324 
325  for (int i = 0; i < iNumDrives; ++i) {
326  drives[i].Set(HP.GetDriveCaller());
327  }
328 
329  switch (eType) {
330  case MMD_MIN:
333  MinDriveCaller(drives));
334  break;
335 
336  case MMD_MAX:
339  MaxDriveCaller(drives));
340  break;
341 
342  default:
343  ASSERT(0);
345  }
346 
347  return pDC;
348 }
349 
350 bool
352 {
354 
355  if (!SetDriveCallerData("min", rf)) {
356  delete rf;
357  return false;
358  }
359 
361 
362  if (!SetDriveCallerData("max", rf)) {
363  delete rf;
364  return false;
365  }
366 
367  return true;
368 }
369 
370 #ifndef STATIC_MODULES
371 
372 extern "C" int
373 module_init(const char *module_name, void *pdm, void *php)
374 {
375  if (!minmaxdrive_set()) {
376  silent_cerr("minmaxdrive: "
377  "module_init(" << module_name << ") "
378  "failed" << std::endl);
379  return -1;
380  }
381 
382  return 0;
383 }
384 
385 #endif // ! STATIC_MODULES
virtual bool bCompare(doublereal lhs, doublereal rhs) const
MinDriveCaller(const std::vector< DriveOwner > &drives)
bool SetDriveCallerData(const char *name, DriveCallerRead *rf)
Definition: drive_.cc:1324
int module_init(const char *module_name, void *pdm, void *php)
This function registers our user defined element for the math parser.
bool minmaxdrive_set()
#define MBDYN_EXCEPT_ARGS
Definition: except.h:63
virtual integer GetInt(integer iDefval=0)
Definition: parser.cc:1050
doublereal dGetP(void) const
MaxDriveCaller(const std::vector< DriveOwner > &drives)
std::vector< DriveOwner >::const_iterator iterator
doublereal dGet(void) const
#define NO_OP
Definition: myassert.h:74
enum MinMaxDriveDCR::Type eType
virtual ~MaxDriveCaller(void)
const char * c_str(void) const
virtual ~MinDriveCaller(void)
virtual const char * c_str(void) const
virtual const char * c_str(void) const
bool bIsDifferentiable(void) const
#define ASSERT(expression)
Definition: colamd.c:977
virtual DriveCaller * pCopy(void) const
#define SAFENEWWITHCONSTRUCTOR(pnt, item, constructor)
Definition: mynewmem.h:698
virtual bool bCompare(doublereal lhs, doublereal rhs) const
virtual DriveCaller * pCopy(void) const
DriveCaller * Read(const DataManager *pDM, MBDynParser &HP, bool bDeferred)
virtual std::ostream & Restart(std::ostream &out) const
DriveCaller * GetDriveCaller(bool bDeferred=false)
Definition: mbpar.cc:2033
const std::vector< DriveOwner > drives
virtual const char * c_str(void) const =0
double doublereal
Definition: colamd.c:52
MinMaxDriveCaller(const std::vector< DriveOwner > &drives)
long int integer
Definition: colamd.c:51
virtual HighParser::ErrOut GetLineData(void) const
Definition: parsinc.cc:697
virtual bool bCompare(doublereal lhs, doublereal rhs) const =0
MinMaxDriveDCR(enum Type type)