Robotran C Documentation
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
mbs_solvekin_struct.h
Go to the documentation of this file.
1 
16 #ifndef MBS_SOLVEKIN_STRUCT_h
17 #define MBS_SOLVEKIN_STRUCT_h
18 
19 #include "lut.h"
20 #include "mbs_aux.h"
21 #include "mbs_buffer.h"
22 
26 
31 typedef struct MbsInvOptions
32 {
40  int motion;
76  double t0;
79  double tf;
86  double dt;
91  int save2file;
92 
102  char *resfilename;
103 
111  char *respath;
112 
120  char *animpath;
121 
148 
155 
164  int verbose;
165 } MbsInvOptions;
166 
170 typedef struct MbsSolvekin
171 {
177  MbsAux* mbs_aux;
178 
181  double tsim;
184  int tindex;
185 
189 
195  int bufferNb;
198  double** savedArrays;
202 
212 
215 }MbsSolvekin;
216 
217 
218 #endif
MbsSolvekin::options
MbsInvOptions * options
Structure defining the option of a inverse kinematic analysis.
Definition: mbs_solvekin_struct.h:174
MbsInvOptions::resfilename
char * resfilename
Basename of the results files, suffixes and extension added automatically.
Definition: mbs_solvekin_struct.h:102
MbsSolvekin::savedArrays
double ** savedArrays
Pointer to the array that must be saved to buffers.
Definition: mbs_solvekin_struct.h:198
MbsInvOptions::buffer_format
char * buffer_format
The format of the results in the res file.
Definition: mbs_solvekin_struct.h:154
MbsSolvekin::buffers
MbsBuffer ** buffers
Buffer to store generalized coordinates, velocities, acceleration.
Definition: mbs_solvekin_struct.h:188
MbsInvOptions::saveperiod
int saveperiod
The number of time steps between two buffer records.
Definition: mbs_solvekin_struct.h:135
MbsInvOptions::buffersize
int buffersize
The number of time step that can be recorded in the buffer.
Definition: mbs_solvekin_struct.h:147
MbsSolvekin::tindex
int tindex
Current time index.
Definition: mbs_solvekin_struct.h:184
MbsInvOptions::max_save_user
int max_save_user
The maximal number of user variables saved.
Definition: mbs_solvekin_struct.h:140
MbsGrowingBuffer
buffer used to store the user variables to output
Definition: mbs_buffer.h:98
closeloop
@ closeloop
Definition: mbs_solvekin_struct.h:25
MbsInvOptions::trajectoryqddname
char * trajectoryqddname
Give the path and filename (with extention) to the file containing the input trajectory in accelerati...
Definition: mbs_solvekin_struct.h:73
MbsSolvekin::qdd
MbsLutRes * qdd
Definition: mbs_solvekin_struct.h:213
mbs_buffer.h
MbsSolvekin::q
MbsLutRes * q
Pointer to save the input trajectories.
Definition: mbs_solvekin_struct.h:213
MbsSolvekin
General structure of the inverse kinematics module.
Definition: mbs_solvekin_struct.h:170
MbsInvOptions::dt
double dt
Time step, default = 0.001.
Definition: mbs_solvekin_struct.h:86
MbsInvOptions::motion
int motion
Determines how the evolution of q, qd qdd are provided.
Definition: mbs_solvekin_struct.h:40
MbsInvOptions::framerate
int framerate
Number of frame per second for the .anim file, default = 1000.
Definition: mbs_solvekin_struct.h:130
MbsInvOptions::t0
double t0
Initial time of the simulation, default = 0.0.
Definition: mbs_solvekin_struct.h:76
MbsInvOptions::trajectoryqname
char * trajectoryqname
Give the path and filename (with extention) to the file containing the input trajectory in position o...
Definition: mbs_solvekin_struct.h:51
MbsBuffer
Definition: mbs_buffer.h:46
MbsSolvekin::bufferNb
int bufferNb
Number of buffers.
Definition: mbs_solvekin_struct.h:195
MbsInvOptions::verbose
int verbose
Gives informations during the process.
Definition: mbs_solvekin_struct.h:164
MbsInvOptions::respath
char * respath
Path in which results file are saved.
Definition: mbs_solvekin_struct.h:111
MbsInvOptions::trajectoryqdname
char * trajectoryqdname
Give the path and filename (with extention) to the file containing the input trajectory in velocity o...
Definition: mbs_solvekin_struct.h:62
MbsInvOptions::tf
double tf
Final time of the simulation, default = 5.0.
Definition: mbs_solvekin_struct.h:79
MbsInvOptions
Structure defining the option of both inverse kinematics and inverse dynamic analysis.
Definition: mbs_solvekin_struct.h:31
lut.h
Interpolation of value from array (Look Up Table) main header.
MbsInvOptions::animpath
char * animpath
Path in which animation file is saved.
Definition: mbs_solvekin_struct.h:120
MbsSolvekin::tsim
double tsim
Current simulation time.
Definition: mbs_solvekin_struct.h:181
oneshot
@ oneshot
Definition: mbs_solvekin_struct.h:25
MbsInvOptions::save2file
int save2file
Determine whether results are written to files on disk (in MbsSolvekinOptions::respath folder):
Definition: mbs_solvekin_struct.h:91
trajectory
@ trajectory
Definition: mbs_solvekin_struct.h:25
MbsSolvekin::user_buffer
MbsGrowingBuffer * user_buffer
Growing buffer to store user values.
Definition: mbs_solvekin_struct.h:192
MbsInvOptions::save_anim
int save_anim
Determine whether animation file is generated (only valid if MbsSolvekinOptions::save2file is set to ...
Definition: mbs_solvekin_struct.h:127
MbsSolvekin::trajectorytype
int trajectorytype
Value to store the type of trajectory provided by the user, automatically set.
Definition: mbs_solvekin_struct.h:210
MbsSolvekin::qd
MbsLutRes * qd
Definition: mbs_solvekin_struct.h:213
MbsSolvekin::mbs_aux
MbsAux * mbs_aux
Structure to store auxiliary value needed during computation.
Definition: mbs_solvekin_struct.h:177
MbsSolvekin::savePeriodCounter
int savePeriodCounter
Counter for checking whether results must be saved.
Definition: mbs_solvekin_struct.h:201
mbs_aux.h
MbsLutRes
Structure for interpolate the trajectories of coordinates.
Definition: lut.h:40