Robotran C Documentation
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
mbs_data.h
Go to the documentation of this file.
1 
16 #ifndef mbs_data_h
17 #define mbs_data_h
18 /*--------------------*/
19 
20 #include "stdio.h"
21 #include "stdlib.h"
22 
23 #include "mbs_output_struct.h"
24 #include "mbs_user_interface.h"
25 #include "mbs_project_fct_ptr.h"
26 #include "mbs_realtime_struct.h"
27 
28 /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
29 // utility structure for managing dynamic lib (for userfct and symbolic libraries)
30 
31 #ifdef _WIN32
32  #define WIN32_LEAN_AND_MEAN
33  #include <windows.h>
34 #elif defined(__unix__) || defined(__APPLE__)
35  #include <dlfcn.h>
36 #else
37 #error Platform not supported.
38 #endif
39 
46 typedef struct MbsDataLibInfo{
47 #ifdef _WIN32
48  HINSTANCE lib_handle;
49 #elif defined(__unix__) || defined(__APPLE__)
50  void *lib_handle;
51 #else
52 #error Platform not supported.
53 #endif
55 
56 
57 /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
58 
59 typedef struct{
60 
61  // Pointers to libraries from which the functions were loaded
64 
65  // Pointers to project function
66 
67  // symbolic function pointers are firstly defined to get the same structure
68  // fields ordering with and without realtime
69  struct{
85  } symb;
86 
87  // user function pointers
88  struct{
90  // user load
93  // user dirdyn
97  // user invdyn
101  // user equil
106  // Various project operation
109  // Constraints
113  // Forces
117 
124 
161 
162  // Symbolic derivative function
167 
172 
177 
182 
183  // Function dedicated to Realtime feature
190 
191  // Function to synchronize global variables between instances of outputs
193  } user;
194 
195 } Functions;
196 
200 typedef struct MbsDp{
201  double **K;
202  double **G;
203  double **M;
204 
206  double *dq_dp;
207  double *dqd_dp;
208  double *dqdd_dp;
209 
210  double *dQa_dp;
211  double *dQc_dp;
212 
213  // User joint forces
214  double **dQq_dq;
215  double **dQq_dqd;
217  double **dQq_dqdd;
219  double *dQq_dp;
221 
223  // User external forces
224  double ***dSWr_dq;
225  double ***dSWr_dqd;
227  double ***dSWr_dqdd;
229  double **dSWr_dp;
231 
233  // User link3d forces
234  double*** dSWr_link3d_dq;
235  double*** dSWr_link3d_dqd;
237  double*** dSWr_link3d_dqdd;
239  double** dSWr_link3d_dp;
241 } MbsDp;
243 
244 /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
245 
246 
247 struct MbsData
248 {
249  // Geometric and dynamic data //
250  int npt;
251  double **dpt;
252  double **l;
253  double *m;
254  double **In;
255  double g[3+1];
257 
258  int nbody;
259  int njoint;
261 
262  // Infos partitionning //
263  int nqu;
264  int nqc;
265  int nqlocked;
266  int nqdriven;
267  int nqa;
268  int nqv;
269  int nhu;
270  int nqrot;
271 
272  int *qu;
273  int *qc;
274  int *qlocked;
275  int *qdriven;
277  int *qa;
279  int *qv;
281  int *hu;
282  int *qrot;
283 
284  // Joint coordinates, initial values and trigonometric values //
285  double *q;
286  double *qd;
287  double *qdd;
288 
289  double *q0;
290  double *qd0;
291  double *qdd0;
292 
293  // only for dirdyn and qu, for now :-)
294  double *q_sin;
295  double *q_cos;
297  // for advanced use of Robotran only ! default is 0.
298 
299  // Frc, Trq, Qq, tsim
300  double **frc;
301  double **trq;
302  double *Qq;
303  double *Qa;
304 
305 
306  double tsim;
307 
308  double t0;
309  double tf;
310  double dt0;
311 
312  // Constraints
313  int n_solid;
314  int n_ball;
315  int n_rod;
316  double *lrod;
317  int Nloopc;
318  int Ncons;
319  int Nuserc;
320  double NRerr;
322  double *lambda;
323  double **jac_user;
330  double *jdqd_user;
331 
332  // Driven variables (and joint forces)
333  double *Qc;
334 
336  // Links
337  int Nlink;
338  int Nlink3D;
339  double *Z;
340  double *Zd;
341  double *Fl;
342 
343  double **l3DWr; // JFC : Attention: la convention des indices est inversée par rapport aux habitudes Robotran
358 
359  // Sensors
360  int Nsensor;
361 
362  // Ext Forces
363  int Nxfrc;
364  int *xfidpt;
365  double **SWr;
366 
373 #if !defined SENSORKIN
374  // User Model
381 
391 
392 #endif
393 
394  // User State
395  double *ux;
396  double *uxd;
397  double *ux0;
398  int Nux;
399 
400  // OTHER FIELDS //
401  double *udd;
402 
403  int DonePart;
404  int DoneEquil;
405  int DoneModal;
406 
407  int process;
408  int flag_stop;
417 
420 
421  char *mbs_filename;
422  char *build_path;
423  char *project_path;
424  char *mbs_name;
425 
427 
429 
431 
434 
435  char *mbsysc_path;
436 
437 };
438 
439 /*--------------------*/
440 #endif
MbsData::qrot
int * qrot
Array with the indices of the rotational articulations (incremental values)
Definition: mbs_data.h:282
mbs_link_ptr
void(* mbs_link_ptr)(double **frc, double **trq, double *Flnk, double *Z, double *Zd, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:105
Functions::user_LinkForces_dq
user_LinkForces_d_ptr user_LinkForces_dq
Definition: mbs_data.h:168
mbs_print_user_IO_ptr
void(* mbs_print_user_IO_ptr)(UserIO *uio)
Definition: mbs_project_fct_ptr.h:91
set_mbs_to_output_ptr
int(* set_mbs_to_output_ptr)(MbsData *mbs_data)
Definition: mbs_project_fct_ptr.h:51
mbs_delete_user_IO_ptr
void(* mbs_delete_user_IO_ptr)(UserIO *uvs)
Definition: mbs_project_fct_ptr.h:83
MbsDp::dSWr_dq
double *** dSWr_dq
The derivative matrices of each external force MbsData::SWr vector according to the independent joint...
Definition: mbs_data.h:224
Functions::mbs_check_symbolic
mbs_checksymb_ptr mbs_check_symbolic
Definition: mbs_data.h:80
user_realtime_options_ptr
void(* user_realtime_options_ptr)(MbsData *mbs_data, Realtime_option *options)
Definition: mbs_project_fct_ptr.h:96
MbsData::xfidpt
int * xfidpt
Array of the points defined as force application points.
Definition: mbs_data.h:364
mbs_output_struct.h
Functions::mbs_invdynared_dqdd
mbs_invdynared_d_ptr mbs_invdynared_dqdd
Definition: mbs_data.h:83
mbs_link3D_ptr
void(* mbs_link3D_ptr)(double **frc, double **trq, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:106
MbsData::Ncons
int Ncons
Number of algebraic constraints.
Definition: mbs_data.h:318
MbsDp::M
double ** M
Tangent matrix to acceleration of size [njoint+1, njoint+1].
Definition: mbs_data.h:203
Functions::mbs_invdynared_dqd
mbs_invdynared_d_ptr mbs_invdynared_dqd
Definition: mbs_data.h:82
UserModel
Definition: user_model.h:24
MbsOutputPtr
Definition: mbs_output_struct.h:44
Functions::user_realtime_visu
user_realtime_visu_ptr user_realtime_visu
Definition: mbs_data.h:189
MbsData::qd
double * qd
Array with the current values of the generalized velocities.
Definition: mbs_data.h:286
MbsDp::dSWr_link3d_dqd
double *** dSWr_link3d_dqd
The derivative matrices of each link3d MbsData::SWr vector according to the independent joint velocit...
Definition: mbs_data.h:236
user_LinkForces_d_ptr
double(* user_LinkForces_d_ptr)(double Z, double d_Z, double Zd, double d_Zd, MbsData *mbs_data, double tsim, int i_link, int index)
Definition: mbs_project_fct_ptr.h:55
user_realtime_plot_ptr
void(* user_realtime_plot_ptr)(MbsData *mbs_data)
Definition: mbs_project_fct_ptr.h:100
MbsDp::dQq_dqd
double ** dQq_dqd
The derivative matrix of the joint force vector according to the independent joint velocities: .
Definition: mbs_data.h:216
MbsData::qa
int * qa
Array with the indices of actuated articulations (only for inverse dynamic).
Definition: mbs_data.h:278
MbsData::dt0
double dt0
Initial value of the integration step size [s]. For dirdyn and invdyn only. This parameter is set fro...
Definition: mbs_data.h:310
user_invdyn_finish_ptr
void(* user_invdyn_finish_ptr)(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Definition: mbs_project_fct_ptr.h:34
MbsData::m
double * m
Array containing the mass of each body.
Definition: mbs_data.h:253
MbsData::DonePart
int DonePart
Flag that indicates if the coordinate partitioning module has been executed (default: 0=not done; 1=d...
Definition: mbs_data.h:403
MbsData::user_IO
UserIO * user_IO
Structure containing all the user IO.
Definition: mbs_data.h:386
mbs_save_um_ptr
void(* mbs_save_um_ptr)(FILE *stream, UserModel *ums)
Definition: mbs_project_fct_ptr.h:90
MbsDp::dq_dp
double * dq_dp
derivative of joint position q w.r.t. param p, vector size of [njoint+1].
Definition: mbs_data.h:206
Functions::mbs_cons_hJ
mbs_cons_hJ_ptr mbs_cons_hJ
Definition: mbs_data.h:76
MbsDp::dSWr_dqd
double *** dSWr_dqd
The derivative matrices of each external force MbsData::SWr vector according to the independent joint...
Definition: mbs_data.h:226
Functions::user_equil_finish
user_equil_finish_ptr user_equil_finish
Definition: mbs_data.h:104
MbsData::tsim
double tsim
The time value.
Definition: mbs_data.h:306
MbsData::nqrot
int nqrot
Number of rotational joint (R1, R2 or R3)
Definition: mbs_data.h:270
MbsData::Nlink3D
int Nlink3D
Number of 3D links.
Definition: mbs_data.h:338
UserIoInfo
Contains information about UserIO.
Definition: mbs_user_interface.h:32
MbsData::mbs_filename
char * mbs_filename
Path to mbs file including the file with the extension (.mbs)
Definition: mbs_data.h:421
mbs_dirdyna_ptr
void(* mbs_dirdyna_ptr)(double **M, double *c, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:109
mbs_project_fct_ptr.h
Functions::mbs_invdynared_dp
mbs_invdynared_d_ptr mbs_invdynared_dp
Definition: mbs_data.h:84
MbsData::nqv
int nqv
Number of dependent articulations.
Definition: mbs_data.h:268
Functions::mbs_link
mbs_link_ptr mbs_link
Definition: mbs_data.h:70
Functions::mbs_new_user_model
mbs_new_user_model_ptr mbs_new_user_model
Definition: mbs_data.h:125
MbsData::DoneEquil
int DoneEquil
Flag that indicates if the equilibrium module has been executed (default: 0=not done; 1=done).
Definition: mbs_data.h:404
mbs_checksymb_ptr
int(* mbs_checksymb_ptr)(MbsData *s)
Definition: mbs_project_fct_ptr.h:115
MbsData::qc
int * qc
Array with the indices of driven (locked and driven) articulations.
Definition: mbs_data.h:273
MbsData::ux0
double * ux0
Array with the initial values of the user variables.
Definition: mbs_data.h:397
Functions::mbs_invdyna
mbs_invdyna_ptr mbs_invdyna
Definition: mbs_data.h:75
mbs_delete_user_model_ptr
void(* mbs_delete_user_model_ptr)(UserModel *ums)
Definition: mbs_project_fct_ptr.h:82
MbsData::nqu
int nqu
Number of independent articulations.
Definition: mbs_data.h:263
mbs_save_user_IO_ptr
void(* mbs_save_user_IO_ptr)(FILE *stream, UserIO *uio)
Definition: mbs_project_fct_ptr.h:92
MbsData::njoint
int njoint
Number of joints in the system.
Definition: mbs_data.h:260
MbsData::tf
double tf
Final time of the simulation [s]. For dirdyn and invdyn only. This parameter is set from dirdyn/invyn...
Definition: mbs_data.h:309
MbsDp::G
double ** G
Damping matrix of size [njoint+1, njoint+1].
Definition: mbs_data.h:202
MbsData::npt
int npt
Number of anchor points.
Definition: mbs_data.h:250
MbsDp::dSWr_link3d_dq
double *** dSWr_link3d_dq
The derivative matrices of each link3d MbsData::SWr vector according to the independent joint coordin...
Definition: mbs_data.h:234
Functions::mbs_delete_user_model
mbs_delete_user_model_ptr mbs_delete_user_model
Definition: mbs_data.h:126
Functions::user_equil_init
user_equil_init_ptr user_equil_init
Definition: mbs_data.h:102
mbs_accelred_ptr
int(* mbs_accelred_ptr)(MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:108
Functions::user_dirdyn_init
user_dirdyn_init_ptr user_dirdyn_init
Definition: mbs_data.h:94
MbsData::n_ball
int n_ball
Number of ball constraint in the system.
Definition: mbs_data.h:314
Functions::user_equil_loop
user_equil_loop_ptr user_equil_loop
Definition: mbs_data.h:103
Functions::user_synch_outputs
set_mbs_to_output_ptr user_synch_outputs
Definition: mbs_data.h:192
Functions::mbs_save_um
mbs_save_um_ptr mbs_save_um
Definition: mbs_data.h:147
UserIO
Definition: user_IO.h:25
Functions::user_dirdyn_loop
user_dirdyn_loop_ptr user_dirdyn_loop
Definition: mbs_data.h:95
mbs_realtime_struct.h
Functions::user_invdyn_finish
user_invdyn_finish_ptr user_invdyn_finish
Definition: mbs_data.h:100
MbsData::Nux
int Nux
Number of user variable.
Definition: mbs_data.h:398
MbsData::flag_jac_position
int flag_jac_position
Flag to compute the Jacobian of the constraint for position or velocity solution.
Definition: mbs_data.h:410
MbsData::jac_user
double ** jac_user
Jacobian of constraints [nqv x njoint] (starting at 1), only used in symbolic accelred,...
Definition: mbs_data.h:329
MbsData::zero_division_thrs
double zero_division_thrs
Value from which a warning is raised if a division by zero (or close to) occurs. Default=1....
Definition: mbs_data.h:419
Functions::user_JointForces_dqdd
user_JointForces_d_ptr user_JointForces_dqdd
Definition: mbs_data.h:165
Functions::user_ExtForces
user_ExtForces_ptr user_ExtForces
Definition: mbs_data.h:116
MbsData::mbs_dp
MbsDp * mbs_dp
Structure to store the matrix of tangent analysis (symbolic).
Definition: mbs_data.h:428
MbsData::DoneModal
int DoneModal
Flag that indicates if the modal module has been executed (default: 0=not done; 1=done).
Definition: mbs_data.h:405
Functions::mbs_dirdyna
mbs_dirdyna_ptr mbs_dirdyna
Definition: mbs_data.h:74
Functions::user_joystick_axes
user_joystick_axes_ptr user_joystick_axes
Definition: mbs_data.h:187
user_ExtForces_d_ptr
double *(* user_ExtForces_d_ptr)(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4], double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4], double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4], MbsData *s, double tsim, int i_force, int index)
Definition: mbs_project_fct_ptr.h:68
MbsData::flag_optim_symb_sin_cos
int flag_optim_symb_sin_cos
allow the "optimisation" of the computation of the sine/cosine in the symbolic files....
Definition: mbs_data.h:296
mbs_new_user_IO_ptr
UserIO *(* mbs_new_user_IO_ptr)(UserIoInfo *ioInfo)
Definition: mbs_project_fct_ptr.h:80
MbsData::SWr
double ** SWr
Array of Swr vector for each external forces.
Definition: mbs_data.h:365
user_Link3DForces_d_ptr
double *(* user_Link3DForces_d_ptr)(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4], double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4], double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4], MbsData *s, double tsim, int i_link3d, int index)
Definition: mbs_project_fct_ptr.h:59
Functions::mbs_link3D
mbs_link3D_ptr mbs_link3D
Definition: mbs_data.h:71
MbsData::mbsysc_path
char * mbsysc_path
Installation directory of MBsysC.
Definition: mbs_data.h:435
MbsData::q_cos
double * q_cos
Array with the cosine values of the generalized coordinates, if rotational (if translational,...
Definition: mbs_data.h:295
mbs_extforces_ptr
void(* mbs_extforces_ptr)(double **frc, double **trq, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:107
Functions::user_Link3DForces
user_Link3DForces_ptr user_Link3DForces
Definition: mbs_data.h:115
user_cons_hJ_ptr
void(* user_cons_hJ_ptr)(double *h, double **Jac, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:41
MbsData::hu
int * hu
Array with the indices of independent constraints.
Definition: mbs_data.h:281
MbsDp::dSWr_link3d_dp
double ** dSWr_link3d_dp
The derivative matrices of each link3d MbsData::SWr vector according to the specified parameter: .
Definition: mbs_data.h:240
MbsDp::dSWr_dp
double ** dSWr_dp
The derivative matrices of each external force MbsData::SWr vector according to the specified paramet...
Definition: mbs_data.h:230
MbsData::Nxfrc
int Nxfrc
Number of points where an external force is applied into a body.
Definition: mbs_data.h:363
user_Link3DForces_dp_ptr
double *(* user_Link3DForces_dp_ptr)(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4], double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4], double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4], MbsData *s, double tsim, int i_link3d)
Definition: mbs_project_fct_ptr.h:63
user_joystick_buttons_ptr
void(* user_joystick_buttons_ptr)(MbsData *mbs_data, int buttonID)
Definition: mbs_project_fct_ptr.h:102
MbsDp::dSWr_dqdd
double *** dSWr_dqdd
The derivative matrices of each external force MbsData::SWr vector according to the independent joint...
Definition: mbs_data.h:228
user_keyboard_ptr
void(* user_keyboard_ptr)(MbsData *mbs_data, Simu_realtime *realtime, int cur_t_usec, const Uint8 *keystates)
Definition: mbs_project_fct_ptr.h:99
Functions::user_joystick_buttons
user_joystick_buttons_ptr user_joystick_buttons
Definition: mbs_data.h:188
user_JointForces_dp_ptr
double *(* user_JointForces_dp_ptr)(MbsData *mbs_data, double tsim)
Definition: mbs_project_fct_ptr.h:54
MbsData::realtime
Simu_realtime * realtime
Pointer to Simu_realtime structure.
Definition: mbs_data.h:430
MbsData::qd0
double * qd0
Array with the initial values of the generalized velocities.
Definition: mbs_data.h:290
Functions::mbs_get_user_model_list
mbs_get_user_model_list_ptr mbs_get_user_model_list
Definition: mbs_data.h:146
Functions::mbs_print_user_IO
mbs_print_user_IO_ptr mbs_print_user_IO
Print the current UserIO values.
Definition: mbs_data.h:153
MbsData::Nlink
int Nlink
Number of forces acting between two points of the system (force law implemented in user_LinkForces())...
Definition: mbs_data.h:337
Functions
Definition: mbs_data.h:59
MbsDp::dQq_dp
double * dQq_dp
The derivative vector of the joint force vector according to the specified parameter: .
Definition: mbs_data.h:220
mbs_load_user_model_ptr
void(* mbs_load_user_model_ptr)(MbsInfos *mbs_infos, UserModel *ums)
Definition: mbs_project_fct_ptr.h:87
Functions::mbs_load_user_model
mbs_load_user_model_ptr mbs_load_user_model
Definition: mbs_data.h:142
user_cons_J_accelred_ptr
void(* user_cons_J_accelred_ptr)(MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:43
Functions::user_Link3DForces_dqd
user_Link3DForces_d_ptr user_Link3DForces_dqd
Definition: mbs_data.h:174
Functions::user_keyboard
user_keyboard_ptr user_keyboard
Definition: mbs_data.h:185
user_LinkForces_ptr
double(* user_LinkForces_ptr)(double Z, double Zd, MbsData *mbs_data, double tsim, int ilnk)
Definition: mbs_project_fct_ptr.h:44
MbsData::flag_safety_checks
int flag_safety_checks
Flag to activate safety checks everywhere in mbsysc core. Faster computation if this flag is put to 0...
Definition: mbs_data.h:418
Functions::user_free
user_free_ptr user_free
Definition: mbs_data.h:92
MbsData::__user_IO_info
UserIoInfo * __user_IO_info
Details of the user IO loaded from multibody file.
Definition: mbs_data.h:390
mbs_new_user_model_ptr
UserModel *(* mbs_new_user_model_ptr)()
Definition: mbs_project_fct_ptr.h:81
Functions::mbs_sensor
mbs_sensor_ptr mbs_sensor
Definition: mbs_data.h:78
MbsData::MAX_NR_ITER
int MAX_NR_ITER
Maximal number of iterations for NR procedure, default 100.
Definition: mbs_data.h:321
MbsData::Nuserc
int Nuserc
Number of user constraints.
Definition: mbs_data.h:319
Functions::user_equil_fxe
user_equil_fxe_ptr user_equil_fxe
Definition: mbs_data.h:105
MbsData::Fl
double * Fl
Array with the current values of the forces on each link (see: user_LinkForces()).
Definition: mbs_data.h:341
MbsData::qu
int * qu
Array with the indices of the independent articulations (free)
Definition: mbs_data.h:272
user_Derivative_ptr
void(* user_Derivative_ptr)(MbsData *s)
Definition: mbs_project_fct_ptr.h:39
MbsData::NRerr
double NRerr
Maximal error on constraint allowed in Newton-Raphson algorithm, default 1.0e-9.
Definition: mbs_data.h:320
MbsDp::dQq_dq
double ** dQq_dq
The derivative matrix of the joint force vector according to the independent joint coordinates: .
Definition: mbs_data.h:214
MbsData::trq
double ** trq
Matrix with the components of the resultant external torques (pure torque and couple produced by forc...
Definition: mbs_data.h:301
MbsData::qv
int * qv
Array with the indices of the dependent articulations .
Definition: mbs_data.h:280
Functions::user_Link3DForces_dq
user_Link3DForces_d_ptr user_Link3DForces_dq
Definition: mbs_data.h:173
MbsData::Qc
double * Qc
Array with the value of joint force introduced in driven joint to respect the user function.
Definition: mbs_data.h:333
MbsData::Nloopc
int Nloopc
Number of loop constraints.
Definition: mbs_data.h:317
user_JointForces_ptr
double *(* user_JointForces_ptr)(MbsData *, double)
Definition: mbs_project_fct_ptr.h:26
Functions::mbs_extforces
mbs_extforces_ptr mbs_extforces
Definition: mbs_data.h:72
Functions::user_cons_hJ
user_cons_hJ_ptr user_cons_hJ
Definition: mbs_data.h:110
MbsData::Zd
double * Zd
Array with the current values of the speed (spreading) between of the points of a link (see: user_Lin...
Definition: mbs_data.h:340
Functions::user_LinkForces
user_LinkForces_ptr user_LinkForces
Definition: mbs_data.h:114
MbsData::Qq
double * Qq
Array with the values of the joint forces.
Definition: mbs_data.h:302
mbs_invdynared_d_ptr
void(* mbs_invdynared_d_ptr)(MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:116
MbsData::q
double * q
Array with the current values of the generalized coordinates.
Definition: mbs_data.h:285
MbsData::In
double ** In
Array containing the inertia tensor component of each body (in the body fixed frame,...
Definition: mbs_data.h:254
MbsData::Nsensor
int Nsensor
< Array of l3DWr vector for each 3D link forces.
Definition: mbs_data.h:360
user_realtime_visu_ptr
void(* user_realtime_visu_ptr)(MbsData *mbs_data, int nb_models, int *nb_q, double **q_vec)
Definition: mbs_project_fct_ptr.h:103
Functions::user_ExtForces_dp
user_ExtForces_dp_ptr user_ExtForces_dp
Definition: mbs_data.h:181
MbsData::project_path
char * project_path
Path to the mbs project folder.
Definition: mbs_data.h:423
Functions::user_Link3DForces_dp
user_Link3DForces_dp_ptr user_Link3DForces_dp
Definition: mbs_data.h:176
Functions::symbolicLibHandle
MbsDataLibInfo * symbolicLibHandle
Definition: mbs_data.h:62
Functions::user_realtime_plot
user_realtime_plot_ptr user_realtime_plot
Definition: mbs_data.h:186
MbsData::nqdriven
int nqdriven
Number of driven articulations.
Definition: mbs_data.h:266
Functions::user_JointForces_dqd
user_JointForces_d_ptr user_JointForces_dqd
Definition: mbs_data.h:164
Functions::user_realtime_options
user_realtime_options_ptr user_realtime_options
Definition: mbs_data.h:184
user_DrivenJoints_ptr
void(* user_DrivenJoints_ptr)(MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:40
MbsData::fct
Functions fct
Structure to store the pointer to the project-specific functions.
Definition: mbs_data.h:426
Functions::user_Derivative
user_Derivative_ptr user_Derivative
Definition: mbs_data.h:107
user_invdyn_init_ptr
void(* user_invdyn_init_ptr)(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Definition: mbs_project_fct_ptr.h:32
mbs_cons_hJ_ptr
void(* mbs_cons_hJ_ptr)(double *h, double **Jac, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:111
Functions::user_invdyn_loop
user_invdyn_loop_ptr user_invdyn_loop
Definition: mbs_data.h:99
Functions::mbs_get_user_model_size
mbs_get_user_model_size_ptr mbs_get_user_model_size
Definition: mbs_data.h:145
MbsData::frc
double ** frc
Matrix with the components of the resultant external forces (in the body fixed frame) applied to the ...
Definition: mbs_data.h:300
MbsDp::dQq_dqdd
double ** dQq_dqdd
The derivative matrix of the joint force vector according to the independent joint accelerations: .
Definition: mbs_data.h:218
mbs_cons_jdqd_ptr
void(* mbs_cons_jdqd_ptr)(double *Jdqd, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:112
MbsData::nqc
int nqc
Number of driven articulations, it includes qlocked and qdriven.
Definition: mbs_data.h:264
mbs_bind_user_model_ptr
void(* mbs_bind_user_model_ptr)(MbsInfos *mbs_infos, UserModel *ums)
Definition: mbs_project_fct_ptr.h:88
user_invdyn_loop_ptr
void(* user_invdyn_loop_ptr)(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Definition: mbs_project_fct_ptr.h:33
MbsDp::dQc_dp
double * dQc_dp
Derivative of Q driven w.r.t. param p, vector size of [njoint+1].
Definition: mbs_data.h:211
MbsData::l3DWr
double ** l3DWr
Definition: mbs_data.h:343
MbsDataLibInfo
This structures contains a reference to a dynamic library handle.
Definition: mbs_data.h:46
MbsData::user_model
UserModel * user_model
Structure containing all user models.
Definition: mbs_data.h:380
Functions::user_LinkForces_dp
user_LinkForces_dp_ptr user_LinkForces_dp
Definition: mbs_data.h:171
Functions::mbs_print_user_model
mbs_print_user_model_ptr mbs_print_user_model
Definition: mbs_data.h:144
user_LinkForces_dp_ptr
double(* user_LinkForces_dp_ptr)(double Z, double d_Z, double Zd, double d_Zd, MbsData *mbs_data, double tsim, int i_link)
Definition: mbs_project_fct_ptr.h:57
Functions::mbs_accelred
mbs_accelred_ptr mbs_accelred
Definition: mbs_data.h:73
MbsData::dpt
double ** dpt
Array containing the coordinate of all anchor points (3+1 lines, npt+1 columns).
Definition: mbs_data.h:251
mbs_get_user_model_size_ptr
void(* mbs_get_user_model_size_ptr)(int *n_usr_model)
Definition: mbs_project_fct_ptr.h:85
MbsDp::K
double ** K
Stiffness matrix of size [njoint+1, njoint+1].
Definition: mbs_data.h:201
MbsData::mbs_name
char * mbs_name
Name of the mbs project as it is stored in the xml file.
Definition: mbs_data.h:424
MbsDp::dSWr_link3d_dqdd
double *** dSWr_link3d_dqdd
The derivative matrices of each link3d MbsData::SWr vector according to the independent joint acceler...
Definition: mbs_data.h:238
user_cons_jdqd_ptr
void(* user_cons_jdqd_ptr)(double *jdqd, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:42
user_equil_finish_ptr
void(* user_equil_finish_ptr)(MbsData *, MbsEquil *)
Definition: mbs_project_fct_ptr.h:37
MbsData::q0
double * q0
Array with the initial values of the generalized coordinates.
Definition: mbs_data.h:289
MbsData
Definition: mbs_data.h:247
MbsData::n_solid
int n_solid
Number of solid constraint in the system.
Definition: mbs_data.h:313
Functions::mbs_get_user_IO_size
mbs_get_user_IO_size_ptr mbs_get_user_IO_size
Get the size of the UserIO structure inside the user_IO.c file.
Definition: mbs_data.h:141
Functions::mbs_gensensor
mbs_gensensor_ptr mbs_gensensor
Definition: mbs_data.h:79
MbsData::n_rod
int n_rod
Number of rod constraint in the system.
Definition: mbs_data.h:315
Simu_realtime
real-time structure
Definition: mbs_realtime_struct.h:133
MbsDp::dqdd_dp
double * dqdd_dp
derivative of joint acceleration qdd w.r.t. param p, vector size of [njoint+1].
Definition: mbs_data.h:208
Functions::user_cons_J_accelred
user_cons_J_accelred_ptr user_cons_J_accelred
Definition: mbs_data.h:112
Functions::user_ExtForces_dqd
user_ExtForces_d_ptr user_ExtForces_dqd
Definition: mbs_data.h:179
Functions::user_Link3DForces_dqdd
user_Link3DForces_d_ptr user_Link3DForces_dqdd
Definition: mbs_data.h:175
Functions::userfctLibHandle
MbsDataLibInfo * userfctLibHandle
Definition: mbs_data.h:63
MbsData::qlocked
int * qlocked
Array with the indices of locked articulations.
Definition: mbs_data.h:274
MbsData::Qa
double * Qa
Array of active joint forces (in case of simulink,invdyna,equil,linearization,...)
Definition: mbs_data.h:303
user_equil_loop_ptr
void(* user_equil_loop_ptr)(MbsData *MBSdata, MbsEquil *mbs_equil)
Definition: mbs_project_fct_ptr.h:36
Functions::user_load_post
user_load_post_ptr user_load_post
Definition: mbs_data.h:91
MbsData::Nuser_model
int Nuser_model
Number of declared user models in MBsysPad, retrieved from the multibody file.
Definition: mbs_data.h:376
MbsData::build_path
char * build_path
Path to the build folder.
Definition: mbs_data.h:422
Functions::mbs_new_user_IO
mbs_new_user_IO_ptr mbs_new_user_IO
Initialize the UserIO structure and bind the ioInfo pointer to the allocated memory (project specific...
Definition: mbs_data.h:123
MbsData::process
int process
Flag that indicate which module is currently running (1=partitioning, 2=equilibrium,...
Definition: mbs_data.h:407
MbsData::nbody
int nbody
Number of bodies in the system.
Definition: mbs_data.h:258
MbsDp
Structure related to tangent matrices computations.
Definition: mbs_data.h:200
MbsData::l
double ** l
Array containing the center of mass coordinates (in the body fixed frame, one column per body includi...
Definition: mbs_data.h:252
Functions::user_JointForces_dq
user_JointForces_d_ptr user_JointForces_dq
Definition: mbs_data.h:163
user_dirdyn_loop_ptr
void(* user_dirdyn_loop_ptr)(MbsData *MBSdata, MbsDirdyn *mbs_dd)
Definition: mbs_project_fct_ptr.h:30
MbsData::t0
double t0
Initial time of the simulation [s]. For dirdyn and invdyn only. This parameter is set from dirdyn/inv...
Definition: mbs_data.h:308
MbsDp::dqd_dp
double * dqd_dp
derivative of joint velocity qd w.r.t. param p, vector size of [njoint+1].
Definition: mbs_data.h:207
user_dirdyn_finish_ptr
void(* user_dirdyn_finish_ptr)(MbsData *, MbsDirdyn *)
Definition: mbs_project_fct_ptr.h:31
Functions::user_cons_jdqd
user_cons_jdqd_ptr user_cons_jdqd
Definition: mbs_data.h:111
user_JointForces_d_ptr
double *(* user_JointForces_d_ptr)(MbsData *mbs_data, double tsim, int index)
Definition: mbs_project_fct_ptr.h:53
Functions::user_DrivenJoints
user_DrivenJoints_ptr user_DrivenJoints
Definition: mbs_data.h:108
Functions::user_invdyn_init
user_invdyn_init_ptr user_invdyn_init
Definition: mbs_data.h:98
MbsData::Z
double * Z
Array with the current values of the distances between of the points of a link (see: user_LinkForces(...
Definition: mbs_data.h:339
mbs_invdyna_ptr
void(* mbs_invdyna_ptr)(double *Q, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:110
MbsData::g
double g[3+1]
The 3 gravity components.
Definition: mbs_data.h:256
MbsData::flag_stop
int flag_stop
stop the simulation in case of non zero value. Negative for error, positive for user_wanted behavior.
Definition: mbs_data.h:409
mbs_user_interface.h
MbsDp::dQa_dp
double * dQa_dp
[Inverse Dynamics] derivative of Q actuated w.r.t. param p, vector size of [njoint+1].
Definition: mbs_data.h:210
user_equil_fxe_ptr
void(* user_equil_fxe_ptr)(MbsData *, double *f)
Definition: mbs_project_fct_ptr.h:38
Functions::user_JointForces_dp
user_JointForces_dp_ptr user_JointForces_dp
Definition: mbs_data.h:166
user_joystick_axes_ptr
void(* user_joystick_axes_ptr)(MbsData *mbs_data, Simu_realtime *realtime, int nb_joysticks)
Definition: mbs_project_fct_ptr.h:101
mbs_get_user_IO_size_ptr
void(* mbs_get_user_IO_size_ptr)(int *n_in, int *n_out, int *n_user_IO)
Definition: mbs_project_fct_ptr.h:84
MbsData::user_outputs
MbsOutputPtr user_outputs
Structure to share outputs between different process/libraries.
Definition: mbs_data.h:432
Functions::mbs_bind_user_model
mbs_bind_user_model_ptr mbs_bind_user_model
Definition: mbs_data.h:143
mbs_gensensor_ptr
void(* mbs_gensensor_ptr)(MbsSensor *sens, MbsData *s, int isens)
Definition: mbs_project_fct_ptr.h:114
mbs_get_user_model_list_ptr
void(* mbs_get_user_model_list_ptr)(int *user_model_list)
Definition: mbs_project_fct_ptr.h:86
MbsData::qdriven
int * qdriven
Array with the indices of driven articulations.
Definition: mbs_data.h:276
MbsData::lambda
double * lambda
Array with the values of the Lagrange Multipliers related to the constraints.
Definition: mbs_data.h:322
MbsData::uxd
double * uxd
Array with the values of the time derivatives of the user variables.
Definition: mbs_data.h:396
user_free_ptr
void(* user_free_ptr)(MbsData *MBSdata)
Definition: mbs_project_fct_ptr.h:28
MbsData::q_sin
double * q_sin
Array with the sine values of the generalized coordinates, if rotational (if translational,...
Definition: mbs_data.h:294
MbsData::qdd0
double * qdd0
Array with the initial values of the generalized acceleration.
Definition: mbs_data.h:291
user_equil_init_ptr
void(* user_equil_init_ptr)(MbsData *MBSdata, MbsEquil *mbs_equil)
Definition: mbs_project_fct_ptr.h:35
MbsData::nqa
int nqa
Number of actuated articulations.
Definition: mbs_data.h:267
Functions::mbs_delete_user_IO
mbs_delete_user_IO_ptr mbs_delete_user_IO
Free the memory associated to the given UserIO structure.
Definition: mbs_data.h:131
MbsData::nqlocked
int nqlocked
Number of locked articulations.
Definition: mbs_data.h:265
user_ExtForces_dp_ptr
double *(* user_ExtForces_dp_ptr)(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4], double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4], double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4], MbsData *s, double tsim, int i_force)
Definition: mbs_project_fct_ptr.h:73
Functions::user_ExtForces_dqdd
user_ExtForces_d_ptr user_ExtForces_dqdd
Definition: mbs_data.h:180
user_Link3DForces_ptr
double *(* user_Link3DForces_ptr)(double PxF[4], double RxF[4][4], double VxF[4], double OMxF[4], double AxF[4], double OMPxF[4], MbsData *s, double tsim, int ixF)
Definition: mbs_project_fct_ptr.h:45
Functions::mbs_save_user_IO
mbs_save_user_IO_ptr mbs_save_user_IO
Save the current UserIO values into a file stream.
Definition: mbs_data.h:160
Functions::user_LinkForces_dqd
user_LinkForces_d_ptr user_LinkForces_dqd
Definition: mbs_data.h:169
MbsData::qdd
double * qdd
Array with the current values of the generalized acceleration.
Definition: mbs_data.h:287
Functions::mbs_cons_jdqd
mbs_cons_jdqd_ptr mbs_cons_jdqd
Definition: mbs_data.h:77
MbsData::jdqd_user
double * jdqd_user
Vector of jdqd for user constraints [nqv] (starting at 1), only used in symbolic accelred,...
Definition: mbs_data.h:330
Functions::user_LinkForces_dqdd
user_LinkForces_d_ptr user_LinkForces_dqdd
Definition: mbs_data.h:170
mbs_sensor_ptr
void(* mbs_sensor_ptr)(MbsSensor *sens, MbsData *s, int isens)
Definition: mbs_project_fct_ptr.h:113
MbsData::udd
double * udd
For axelle red: array with the values of the acceleration of independent coordinate.
Definition: mbs_data.h:401
MbsData::ux
double * ux
Array with the values of the user variables.
Definition: mbs_data.h:395
Functions::mbs_invdynared_dq
mbs_invdynared_d_ptr mbs_invdynared_dq
Definition: mbs_data.h:81
user_dirdyn_init_ptr
void(* user_dirdyn_init_ptr)(MbsData *MBSdata, MbsDirdyn *mbs_dd)
Definition: mbs_project_fct_ptr.h:29
mbs_print_user_model_ptr
void(* mbs_print_user_model_ptr)(UserModel *ums, FILE *fs)
Definition: mbs_project_fct_ptr.h:89
user_ExtForces_ptr
double *(* user_ExtForces_ptr)(double PxF[4], double RxF[4][4], double VxF[4], double OMxF[4], double AxF[4], double OMPxF[4], MbsData *s, double tsim, int ixF)
Definition: mbs_project_fct_ptr.h:46
Functions::user_JointForces
user_JointForces_ptr user_JointForces
Definition: mbs_data.h:89
MbsData::nhu
int nhu
Number of independent constraints.
Definition: mbs_data.h:269
MbsData::lrod
double * lrod
Array with the length of each rod.
Definition: mbs_data.h:316
MbsData::n_user_IO
int n_user_IO
Number of declared user IO in MBsysPad, retrieved from the file.
Definition: mbs_data.h:383
user_load_post_ptr
void(* user_load_post_ptr)(MbsData *MBSdata, MbsLoader *mbs_loader)
Definition: mbs_project_fct_ptr.h:27
Functions::user_dirdyn_finish
user_dirdyn_finish_ptr user_dirdyn_finish
Definition: mbs_data.h:96
Functions::user_ExtForces_dq
user_ExtForces_d_ptr user_ExtForces_dq
Definition: mbs_data.h:178