Robotran C Documentation
mbs_project_interface.h
Go to the documentation of this file.
1 
13 #include "mbs_equil_struct.h"
14 
18 void mbs_get_project_functions(MbsData *mbs_data);
19 
20 /* * * * * * * * * * * * * * * * * * * * * * * * * * * * */
21 /* User functions */
22 /* * * * * * * * * * * * * * * * * * * * * * * * * * * * */
23 void user_load_post(MbsData *MBSdata, MbsLoader *mbs_loader);
24 void user_free(MbsData *MBSdata);
25 
26 
30 void user_call_dirdyn_init(MbsData *MBSdata, MbsDirdyn *mbs_dd);
31 void user_dirdyn_init(MbsData *MBSdata, MbsDirdyn *mbs_dd);
35 void user_call_dirdyn_loop(MbsData *MBSdata, MbsDirdyn *mbs_dd);
36 void user_dirdyn_loop(MbsData *MBSdata, MbsDirdyn *mbs_dd);
40 void user_call_dirdyn_finish(MbsData *MBSdata, MbsDirdyn *mbs_dd);
41 void user_dirdyn_finish(MbsData *MBSdata, MbsDirdyn *mbs_dd);
42 
46 void user_call_invdyn_init(MbsData *MBSdata, MbsInvdyn *mbs_invd);
47 void user_invdyn_init(MbsData *MBSdata, MbsInvdyn *mbs_invd);
51 void user_call_invdyn_loop(MbsData *MBSdata, MbsInvdyn *mbs_invd);
52 void user_invd_loop(MbsData *MBSdata, MbsInvdyn *mbs_invd);
56 void user_call_invdyn_finish(MbsData *MBSdata, MbsInvdyn *mbs_invd);
57 void user_invdyn_finish(MbsData *MBSdata, MbsInvdyn *mbs_invd);
58 
62 void user_call_equil_init(MbsData *MBSdata, MbsEquil *mbs_equil);
63 void user_equil_init(MbsData *MBSdata, MbsEquil *mbs_equil);
67 void user_call_equil_loop(MbsData *MBSdata, MbsEquil *mbs_equil);
68 void user_equil_loop(MbsData *MBSdata, MbsEquil *mbs_equil);
72 void user_call_equil_finish(MbsData *MBSdata, MbsEquil *mbs_equil);
73 void user_equil_finish(MbsData *MBSdata, MbsEquil *mbs_equil);
77 void user_call_equil_fxe(MbsData *mbs_data, double* f);
78 void user_equil_fxe(MbsData *mbs_data, double* f);
79 
93 void user_cons_hJ(double *h, double **Jac, MbsData *s, double tsim);
99 int user_call_cons_hJ(double *h, double **Jac, MbsData *s, double tsim);
100 
111 void user_cons_jdqd(double *jdqd, MbsData *s, double tsim);
117 int user_call_cons_jdqd(double *jdqd, MbsData *s, double tsim);
118 
128 void user_Derivative(MbsData *s);
135 
147 void user_DrivenJoints(MbsData *s, double tsim);
153 int user_call_DrivenJoints(MbsData *s, double tsim);
154 
176 double* user_ExtForces(double PxF[4], double RxF[4][4], double VxF[4], double OMxF[4],
177  double AxF[4], double OMPxF[4], MbsData *s, double tsim, int ixF);
181 double* user_call_ExtForces(double PxF[4], double RxF[4][4], double VxF[4], double OMxF[4],
182  double AxF[4], double OMPxF[4], MbsData *s, double tsim, int ixF);
183 
184 double* user_GenExtForces(double PxF[4], double RxF[4][4],
185  double VxF[4], double OMxF[4],
186  double AxF[4], double OMPxF[4],
187  MbsData *s, double tsim,int iBody);
188 
201 double* user_JointForces(MbsData *s, double tsim);
205 double* user_call_JointForces(MbsData *s, double tsim);
206 
220 double user_LinkForces(double Z, double Zd, MbsData *s, double tsim, int ilnk);
221 
228 double user_call_LinkForces(double Z, double Zd, MbsData *s, double tsim, int ilnk);
229 
268 double* user_Link3DForces(double PxF[4], double RxF[4][4], double VxF[4], double OMxF[4],
269  double AxF[4], double OMPxF[4], MbsData *s, double tsim,int ixF);
273 double* user_call_Link3DForces(double PxF[4], double RxF[4][4],
274  double VxF[4], double OMxF[4],
275  double AxF[4], double OMPxF[4],
276  MbsData *s, double tsim,int ixF);
277 
301 int user_cons_J_accelred(MbsData* s, double tsim);
305 int user_call_cons_J_accelred(MbsData* s, double tsim);
306 
307 #ifdef __cplusplus
308 extern "C" {
309 #endif
311 void user_call_keyboard(MbsData* mbs_data, Simu_realtime *realtime,
312  int cur_t_usec, const Uint8 *keystates);
313 void user_call_realtime_plot(MbsData* mbs_data);
314 void user_call_joystick_axes(MbsData* mbs_data, Simu_realtime *realtime,
315  int nb_joysticks);
316 void user_call_joystick_buttons(MbsData* mbs_data, int buttonID);
329 void user_call_realtime_visu(MbsData* mbs_data, int nb_models, int *nb_q, double **q_vec);
330 
331 
343 double* user_JointForces_dq(MbsData* mbs_data, double tsim, int ixJ);
344 
348 double* user_call_JointForces_dq(MbsData* mbs_data, double tsim, int ixJ);
349 
361 double* user_JointForces_dqd(MbsData* mbs_data, double tsim, int ixJ);
362 
366 double* user_call_JointForces_dqd(MbsData* mbs_data, double tsim, int ixJ);
367 
368 
380 double* user_JointForces_dqdd(MbsData* mbs_data, double tsim, int ixJ);
381 
385 double* user_call_JointForces_dqdd(MbsData* mbs_data, double tsim, int ixJ);
386 
397 double* user_JointForces_dp(MbsData* mbs_data, double tsim);
398 
402 double* user_call_JointForces_dp(MbsData* mbs_data, double tsim);
403 
425 double user_LinkForces_dq(double Z, double d_Z, double Zd, double d_Zd,
426  MbsData* mbs_data, double tsim, int i_link, int i_param);
427 
431 double user_call_LinkForces_dq(double Z, double d_Z, double Zd, double d_Zd,
432  MbsData* mbs_data, double tsim, int i_link, int i_param);
433 
455 double user_LinkForces_dqd(double Z, double d_Z, double Zd, double d_Zd,
456  MbsData* mbs_data, double tsim, int i_link, int i_param);
457 
461 double user_call_LinkForces_dqd(double Z, double d_Z, double Zd, double d_Zd,
462  MbsData* mbs_data, double tsim, int i_link, int i_param);
463 
485 double user_LinkForces_dqdd(double Z, double d_Z, double Zd, double d_Zd,
486  MbsData* mbs_data, double tsim, int i_link, int i_param);
487 
491 double user_call_LinkForces_dqdd(double Z, double d_Z, double Zd, double d_Zd,
492  MbsData* mbs_data, double tsim, int i_link, int i_param);
493 
510 double user_LinkForces_dp(double Z, double d_Z, double Zd, double d_Zd,
511  MbsData* mbs_data, double tsim, int i_link);
512 
516 double user_call_LinkForces_dp(double Z, double d_Z, double Zd, double d_Zd,
517  MbsData* mbs_data, double tsim, int i_link);
518 
576 double* user_Link3DForces_dq(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
577  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
578  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
579  MbsData* s, double tsim, int i_link3d, int i_param);
580 
584 double* user_call_Link3DForces_dq(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
585  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
586  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
587  MbsData* s, double tsim, int i_link3d, int i_param);
588 
644 double* user_Link3DForces_dqd(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
645  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
646  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
647  MbsData* s, double tsim, int i_link3d, int i_param);
648 
652 double* user_call_Link3DForces_dqd(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
653  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
654  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
655  MbsData* s, double tsim, int i_link3d, int i_param);
656 
714 double* user_Link3DForces_dqdd(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
715  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
716  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
717  MbsData* s, double tsim, int i_link3d, int i_param);
718 
722 double* user_call_Link3DForces_dqdd(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
723  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
724  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
725  MbsData* s, double tsim, int i_link3d, int i_param);
726 
727 
784 double* user_Link3DForces_dp(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
785  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
786  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
787  MbsData* s, double tsim, int i_link3d);
788 
792 double* user_call_Link3DForces_dp(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
793  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
794  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
795  MbsData* s, double tsim, int i_link3d);
796 
855 double* user_ExtForces_dq(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
856  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
857  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
858  MbsData* s, double tsim, int i_force, int i_joint);
859 
863 double* user_call_ExtForces_dq(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
864  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
865  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
866  MbsData* s, double tsim, int i_force, int i_joint);
867 
926 double* user_ExtForces_dqd(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
927  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
928  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
929  MbsData* s, double tsim, int i_force, int i_joint);
930 
934 double* user_call_ExtForces_dqd(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
935  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
936  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
937  MbsData* s, double tsim, int i_force, int i_joint);
938 
997 double* user_ExtForces_dqdd(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
998  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
999  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
1000  MbsData* s, double tsim, int i_force, int i_joint);
1001 
1005 double* user_call_ExtForces_dqdd(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
1006  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
1007  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
1008  MbsData* s, double tsim, int i_force, int i_joint);
1009 
1067 double* user_ExtForces_dp(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
1068  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
1069  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
1070  MbsData* s, double tsim, int i_force, int i_joint);
1071 
1075 double* user_call_ExtForces_dp(double PxF[4], double d_PxF[4], double RxF[4][4], double d_RxF[4][4],
1076  double VxF[4], double d_VxF[4], double OMxF[4], double d_OMxF[4],
1077  double AxF[4], double d_AxF[4], double OMPxF[4], double d_OMPxF[4],
1078  MbsData* s, double tsim, int i_force);
1079 
1080 
1081 /* * * * * * * * * * * * * * * * * * * * * * * * * * * * */
1082 /* Symbolic functions */
1083 /* * * * * * * * * * * * * * * * * * * * * * * * * * * * */
1097 int mbs_call_cons_hJ(double *h, double **Jac, MbsData *s, double tsim);
1103 void mbs_cons_hJ(double *h, double **Jac, MbsData *s, double tsim);
1104 
1105 void mbs_invdyna(double *Qq, MbsData *s, double tsim);
1106 
1119 int mbs_call_cons_jdqd(double *Jdqd, MbsData *s, double tsim);
1125 void mbs_cons_jdqd(double *Jdqd, MbsData *s, double tsim);
1126 
1143 int mbs_call_link(double **frc, double **trq, double *Flnk, double *Z, double *Zd, MbsData *s, double tsim);
1147 void mbs_link(double **frc, double **trq, double *Flnk, double *Z, double *Zd, MbsData *s, double tsim);
1148 
1162 int mbs_call_link3D(double **frc, double **trq, MbsData *s, double tsim);
1166 void mbs_link3D(double **frc, double **trq, MbsData *s, double tsim);
1167 
1181 int mbs_call_extforces(double **frc, double **trq, MbsData *s, double tsim);
1185 void mbs_extforces(double **frc, double **trq, MbsData *s, double tsim);
1186 
1198 int mbs_call_accelred(MbsData *s, double tsim);
1202 int mbs_accelred(MbsData *s, double tsim);
1203 
1216 int mbs_call_gensensor(MbsSensor *sens, MbsData *s, int isens);
1222 void mbs_gensensor(MbsSensor *sens, MbsData *s, int isens);
1223 
1237 int mbs_check_symbolic(MbsData *s);
1253 
1268 int mbs_call_sensor(MbsSensor *sens, MbsData *s, int isens);
1274 void mbs_sensor(MbsSensor *sens, MbsData *s, int isens);
1275 
1288 int mbs_call_invdyna(double *Qq, MbsData *s, double tsim);
1294 void mbs_invdyna(double *Qq, MbsData *s, double tsim);
1295 
1306 int mbs_call_invdynared_dq(MbsData* s, double tsim);
1307 
1311 int mbs_invdynared_dq(MbsData* s, double tsim);
1312 
1323 int mbs_call_invdynared_dqd(MbsData* s, double tsim);
1324 
1328 int mbs_invdynared_dqd(MbsData* s, double tsim);
1329 
1340 int mbs_call_invdynared_dqdd(MbsData* s, double tsim);
1341 
1345 int mbs_invdynared_dqdd(MbsData* s, double tsim);
1346 
1357 int mbs_call_invdyna_dp(MbsData* s, double tsim);
1358 
1362 int mbs_invdynared_dp(MbsData* s, double tsim);
1363 
1364 
1378 int mbs_call_dirdyna(double **M, double *c, MbsData *s, double tsim);
1384 void mbs_dirdyna(double **M, double *c, MbsData *s, double tsim);
1385 #ifdef __cplusplus
1386 }
1387 #endif
mbs_invdynared_dq
int mbs_invdynared_dq(MbsData *s, double tsim)
Symbolic function, see mbs_call_invdynared_dq().
user_call_ExtForces
double * user_call_ExtForces(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)
Module redirection for the computation of external forces, see user_DrivenJoints().
Definition: mbs_project_fct_ptr.c:235
user_call_DrivenJoints
int user_call_DrivenJoints(MbsData *s, double tsim)
Module redirection for the computation of driven joints, see user_DrivenJoints() however the return d...
Definition: mbs_project_fct_ptr.c:258
user_ExtForces
double * user_ExtForces(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)
Compute an user-specified external force.
Definition: user_ExtForces.c:15
mbs_get_project_functions
void mbs_get_project_functions(MbsData *mbs_data)
loads the project function into the pointers defined in MbsData::fct
user_Derivative
void user_Derivative(MbsData *s)
Compute the time derivative of the user state variables defined in the user model.
Definition: user_Derivative.c:15
mbs_invdynared_dqd
int mbs_invdynared_dqd(MbsData *s, double tsim)
Symbolic function, see mbs_call_invdynared_dqd().
Realtime_option
user real-time option
Definition: realtime.h:42
user_LinkForces_dp
double user_LinkForces_dp(double Z, double d_Z, double Zd, double d_Zd, MbsData *mbs_data, double tsim, int i_link)
Compute the partial derivative of a link forces with respect to a specific parameter.
Definition: user_LinkForces_deriv.c:47
Simu_realtime::options
Realtime_option * options
user options
Definition: realtime.h:145
mbs_call_dirdyna
int mbs_call_dirdyna(double **M, double *c, MbsData *s, double tsim)
Symbolic direct dynamic function declaration.
Definition: mbs_project_fct_ptr.c:72
mbs_call_invdyna
int mbs_call_invdyna(double *Qq, MbsData *s, double tsim)
Symbolic inverse dynamic function declaration.
Definition: mbs_project_fct_ptr.c:83
user_call_invdyn_loop
void user_call_invdyn_loop(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Module redirection for user own dirdyn loop function, see user_dirdyn_loop().
Definition: mbs_project_fct_ptr.c:540
MbsInvdyn
General structure of the inverse dynamics module.
Definition: mbs_invdyn_struct.h:27
user_cons_jdqd
void user_cons_jdqd(double *jdqd, MbsData *s, double tsim)
Compute the jdqd term of the user-specified constraints.
Definition: user_cons_jdqd.c:15
mbs_link
void mbs_link(double **frc, double **trq, double *Flnk, double *Z, double *Zd, MbsData *s, double tsim)
Symbolic link forces function, see mbs_call_link().
user_call_JointForces_dqd
double * user_call_JointForces_dqd(MbsData *mbs_data, double tsim, int ixJ)
Module redirection for user function, see user_JointForces_dqd().
Definition: mbs_project_fct_ptr.c:314
mbs_cons_jdqd
void mbs_cons_jdqd(double *Jdqd, MbsData *s, double tsim)
Symbolic jdqd function, see mbs_call_cons_jdqd().
user_ExtForces_dqdd
double * user_ExtForces_dqdd(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 i_joint)
Compute the partial derivative of an user-specified external force with respect to a generalized acce...
Definition: user_ExtForces_deriv.c:101
mbs_call_extforces
int mbs_call_extforces(double **frc, double **trq, MbsData *s, double tsim)
Symbolic external forces function declaration.
Definition: mbs_project_fct_ptr.c:51
user_call_realtime_visu
void user_call_realtime_visu(MbsData *mbs_data, int nb_models, int *nb_q, double **q_vec)
Redirection to the user-specified user function of realtime visualization.
Definition: mbs_project_fct_ptr.c:620
mbs_link3D
void mbs_link3D(double **frc, double **trq, MbsData *s, double tsim)
Symbolic link3D forces function, see mbs_call_link3D().
user_call_equil_loop
void user_call_equil_loop(MbsData *MBSdata, MbsEquil *mbs_equil)
Module redirection for user own equil loop function, see user_equil_loop().
Definition: mbs_project_fct_ptr.c:560
user_call_Derivative
int user_call_Derivative(MbsData *s)
Module redirection for the time derivative of the user state variables, see user_Derivative() however...
Definition: mbs_project_fct_ptr.c:248
user_JointForces_dp
double * user_JointForces_dp(MbsData *mbs_data, double tsim)
Compute the derivative of the joint forces vector according to a specific parameter.
Definition: user_JointForces_deriv.c:51
user_invd_loop
void user_invd_loop(MbsData *MBSdata, MbsInvdyn *mbs_invd)
user_call_Link3DForces
double * user_call_Link3DForces(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)
Module redirection for user link 3D function, see user_Link3DForces().
Definition: mbs_project_fct_ptr.c:212
mbs_dirdyna
void mbs_dirdyna(double **M, double *c, MbsData *s, double tsim)
Symbolic direct dynamic function, see mbs_call_dirdyna().
user_LinkForces_dqd
double user_LinkForces_dqd(double Z, double d_Z, double Zd, double d_Zd, MbsData *mbs_data, double tsim, int i_link, int i_param)
Compute the partial derivative of a link forces with respect to a generalized velocity.
Definition: user_LinkForces_deriv.c:27
mbs_call_invdyna_dp
int mbs_call_invdyna_dp(MbsData *s, double tsim)
Compute the tangeant matrix of the system to arbitrary parameters.
mbs_call_link3D
int mbs_call_link3D(double **frc, double **trq, MbsData *s, double tsim)
Symbolic link 3D forces function declaration.
Definition: mbs_project_fct_ptr.c:40
user_call_cons_jdqd
int user_call_cons_jdqd(double *jdqd, MbsData *s, double tsim)
Module redirection for jdqd term of the user-specified constraints, see user_cons_jdqd() however the ...
Definition: mbs_project_fct_ptr.c:280
user_DrivenJoints
void user_DrivenJoints(MbsData *s, double tsim)
Compute the positions, velocities and acceleration of driven joint.
Definition: user_DrivenJoints.c:15
user_LinkForces
double user_LinkForces(double Z, double Zd, MbsData *s, double tsim, int ilnk)
Compute the value of a link forces.
Definition: user_LinkForces.c:15
mbs_call_sensor
int mbs_call_sensor(MbsSensor *sens, MbsData *s, int isens)
Declaration of the symbolic function computing all fields of a sensor.
Definition: mbs_project_fct_ptr.c:116
user_JointForces
double * user_JointForces(MbsData *s, double tsim)
Compute the user-specified joint force in all joint.
Definition: user_JointForces.c:17
user_call_equil_init
void user_call_equil_init(MbsData *MBSdata, MbsEquil *mbs_equil)
Module redirection for user own equilibrium initialization function, see user_equil_init().
Definition: mbs_project_fct_ptr.c:554
user_call_JointForces_dp
double * user_call_JointForces_dp(MbsData *mbs_data, double tsim)
Module redirection for user function, see user_JointForces_dp().
Definition: mbs_project_fct_ptr.c:334
user_equil_loop
void user_equil_loop(MbsData *MBSdata, MbsEquil *mbs_equil)
user own loop functions
Definition: user_equil.c:40
mbs_invdynared_dp
int mbs_invdynared_dp(MbsData *s, double tsim)
Symbolic function, see mbs_call_invdynared_dp().
user_call_joystick_buttons
void user_call_joystick_buttons(MbsData *mbs_data, int buttonID)
Definition: mbs_project_fct_ptr.c:612
mbs_gensensor
void mbs_gensensor(MbsSensor *sens, MbsData *s, int isens)
Symbolic sensor computation function, see mbs_call_sensor().
user_Link3DForces_dp
double * user_Link3DForces_dp(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)
Compute the partial derivative of a link3D forces with respect to a parameter.
Definition: user_Link3DForces_deriv.c:64
user_call_JointForces_dqdd
double * user_call_JointForces_dqdd(MbsData *mbs_data, double tsim, int ixJ)
Module redirection for user function, see user_call_JointForces_dqdd().
Definition: mbs_project_fct_ptr.c:324
user_call_Link3DForces_dp
double * user_call_Link3DForces_dp(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)
Module redirection for user function, see user_Link3DForces_dp().
Definition: mbs_project_fct_ptr.c:497
mbs_call_cons_jdqd
int mbs_call_cons_jdqd(double *Jdqd, MbsData *s, double tsim)
Symbolic jdqd function declaration.
Definition: mbs_project_fct_ptr.c:105
user_call_JointForces_dq
double * user_call_JointForces_dq(MbsData *mbs_data, double tsim, int ixJ)
Module redirection for user function, see user_JointForces_dq().
Definition: mbs_project_fct_ptr.c:304
user_LinkForces_dq
double user_LinkForces_dq(double Z, double d_Z, double Zd, double d_Zd, MbsData *mbs_data, double tsim, int i_link, int i_param)
Compute the partial derivative of a link forces with respect to a generalized coordinate.
Definition: user_LinkForces_deriv.c:17
user_Link3DForces_dqd
double * user_Link3DForces_dqd(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 i_param)
Compute the partial derivative of a link3D forces with respect to a generalized velocity.
Definition: user_Link3DForces_deriv.c:33
user_ExtForces_dp
double * user_ExtForces_dp(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 i_joint)
Compute the partial derivative of an user-specified external force with respect to a specific paramet...
user_dirdyn_finish
void user_dirdyn_finish(MbsData *MBSdata, MbsDirdyn *mbs_dd)
user own finishing functions
Definition: user_dirdyn.c:59
user_call_equil_fxe
void user_call_equil_fxe(MbsData *mbs_data, double *f)
Module redirection for user own equilibrium equations function, see user_equil_fxe().
Definition: mbs_project_fct_ptr.c:572
user_call_invdyn_init
void user_call_invdyn_init(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Module redirection for user own dirdyn initialization function, see user_dirdyn_init().
Definition: mbs_project_fct_ptr.c:534
user_equil_fxe
void user_equil_fxe(MbsData *mbs_data, double *f)
user own implementation of added equilibrium equations Fxe Necessary to express equilibrium f(x)=0
Definition: user_equil.c:65
mbs_cons_hJ
void mbs_cons_hJ(double *h, double **Jac, MbsData *s, double tsim)
Symbolic constraints function, see mbs_call_cons_hJ().
user_invdyn_finish
void user_invdyn_finish(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Definition: user_invdyn.c:27
user_call_Link3DForces_dqdd
double * user_call_Link3DForces_dqdd(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 i_param)
Module redirection for user function, see user_Link3DForces_dqdd().
Definition: mbs_project_fct_ptr.c:481
MbsEquil
Definition: mbs_equil_struct.h:79
user_call_LinkForces_dqdd
double user_call_LinkForces_dqdd(double Z, double d_Z, double Zd, double d_Zd, MbsData *mbs_data, double tsim, int i_link, int i_param)
Module redirection for user function, see user_LinkForces_dqdd().
Definition: mbs_project_fct_ptr.c:364
mbs_accelred
int mbs_accelred(MbsData *s, double tsim)
Symbolic reduced acceleration function, see mbs_call_accelred().
mbs_invdynared_dqdd
int mbs_invdynared_dqdd(MbsData *s, double tsim)
Symbolic function, see mbs_call_invdynared_dqdd().
user_call_Link3DForces_dqd
double * user_call_Link3DForces_dqd(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 i_param)
Module redirection for user function, see user_Link3DForces_dqd().
Definition: mbs_project_fct_ptr.c:465
user_ExtForces_dq
double * user_ExtForces_dq(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 i_joint)
Compute the partial derivative of an user-specified external force with respect to a generalized coor...
Definition: user_ExtForces_deriv.c:17
user_call_joystick_axes
void user_call_joystick_axes(MbsData *mbs_data, Simu_realtime *realtime, int nb_joysticks)
Definition: mbs_project_fct_ptr.c:604
mbs_call_invdynared_dq
int mbs_call_invdynared_dq(MbsData *s, double tsim)
Compute the stiffness matrix of the system.
Definition: mbs_project_fct_ptr.c:154
MbsLoader
Definition: mbs_load_struct.h:76
Uint8
uint8_t Uint8
Definition: mbs_project_fct_ptr.h:98
user_call_cons_hJ
int user_call_cons_hJ(double *h, double **Jac, MbsData *s, double tsim)
Module redirection for user joint force function, see user_cons_hJ() however the return differs.
Definition: mbs_project_fct_ptr.c:269
user_call_dirdyn_init
void user_call_dirdyn_init(MbsData *MBSdata, MbsDirdyn *mbs_dd)
Module redirection for user own dirdyn initialization function, see user_dirdyn_init().
Definition: mbs_project_fct_ptr.c:514
mbs_invdyna
void mbs_invdyna(double *Qq, MbsData *s, double tsim)
Symbolic inverse dynamic function, see mbs_call_invdyna().
user_call_Link3DForces_dq
double * user_call_Link3DForces_dq(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 i_param)
Module redirection for user function, see user_Link3DForces_dq().
Definition: mbs_project_fct_ptr.c:449
mbs_equil_struct.h
user_call_equil_finish
void user_call_equil_finish(MbsData *MBSdata, MbsEquil *mbs_equil)
Module redirection for user own equil finish function, see user_equil_finish().
Definition: mbs_project_fct_ptr.c:566
user_call_JointForces
double * user_call_JointForces(MbsData *s, double tsim)
Module redirection for user joint force function, see user_JointForces().
Definition: mbs_project_fct_ptr.c:202
user_LinkForces_dqdd
double user_LinkForces_dqdd(double Z, double d_Z, double Zd, double d_Zd, MbsData *mbs_data, double tsim, int i_link, int i_param)
Compute the partial derivative of a link forces with respect to a generalized acceleration.
Definition: user_LinkForces_deriv.c:37
mbs_call_invdynared_dqd
int mbs_call_invdynared_dqd(MbsData *s, double tsim)
Compute the damping matrix of the system.
Definition: mbs_project_fct_ptr.c:165
user_call_ExtForces_dp
double * user_call_ExtForces_dp(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)
Module redirection for user function, see user_ExtForces_dp().
Definition: mbs_project_fct_ptr.c:432
user_call_ExtForces_dq
double * user_call_ExtForces_dq(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 i_joint)
Module redirection for user function, see user_call_ExtForces_dq().
Definition: mbs_project_fct_ptr.c:384
user_Link3DForces_dq
double * user_Link3DForces_dq(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 i_param)
Compute the partial derivative of a link3D forces with respect to a generalized coordinate.
Definition: user_Link3DForces_deriv.c:18
Simu_realtime::tsim
double tsim
current simulation time [s]
Definition: realtime.h:114
user_call_LinkForces
double user_call_LinkForces(double Z, double Zd, MbsData *s, double tsim, int ilnk)
Module redirection for user link force function, see user_LinkForces().
Definition: mbs_project_fct_ptr.c:225
mbs_sensor
void mbs_sensor(MbsSensor *sens, MbsData *s, int isens)
Symbolic sensor computation function, see mbs_call_sensor().
user_invdyn_init
void user_invdyn_init(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Definition: user_invdyn.c:16
mbs_check_symbolic
int mbs_check_symbolic(MbsData *s)
Declaration of the generated file checking coherence with the MbsData.
MbsData
Definition: mbs_data.h:246
user_cons_hJ
void user_cons_hJ(double *h, double **Jac, MbsData *s, double tsim)
Compute the user-specified constraint vector and Jacobian.
Definition: user_cons_hJ.c:15
Simu_realtime
real-time structure
Definition: realtime.h:99
user_call_cons_J_accelred
int user_call_cons_J_accelred(MbsData *s, double tsim)
Module redirection for accelred user-specified constraints function, see user_cons_J_accelred().
Definition: mbs_project_fct_ptr.c:291
mbs_call_cons_hJ
int mbs_call_cons_hJ(double *h, double **Jac, MbsData *s, double tsim)
Symbolic constraints function declaration.
Definition: mbs_project_fct_ptr.c:94
user_call_keyboard
void user_call_keyboard(MbsData *mbs_data, Simu_realtime *realtime, int cur_t_usec, const Uint8 *keystates)
Definition: mbs_project_fct_ptr.c:587
MbsSensor
Definition: mbs_sensor_struct.h:18
user_GenExtForces
double * user_GenExtForces(double PxF[4], double RxF[4][4], double VxF[4], double OMxF[4], double AxF[4], double OMPxF[4], MbsData *s, double tsim, int iBody)
mbs_extforces
void mbs_extforces(double **frc, double **trq, MbsData *s, double tsim)
Symbolic external forces function, see mbs_call_extforces().
user_free
void user_free(MbsData *MBSdata)
User own freeing operations.
Definition: user_load.c:44
user_ExtForces_dqd
double * user_ExtForces_dqd(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 i_joint)
Compute the partial derivative of an user-specified external force with respect to a generalized velo...
Definition: user_ExtForces_deriv.c:59
user_load_post
void user_load_post(MbsData *MBSdata, MbsLoader *mbs_loader)
User own initialization operations.
Definition: user_load.c:25
user_call_dirdyn_loop
void user_call_dirdyn_loop(MbsData *MBSdata, MbsDirdyn *mbs_dd)
Module redirection for user own dirdyn loop function, see user_dirdyn_loop().
Definition: mbs_project_fct_ptr.c:520
user_Link3DForces
double * user_Link3DForces(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)
Compute an user-specified point to point force, with arbitrary line of action.
Definition: user_Link3DForces.c:15
user_cons_J_accelred
int user_cons_J_accelred(MbsData *s, double tsim)
Close the user-specified constraints and compute the Jacobian of the constraints vector.
Definition: user_cons_J_accelred.c:16
user_call_LinkForces_dp
double user_call_LinkForces_dp(double Z, double d_Z, double Zd, double d_Zd, MbsData *mbs_data, double tsim, int i_link)
Module redirection for user function, see user_LinkForces_dp().
Definition: mbs_project_fct_ptr.c:374
mbs_call_invdynared_dqdd
int mbs_call_invdynared_dqdd(MbsData *s, double tsim)
Compute the reduced mass matrix of the system.
Definition: mbs_project_fct_ptr.c:176
user_call_ExtForces_dqdd
double * user_call_ExtForces_dqdd(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 i_joint)
Module redirection for user function, see user_ExtForces_dqdd().
Definition: mbs_project_fct_ptr.c:416
mbs_call_link
int mbs_call_link(double **frc, double **trq, double *Flnk, double *Z, double *Zd, MbsData *s, double tsim)
Symbolic link forces function declaration.
Definition: mbs_project_fct_ptr.c:29
mbs_call_gensensor
int mbs_call_gensensor(MbsSensor *sens, MbsData *s, int isens)
Declaration of the symbolic function computing all fields of a sensor located at a body origin.
Definition: mbs_project_fct_ptr.c:127
MbsDirdyn
General structure of the direct dynamic module.
Definition: mbs_dirdyn_struct.h:166
user_JointForces_dqd
double * user_JointForces_dqd(MbsData *mbs_data, double tsim, int ixJ)
Compute the derivative of the joint forces vector according to a generalized velocity.
Definition: user_JointForces_deriv.c:27
user_call_ExtForces_dqd
double * user_call_ExtForces_dqd(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 i_joint)
Module redirection for user function, see user_ExtForces_dqd().
Definition: mbs_project_fct_ptr.c:400
user_dirdyn_init
void user_dirdyn_init(MbsData *MBSdata, MbsDirdyn *mbs_dd)
user own initialization functions
Definition: user_dirdyn.c:28
user_equil_finish
void user_equil_finish(MbsData *MBSdata, MbsEquil *mbs_equil)
user own finishing functions
Definition: user_equil.c:53
user_JointForces_dqdd
double * user_JointForces_dqdd(MbsData *mbs_data, double tsim, int ixJ)
Compute the derivative of the joint forces vector according to a generalized acceleartion.
Definition: user_JointForces_deriv.c:39
user_JointForces_dq
double * user_JointForces_dq(MbsData *mbs_data, double tsim, int ixJ)
Compute the derivative of the joint forces vector according to a generalized coordinate.
Definition: user_JointForces_deriv.c:15
mbs_call_check_symbolic
int mbs_call_check_symbolic(MbsData *s)
Call the symbolic checking function, see mbs_check_symbolic().
Definition: mbs_project_fct_ptr.c:138
user_Link3DForces_dqdd
double * user_Link3DForces_dqdd(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 i_param)
Compute the partial derivative of a link3D forces with respect to a generalized acceleration.
Definition: user_Link3DForces_deriv.c:48
user_call_dirdyn_finish
void user_call_dirdyn_finish(MbsData *MBSdata, MbsDirdyn *mbs_dd)
Module redirection for user own dirdyn finish function, see user_dirdyn_finish().
Definition: mbs_project_fct_ptr.c:526
user_call_realtime_plot
void user_call_realtime_plot(MbsData *mbs_data)
Definition: mbs_project_fct_ptr.c:596
user_call_realtime_options
void user_call_realtime_options(MbsData *mbs_data, Realtime_option *options)
Definition: mbs_project_fct_ptr.c:579
user_call_invdyn_finish
void user_call_invdyn_finish(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Module redirection for user own dirdyn finish function, see user_dirdyn_finish().
Definition: mbs_project_fct_ptr.c:546
user_call_LinkForces_dqd
double user_call_LinkForces_dqd(double Z, double d_Z, double Zd, double d_Zd, MbsData *mbs_data, double tsim, int i_link, int i_param)
Module redirection for user function, see user_LinkForces_dqd().
Definition: mbs_project_fct_ptr.c:354
mbs_call_accelred
int mbs_call_accelred(MbsData *s, double tsim)
Symbolic reduced acceleration function declaration.
Definition: mbs_project_fct_ptr.c:62
user_call_LinkForces_dq
double user_call_LinkForces_dq(double Z, double d_Z, double Zd, double d_Zd, MbsData *mbs_data, double tsim, int i_link, int i_param)
Module redirection for user function, see user_LinkForces_dq().
Definition: mbs_project_fct_ptr.c:344
user_dirdyn_loop
void user_dirdyn_loop(MbsData *MBSdata, MbsDirdyn *mbs_dd)
user own loop functions
Definition: user_dirdyn.c:46
user_equil_init
void user_equil_init(MbsData *MBSdata, MbsEquil *mbs_equil)
user own initialization functions
Definition: user_equil.c:27