Robotran C Documentation
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_user_interface.h"
24 
25 #include "mbs_project_fct_ptr.h"
26 
27 /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
28 // utility structure for managing dynamic lib (for userfct and symbolic libraries)
29 
30 #ifdef PRJ_FCT_PTR
31 
32 #ifdef UNIX
33  #include <dlfcn.h>
34 #else
35  #define WIN32_LEAN_AND_MEAN
36  #include <windows.h>
37 #endif
38 
45 typedef struct MbsDataLibInfo{
46  #ifdef UNIX
47  void *lib_handle;
48  #else
49  HINSTANCE lib_handle;
50  #endif
52 
53 #endif
54 
55 /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
56 
57 #ifdef PRJ_FCT_PTR
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{
80  } symb;
81 
82  // user function pointers
83  struct{
85  // user load
88  // user dirdyn
92  // user invdyn
96  // user equil
101 
110 
124 
125  #ifdef REAL_TIME
127 
128  #ifdef SDL
129  user_keyboard_ptr user_keyboard;
130  user_realtime_plot_ptr user_realtime_plot;
131  user_joystick_axes_ptr user_joystick_axes;
132  user_joystick_buttons_ptr user_joystick_buttons;
133  #endif
134 
135  #ifdef VISU_3D
136  user_realtime_visu_ptr user_realtime_visu;
137  #endif
138  #endif
139  } user;
140 
141 } Functions;
142 
143 #endif
144 
145 
146 /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
147 
148 
149 struct MbsData
150 {
151  // Geometric and dynamic data //
152  int npt;
153  double **dpt;
154  double **l;
155  double *m;
156  double **In;
157  double g[3+1];
159 
160  int nbody;
161  int njoint;
163 
164  // Infos partitionnement //
165  int nqu;
166  int nqc;
167  int nqlocked;
168  int nqdriven;
169  int nqa;
170  int nqv;
171  int nhu;
172  int nqrot;
173 
174  int *qu;
175  int *qc;
176  int *qlocked;
177  int *qdriven;
179  int *qa;
181  int *qv;
183  int *hu;
184  int *qrot;
185 
186  // Joint coordinates, initial values and trigonometric values //
187  double *q;
188  double *qd;
189  double *qdd;
190 
191  double *q0;
192  double *qd0;
193  double *qdd0;
194 
195  // only for dirdyn and qu, for now :-)
196  double *q_sin;
197  double *q_cos;
199  // for advanced use of Robotran only ! default is 0.
200 
201  // Frc, Trq, Qq, tsim
202  double **frc;
203  double **trq;
204  double *Qq;
205  double *Qa;
206 
207 
208  double tsim;
209 
210  double t0;
211  double tf;
212  double dt0;
213 
214  // Constraints
215  int n_rod;
216  double *lrod;
217  int Nloopc;
218  int Ncons;
219  int Nuserc;
220  double NRerr;
222  double *lambda;
223  double **jac_user;
230  double *jdqd_user;
231 
232  // Driven variables (and joint forces)
233  double *Qc;
234 
236  // Links
237  int Nlink;
238  int Nlink3D;
239  double *Z;
240  double *Zd;
241  double *Fl;
242 
243  double **l3DWr; // JFC : Attention: la convention des indices est inversée par rapport aux habitudes Robotran
258 
259  // Sensors
260  int Nsensor;
261 
262  // Ext Forces
263  int Nxfrc;
264  int *xfidpt;
265  double **SWr;
266 
273 #if !defined SENSORKIN
274  // User Model
277 
281 
282 #endif
283 
284  // User State
285  double *ux;
286  double *uxd;
287  double *ux0;
288  int Nux;
289 
290  // OTHER FIELDS //
291  double *udd;
292 
293  int DonePart;
294  int DoneEquil;
295  int DoneModal;
296 
297  int process;
298  int flag_stop;
306 
309 
310  char *mbs_filename;
311  char *build_path;
312  char *project_path;
313  char *mbs_name;
314 
315  #ifdef PRJ_FCT_PTR
317  #endif
318 
319  #ifdef REAL_TIME
320  // This is set at the end of the structure to allow python (Ctypes) loading
321  // with and without real time activated
322  void *realtime;
323  #endif
324 
325 };
326 
327 /*--------------------*/
328 #endif
MbsData::qrot
int * qrot
Array with the indices of the rotational articulations (incremental values)
Definition: mbs_data.h:184
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:84
mbs_print_user_IO_ptr
void(* mbs_print_user_IO_ptr)(UserIO *uio)
Definition: mbs_project_fct_ptr.h:59
mbs_delete_user_IO_ptr
void(* mbs_delete_user_IO_ptr)(UserIO *uvs)
Definition: mbs_project_fct_ptr.h:51
user_realtime_options_ptr
void(* user_realtime_options_ptr)(MbsData *mbs_data, Realtime_option *options)
Definition: mbs_project_fct_ptr.h:66
MbsData::xfidpt
int * xfidpt
Array of the points defined as force application points.
Definition: mbs_data.h:264
mbs_link3D_ptr
void(* mbs_link3D_ptr)(double **frc, double **trq, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:85
MbsData::Ncons
int Ncons
Number of algebraic constraints.
Definition: mbs_data.h:218
UserModel
Definition: user_model.h:24
MbsData::qd
double * qd
Array with the current values of the generalized velocities.
Definition: mbs_data.h:188
MbsData::qa
int * qa
Array with the indices of actuated articulations (only for inverse dynamic).
Definition: mbs_data.h:180
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:212
user_invdyn_finish_ptr
void(* user_invdyn_finish_ptr)(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Definition: mbs_project_fct_ptr.h:28
MbsData::m
double * m
Array containing the mass of each body.
Definition: mbs_data.h:155
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:293
MbsData::user_IO
UserIO * user_IO
Definition: mbs_data.h:279
mbs_save_um_ptr
void(* mbs_save_um_ptr)(FILE *stream, UserModel *ums)
Definition: mbs_project_fct_ptr.h:58
Functions::mbs_cons_hJ
mbs_cons_hJ_ptr mbs_cons_hJ
Definition: mbs_data.h:76
Functions::user_equil_finish
user_equil_finish_ptr user_equil_finish
Definition: mbs_data.h:99
MbsData::tsim
double tsim
The time value.
Definition: mbs_data.h:208
MbsData::nqrot
int nqrot
Number of rotational joint (R1, R2 or R3)
Definition: mbs_data.h:172
MbsData::Nlink3D
int Nlink3D
Number of 3D links.
Definition: mbs_data.h:238
UserIoInfo
Contains information about UserIO.
Definition: mbs_user_interface.h:44
MbsData::mbs_filename
char * mbs_filename
Path to mbs file including the file with the extension (.mbs)
Definition: mbs_data.h:310
mbs_dirdyna_ptr
void(* mbs_dirdyna_ptr)(double **M, double *c, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:88
mbs_project_fct_ptr.h
MbsData::nqv
int nqv
Number of dependent articulations.
Definition: mbs_data.h:170
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:112
MbsData::DoneEquil
int DoneEquil
Flag that indicates if the equilibrium module has been executed (default: 0=not done; 1=done).
Definition: mbs_data.h:294
MbsData::qc
int * qc
Array with the indices of driven (locked and driven) articulations.
Definition: mbs_data.h:175
MbsData::ux0
double * ux0
Array with the initial values of the user variables.
Definition: mbs_data.h:287
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:50
MbsData::nqu
int nqu
Number of independent articulations.
Definition: mbs_data.h:165
mbs_save_user_IO_ptr
void(* mbs_save_user_IO_ptr)(FILE *stream, UserIO *uio)
Definition: mbs_project_fct_ptr.h:60
MbsData::njoint
int njoint
Number of joints in the system.
Definition: mbs_data.h:162
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:211
MbsData::npt
int npt
Number of anchor points.
Definition: mbs_data.h:152
Functions::mbs_delete_user_model
mbs_delete_user_model_ptr mbs_delete_user_model
Definition: mbs_data.h:113
Functions::user_equil_init
user_equil_init_ptr user_equil_init
Definition: mbs_data.h:97
mbs_accelred_ptr
int(* mbs_accelred_ptr)(MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:87
Functions::user_dirdyn_init
user_dirdyn_init_ptr user_dirdyn_init
Definition: mbs_data.h:89
Functions::user_equil_loop
user_equil_loop_ptr user_equil_loop
Definition: mbs_data.h:98
Functions::mbs_save_um
mbs_save_um_ptr mbs_save_um
Definition: mbs_data.h:121
UserIO
Definition: user_IO.h:25
Functions::user_dirdyn_loop
user_dirdyn_loop_ptr user_dirdyn_loop
Definition: mbs_data.h:90
Functions::user_invdyn_finish
user_invdyn_finish_ptr user_invdyn_finish
Definition: mbs_data.h:95
MbsData::Nux
int Nux
Number of user variable.
Definition: mbs_data.h:288
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:299
MbsData::jac_user
double ** jac_user
Jacobian of constraints [nqv x njoint] (starting at 1), only used in symbolic accelred,...
Definition: mbs_data.h:229
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:308
Functions::user_ExtForces
user_ExtForces_ptr user_ExtForces
Definition: mbs_data.h:109
mbs_print_user_model_ptr
void(* mbs_print_user_model_ptr)(UserModel *ums)
Definition: mbs_project_fct_ptr.h:57
MbsData::DoneModal
int DoneModal
Flag that indicates if the modal module has been executed (default: 0=not done; 1=done).
Definition: mbs_data.h:295
Functions::mbs_dirdyna
mbs_dirdyna_ptr mbs_dirdyna
Definition: mbs_data.h:74
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:198
mbs_new_user_IO_ptr
UserIO *(* mbs_new_user_IO_ptr)(UserIoInfo *ioInfo)
Definition: mbs_project_fct_ptr.h:48
MbsData::SWr
double ** SWr
Array of Swr vector for each external forces.
Definition: mbs_data.h:265
Functions::mbs_link3D
mbs_link3D_ptr mbs_link3D
Definition: mbs_data.h:71
MbsData::q_cos
double * q_cos
Array with the cosine values of the generalized coordinates, if rotational (if translational,...
Definition: mbs_data.h:197
mbs_extforces_ptr
void(* mbs_extforces_ptr)(double **frc, double **trq, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:86
Functions::user_Link3DForces
user_Link3DForces_ptr user_Link3DForces
Definition: mbs_data.h:108
user_cons_hJ_ptr
void(* user_cons_hJ_ptr)(double *h, double **Jac, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:35
MbsData::hu
int * hu
Array with the indices of independent constraints.
Definition: mbs_data.h:183
MbsData::Nxfrc
int Nxfrc
Number of points where an external force is applied into a body.
Definition: mbs_data.h:263
MbsData::qd0
double * qd0
Array with the initial values of the generalized velocities.
Definition: mbs_data.h:192
Functions::mbs_get_user_model_list
mbs_get_user_model_list_ptr mbs_get_user_model_list
Definition: mbs_data.h:120
Functions::mbs_print_user_IO
mbs_print_user_IO_ptr mbs_print_user_IO
Definition: mbs_data.h:122
MbsData::Nlink
int Nlink
Number of forces acting between two points of the system (force law implemented in user_LinkForces())...
Definition: mbs_data.h:237
Functions
Definition: mbs_data.h:59
mbs_load_user_model_ptr
void(* mbs_load_user_model_ptr)(MbsInfos *mbs_infos, UserModel *ums)
Definition: mbs_project_fct_ptr.h:55
Functions::mbs_load_user_model
mbs_load_user_model_ptr mbs_load_user_model
Definition: mbs_data.h:116
user_cons_J_accelred_ptr
void(* user_cons_J_accelred_ptr)(MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:37
user_LinkForces_ptr
double(* user_LinkForces_ptr)(double Z, double Zd, MbsData *mbs_data, double tsim, int ilnk)
Definition: mbs_project_fct_ptr.h:38
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:307
Functions::user_free
user_free_ptr user_free
Definition: mbs_data.h:87
MbsData::__user_IO_info
UserIoInfo * __user_IO_info
Definition: mbs_data.h:280
mbs_new_user_model_ptr
UserModel *(* mbs_new_user_model_ptr)()
Definition: mbs_project_fct_ptr.h:49
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:221
MbsData::Nuserc
int Nuserc
Number of user constraints.
Definition: mbs_data.h:219
Functions::user_equil_fxe
user_equil_fxe_ptr user_equil_fxe
Definition: mbs_data.h:100
MbsData::Fl
double * Fl
Array with the current values of the forces on each link (see: user_LinkForces()).
Definition: mbs_data.h:241
MbsData::qu
int * qu
Array with the indices of the independent articulations (free)
Definition: mbs_data.h:174
user_Derivative_ptr
void(* user_Derivative_ptr)(MbsData *s)
Definition: mbs_project_fct_ptr.h:33
MbsData::NRerr
double NRerr
Maximal error on constraint allowed in Newton-Raphson algorithm, default 1.0e-9.
Definition: mbs_data.h:220
MbsData::trq
double ** trq
Matrix with the components of the resultant external torques (pure torque and couple produced by forc...
Definition: mbs_data.h:203
MbsData::qv
int * qv
Array with the indices of the dependent articulations .
Definition: mbs_data.h:182
MbsData::Qc
double * Qc
Array with the value of joint force introduced in driven joint to respect the user function.
Definition: mbs_data.h:233
MbsData::Nloopc
int Nloopc
Number of loop constraints.
Definition: mbs_data.h:217
user_JointForces_ptr
double *(* user_JointForces_ptr)(MbsData *, double)
Definition: mbs_project_fct_ptr.h:20
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:104
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:240
Functions::user_LinkForces
user_LinkForces_ptr user_LinkForces
Definition: mbs_data.h:107
MbsData::Qq
double * Qq
Array with the values of the joint forces.
Definition: mbs_data.h:204
MbsData::q
double * q
Array with the current values of the generalized coordinates.
Definition: mbs_data.h:187
MbsData::In
double ** In
Array containing the inertia tensor component of each body (in the body fixed frame,...
Definition: mbs_data.h:156
MbsData::Nsensor
int Nsensor
< Array of l3DWr vector for each 3D link forces.
Definition: mbs_data.h:260
MbsData::project_path
char * project_path
Path to the mbs project folder.
Definition: mbs_data.h:312
Functions::symbolicLibHandle
MbsDataLibInfo * symbolicLibHandle
Definition: mbs_data.h:62
MbsData::nqdriven
int nqdriven
Number of driven articulations.
Definition: mbs_data.h:168
Functions::user_realtime_options
user_realtime_options_ptr user_realtime_options
Definition: mbs_data.h:126
user_DrivenJoints_ptr
void(* user_DrivenJoints_ptr)(MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:34
MbsData::fct
Functions fct
Structure to store the pointer to the project-specific functions.
Definition: mbs_data.h:316
Functions::user_Derivative
user_Derivative_ptr user_Derivative
Definition: mbs_data.h:102
user_invdyn_init_ptr
void(* user_invdyn_init_ptr)(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Definition: mbs_project_fct_ptr.h:26
mbs_cons_hJ_ptr
void(* mbs_cons_hJ_ptr)(double *h, double **Jac, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:90
Functions::user_invdyn_loop
user_invdyn_loop_ptr user_invdyn_loop
Definition: mbs_data.h:94
Functions::mbs_get_user_model_size
mbs_get_user_model_size_ptr mbs_get_user_model_size
Definition: mbs_data.h:119
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:202
mbs_cons_jdqd_ptr
void(* mbs_cons_jdqd_ptr)(double *Jdqd, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:91
MbsData::nqc
int nqc
Number of driven articulations, it includes qlocked and qdriven.
Definition: mbs_data.h:166
mbs_bind_user_model_ptr
void(* mbs_bind_user_model_ptr)(MbsInfos *mbs_infos, UserModel *ums)
Definition: mbs_project_fct_ptr.h:56
user_invdyn_loop_ptr
void(* user_invdyn_loop_ptr)(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Definition: mbs_project_fct_ptr.h:27
MbsData::l3DWr
double ** l3DWr
Definition: mbs_data.h:243
MbsDataLibInfo::lib_handle
HINSTANCE lib_handle
Definition: mbs_data.h:49
MbsDataLibInfo
This structures contains a reference to a dynamic library handle.
Definition: mbs_data.h:45
MbsData::user_model
UserModel * user_model
Structure containing all user model, this structure is specific for each project.
Definition: mbs_data.h:276
MbsData::realtime
void * realtime
Pointer to Simu_realtime structure.
Definition: mbs_data.h:322
Functions::mbs_print_user_model
mbs_print_user_model_ptr mbs_print_user_model
Definition: mbs_data.h:118
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:153
mbs_get_user_model_size_ptr
void(* mbs_get_user_model_size_ptr)(int *n_usr_model)
Definition: mbs_project_fct_ptr.h:53
MbsData::mbs_name
char * mbs_name
Name of the mbs project as it is stored in the xml file.
Definition: mbs_data.h:313
user_cons_jdqd_ptr
void(* user_cons_jdqd_ptr)(double *jdqd, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:36
user_equil_finish_ptr
void(* user_equil_finish_ptr)(MbsData *, MbsEquil *)
Definition: mbs_project_fct_ptr.h:31
MbsData::q0
double * q0
Array with the initial values of the generalized coordinates.
Definition: mbs_data.h:191
MbsData
Definition: mbs_data.h:149
Functions::mbs_get_user_IO_size
mbs_get_user_IO_size_ptr mbs_get_user_IO_size
Definition: mbs_data.h:115
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:215
Functions::user_cons_J_accelred
user_cons_J_accelred_ptr user_cons_J_accelred
Definition: mbs_data.h:106
Functions::userfctLibHandle
MbsDataLibInfo * userfctLibHandle
Definition: mbs_data.h:63
MbsData::qlocked
int * qlocked
Array with the indices of locked articulations.
Definition: mbs_data.h:176
MbsData::Qa
double * Qa
Array of active joint forces (in case of simulink,invdyna,equil,linearization,...)
Definition: mbs_data.h:205
user_equil_loop_ptr
void(* user_equil_loop_ptr)(MbsData *MBSdata, MbsEquil *mbs_equil)
Definition: mbs_project_fct_ptr.h:30
Functions::user_load_post
user_load_post_ptr user_load_post
Definition: mbs_data.h:86
MbsData::Nuser_model
int Nuser_model
Number of declared user models in MBsysPad.
Definition: mbs_data.h:275
MbsData::build_path
char * build_path
Path to the build folder.
Definition: mbs_data.h:311
Functions::mbs_new_user_IO
mbs_new_user_IO_ptr mbs_new_user_IO
Definition: mbs_data.h:111
MbsData::process
int process
Flag that indicate which module is currently running (1=partitioning, 2=equilibrium,...
Definition: mbs_data.h:297
MbsData::nbody
int nbody
Number of bodies in the system.
Definition: mbs_data.h:160
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:154
user_dirdyn_loop_ptr
void(* user_dirdyn_loop_ptr)(MbsData *MBSdata, MbsDirdyn *mbs_dd)
Definition: mbs_project_fct_ptr.h:24
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:210
user_load_post_ptr
void(* user_load_post_ptr)(MbsData *MBSdata)
Definition: mbs_project_fct_ptr.h:21
user_dirdyn_finish_ptr
void(* user_dirdyn_finish_ptr)(MbsData *, MbsDirdyn *)
Definition: mbs_project_fct_ptr.h:25
Functions::user_cons_jdqd
user_cons_jdqd_ptr user_cons_jdqd
Definition: mbs_data.h:105
Functions::user_DrivenJoints
user_DrivenJoints_ptr user_DrivenJoints
Definition: mbs_data.h:103
Functions::user_invdyn_init
user_invdyn_init_ptr user_invdyn_init
Definition: mbs_data.h:93
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:239
mbs_invdyna_ptr
void(* mbs_invdyna_ptr)(double *Q, MbsData *s, double tsim)
Definition: mbs_project_fct_ptr.h:89
MbsData::g
double g[3+1]
The 3 gravity components.
Definition: mbs_data.h:158
MbsData::flag_stop
int flag_stop
stop the simulation. For dirdyn, equil, invdyn and solvekin only.
Definition: mbs_data.h:298
mbs_user_interface.h
user_equil_fxe_ptr
void(* user_equil_fxe_ptr)(MbsData *, double *f)
Definition: mbs_project_fct_ptr.h:32
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:52
Functions::mbs_bind_user_model
mbs_bind_user_model_ptr mbs_bind_user_model
Definition: mbs_data.h:117
mbs_gensensor_ptr
void(* mbs_gensensor_ptr)(MbsSensor *sens, MbsData *s, int isens)
Definition: mbs_project_fct_ptr.h:93
mbs_get_user_model_list_ptr
void(* mbs_get_user_model_list_ptr)(int *user_model_list)
Definition: mbs_project_fct_ptr.h:54
MbsData::qdriven
int * qdriven
Array with the indices of driven articulations.
Definition: mbs_data.h:178
MbsData::lambda
double * lambda
Array with the values of the Lagrange Multipliers related to the constraints.
Definition: mbs_data.h:222
MbsData::uxd
double * uxd
Array with the values of the time derivatives of the user variables.
Definition: mbs_data.h:286
user_free_ptr
void(* user_free_ptr)(MbsData *MBSdata)
Definition: mbs_project_fct_ptr.h:22
MbsData::q_sin
double * q_sin
Array with the sine values of the generalized coordinates, if rotational (if translational,...
Definition: mbs_data.h:196
MbsData::qdd0
double * qdd0
Array with the initial values of the generalized acceleration.
Definition: mbs_data.h:193
user_equil_init_ptr
void(* user_equil_init_ptr)(MbsData *MBSdata, MbsEquil *mbs_equil)
Definition: mbs_project_fct_ptr.h:29
MbsData::nqa
int nqa
Number of actuated articulations.
Definition: mbs_data.h:169
Functions::mbs_delete_user_IO
mbs_delete_user_IO_ptr mbs_delete_user_IO
Definition: mbs_data.h:114
MbsData::nqlocked
int nqlocked
Number of locked articulations.
Definition: mbs_data.h:167
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:39
Functions::mbs_save_user_IO
mbs_save_user_IO_ptr mbs_save_user_IO
Definition: mbs_data.h:123
MbsData::qdd
double * qdd
Array with the current values of the generalized acceleration.
Definition: mbs_data.h:189
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:230
mbs_sensor_ptr
void(* mbs_sensor_ptr)(MbsSensor *sens, MbsData *s, int isens)
Definition: mbs_project_fct_ptr.h:92
MbsData::udd
double * udd
For axelle red: array with the values of the acceleration of independent coordinate.
Definition: mbs_data.h:291
MbsData::ux
double * ux
Array with the values of the user variables.
Definition: mbs_data.h:285
user_dirdyn_init_ptr
void(* user_dirdyn_init_ptr)(MbsData *MBSdata, MbsDirdyn *mbs_dd)
Definition: mbs_project_fct_ptr.h:23
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:40
Functions::user_JointForces
user_JointForces_ptr user_JointForces
Definition: mbs_data.h:84
MbsData::nhu
int nhu
Number of independent constraints.
Definition: mbs_data.h:171
MbsData::lrod
double * lrod
Array with the length of each rod.
Definition: mbs_data.h:216
MbsData::n_user_IO
int n_user_IO
Definition: mbs_data.h:278
Functions::user_dirdyn_finish
user_dirdyn_finish_ptr user_dirdyn_finish
Definition: mbs_data.h:91