|
Robotran C Documentation
|
Go to the documentation of this file.
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);
185 double VxF[4],
double OMxF[4],
186 double AxF[4],
double OMPxF[4],
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);
274 double VxF[4],
double OMxF[4],
275 double AxF[4],
double OMPxF[4],
312 int cur_t_usec,
const Uint8 *keystates);
426 MbsData* mbs_data,
double tsim,
int i_link,
int i_param);
432 MbsData* mbs_data,
double tsim,
int i_link,
int i_param);
456 MbsData* mbs_data,
double tsim,
int i_link,
int i_param);
462 MbsData* mbs_data,
double tsim,
int i_link,
int i_param);
486 MbsData* mbs_data,
double tsim,
int i_link,
int i_param);
492 MbsData* mbs_data,
double tsim,
int i_link,
int i_param);
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);
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);
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);
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);
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);
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);
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],
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],
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);
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);
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);
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);
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);
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);
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);
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],
1147 void mbs_link(
double **frc,
double **trq,
double *Flnk,
double *Z,
double *Zd,
MbsData *s,
double tsim);
int mbs_invdynared_dq(MbsData *s, double tsim)
Symbolic function, see mbs_call_invdynared_dq().
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
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
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
void mbs_get_project_functions(MbsData *mbs_data)
loads the project function into the pointers defined in MbsData::fct
void user_Derivative(MbsData *s)
Compute the time derivative of the user state variables defined in the user model.
Definition: user_Derivative.c:15
int mbs_invdynared_dqd(MbsData *s, double tsim)
Symbolic function, see mbs_call_invdynared_dqd().
user real-time option
Definition: realtime.h:42
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
Realtime_option * options
user options
Definition: realtime.h:145
int mbs_call_dirdyna(double **M, double *c, MbsData *s, double tsim)
Symbolic direct dynamic function declaration.
Definition: mbs_project_fct_ptr.c:72
int mbs_call_invdyna(double *Qq, MbsData *s, double tsim)
Symbolic inverse dynamic function declaration.
Definition: mbs_project_fct_ptr.c:83
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
General structure of the inverse dynamics module.
Definition: mbs_invdyn_struct.h:27
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
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().
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
void mbs_cons_jdqd(double *Jdqd, MbsData *s, double tsim)
Symbolic jdqd function, see mbs_call_cons_jdqd().
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
int mbs_call_extforces(double **frc, double **trq, MbsData *s, double tsim)
Symbolic external forces function declaration.
Definition: mbs_project_fct_ptr.c:51
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
void mbs_link3D(double **frc, double **trq, MbsData *s, double tsim)
Symbolic link3D forces function, see mbs_call_link3D().
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
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
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
void user_invd_loop(MbsData *MBSdata, MbsInvdyn *mbs_invd)
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
void mbs_dirdyna(double **M, double *c, MbsData *s, double tsim)
Symbolic direct dynamic function, see mbs_call_dirdyna().
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
int mbs_call_invdyna_dp(MbsData *s, double tsim)
Compute the tangeant matrix of the system to arbitrary parameters.
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
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
void user_DrivenJoints(MbsData *s, double tsim)
Compute the positions, velocities and acceleration of driven joint.
Definition: user_DrivenJoints.c:15
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
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
double * user_JointForces(MbsData *s, double tsim)
Compute the user-specified joint force in all joint.
Definition: user_JointForces.c:17
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
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
void user_equil_loop(MbsData *MBSdata, MbsEquil *mbs_equil)
user own loop functions
Definition: user_equil.c:40
int mbs_invdynared_dp(MbsData *s, double tsim)
Symbolic function, see mbs_call_invdynared_dp().
void user_call_joystick_buttons(MbsData *mbs_data, int buttonID)
Definition: mbs_project_fct_ptr.c:612
void mbs_gensensor(MbsSensor *sens, MbsData *s, int isens)
Symbolic sensor computation function, see mbs_call_sensor().
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
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
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
int mbs_call_cons_jdqd(double *Jdqd, MbsData *s, double tsim)
Symbolic jdqd function declaration.
Definition: mbs_project_fct_ptr.c:105
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
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
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
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...
void user_dirdyn_finish(MbsData *MBSdata, MbsDirdyn *mbs_dd)
user own finishing functions
Definition: user_dirdyn.c:59
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
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
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
void mbs_cons_hJ(double *h, double **Jac, MbsData *s, double tsim)
Symbolic constraints function, see mbs_call_cons_hJ().
void user_invdyn_finish(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Definition: user_invdyn.c:27
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
Definition: mbs_equil_struct.h:79
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
int mbs_accelred(MbsData *s, double tsim)
Symbolic reduced acceleration function, see mbs_call_accelred().
int mbs_invdynared_dqdd(MbsData *s, double tsim)
Symbolic function, see mbs_call_invdynared_dqdd().
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
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
void user_call_joystick_axes(MbsData *mbs_data, Simu_realtime *realtime, int nb_joysticks)
Definition: mbs_project_fct_ptr.c:604
int mbs_call_invdynared_dq(MbsData *s, double tsim)
Compute the stiffness matrix of the system.
Definition: mbs_project_fct_ptr.c:154
Definition: mbs_load_struct.h:76
uint8_t Uint8
Definition: mbs_project_fct_ptr.h:98
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
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
void mbs_invdyna(double *Qq, MbsData *s, double tsim)
Symbolic inverse dynamic function, see mbs_call_invdyna().
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
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
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
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
int mbs_call_invdynared_dqd(MbsData *s, double tsim)
Compute the damping matrix of the system.
Definition: mbs_project_fct_ptr.c:165
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
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
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
double tsim
current simulation time [s]
Definition: realtime.h:114
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
void mbs_sensor(MbsSensor *sens, MbsData *s, int isens)
Symbolic sensor computation function, see mbs_call_sensor().
void user_invdyn_init(MbsData *MBSdata, MbsInvdyn *mbs_invd)
Definition: user_invdyn.c:16
int mbs_check_symbolic(MbsData *s)
Declaration of the generated file checking coherence with the MbsData.
Definition: mbs_data.h:246
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
real-time structure
Definition: realtime.h:99
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
int mbs_call_cons_hJ(double *h, double **Jac, MbsData *s, double tsim)
Symbolic constraints function declaration.
Definition: mbs_project_fct_ptr.c:94
void user_call_keyboard(MbsData *mbs_data, Simu_realtime *realtime, int cur_t_usec, const Uint8 *keystates)
Definition: mbs_project_fct_ptr.c:587
Definition: mbs_sensor_struct.h:18
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)
void mbs_extforces(double **frc, double **trq, MbsData *s, double tsim)
Symbolic external forces function, see mbs_call_extforces().
void user_free(MbsData *MBSdata)
User own freeing operations.
Definition: user_load.c:44
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
void user_load_post(MbsData *MBSdata, MbsLoader *mbs_loader)
User own initialization operations.
Definition: user_load.c:25
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
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
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
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
int mbs_call_invdynared_dqdd(MbsData *s, double tsim)
Compute the reduced mass matrix of the system.
Definition: mbs_project_fct_ptr.c:176
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
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
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
General structure of the direct dynamic module.
Definition: mbs_dirdyn_struct.h:166
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
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
void user_dirdyn_init(MbsData *MBSdata, MbsDirdyn *mbs_dd)
user own initialization functions
Definition: user_dirdyn.c:28
void user_equil_finish(MbsData *MBSdata, MbsEquil *mbs_equil)
user own finishing functions
Definition: user_equil.c:53
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
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
int mbs_call_check_symbolic(MbsData *s)
Call the symbolic checking function, see mbs_check_symbolic().
Definition: mbs_project_fct_ptr.c:138
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
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
void user_call_realtime_plot(MbsData *mbs_data)
Definition: mbs_project_fct_ptr.c:596
void user_call_realtime_options(MbsData *mbs_data, Realtime_option *options)
Definition: mbs_project_fct_ptr.c:579
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
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
int mbs_call_accelred(MbsData *s, double tsim)
Symbolic reduced acceleration function declaration.
Definition: mbs_project_fct_ptr.c:62
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
void user_dirdyn_loop(MbsData *MBSdata, MbsDirdyn *mbs_dd)
user own loop functions
Definition: user_dirdyn.c:46
void user_equil_init(MbsData *MBSdata, MbsEquil *mbs_equil)
user own initialization functions
Definition: user_equil.c:27