Robotran C Documentation
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;
94  char* resfilename;
99  const char* respath;
104  const char* animpath;
131 
138 
143  int verbose;
144 } MbsInvOptions;
145 
149 typedef struct MbsSolvekin
150 {
156  MbsAux* mbs_aux;
157 
160  double tsim;
163  int tindex;
164 
168 
174  int bufferNb;
177  double** savedArrays;
181 
191 
194 }MbsSolvekin;
195 
196 
197 #endif
MbsSolvekin::options
MbsInvOptions * options
Structure defining the option of a inverse kinematic analysis.
Definition: mbs_solvekin_struct.h:153
MbsInvOptions::resfilename
char * resfilename
The keyword used for determining the name of result files.
Definition: mbs_solvekin_struct.h:94
MbsSolvekin::savedArrays
double ** savedArrays
Pointer to the array that must be saved to buffers.
Definition: mbs_solvekin_struct.h:177
MbsInvOptions::buffer_format
char * buffer_format
The format of the results in the res file.
Definition: mbs_solvekin_struct.h:137
MbsSolvekin::buffers
MbsBuffer ** buffers
Buffer to store generalized coordinates, velocities, acceleration.
Definition: mbs_solvekin_struct.h:167
MbsInvOptions::saveperiod
int saveperiod
The number of time steps between two buffer records.
Definition: mbs_solvekin_struct.h:118
MbsInvOptions::buffersize
int buffersize
The number of time step that can be recorded in the buffer.
Definition: mbs_solvekin_struct.h:130
MbsSolvekin::tindex
int tindex
Current time index.
Definition: mbs_solvekin_struct.h:163
MbsInvOptions::max_save_user
int max_save_user
The maximal number of user variables saved.
Definition: mbs_solvekin_struct.h:123
MbsGrowingBuffer
buffer used to store the user variables to output
Definition: mbs_buffer.h:92
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:192
mbs_buffer.h
closeloop
@ closeloop
Definition: mbs_solvekin_struct.h:25
MbsSolvekin::q
MbsLutRes * q
Pointer to save the input trajectories.
Definition: mbs_solvekin_struct.h:192
MbsSolvekin
General structure of the inverse kinematics module.
Definition: mbs_solvekin_struct.h:149
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:113
MbsInvOptions::t0
double t0
Initial time of the simulation, default = 0.0.
Definition: mbs_solvekin_struct.h:76
MbsInvOptions::animpath
const char * animpath
Path in which anim file is saved.
Definition: mbs_solvekin_struct.h:104
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:174
MbsInvOptions::verbose
int verbose
Gives informations during the process.
Definition: mbs_solvekin_struct.h:143
trajectory
@ trajectory
Definition: mbs_solvekin_struct.h:25
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::respath
const char * respath
Path in which result file are saved.
Definition: mbs_solvekin_struct.h:99
MbsSolvekin::tsim
double tsim
Current simulation time.
Definition: mbs_solvekin_struct.h:160
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
MbsSolvekin::user_buffer
MbsGrowingBuffer * user_buffer
Growing buffer to store user values.
Definition: mbs_solvekin_struct.h:171
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:110
MbsSolvekin::trajectorytype
int trajectorytype
Value to store the type of trajectory provided by the user, automatically set.
Definition: mbs_solvekin_struct.h:189
MbsSolvekin::qd
MbsLutRes * qd
Definition: mbs_solvekin_struct.h:192
MbsSolvekin::mbs_aux
MbsAux * mbs_aux
Structure to store auxiliary value needed during computation.
Definition: mbs_solvekin_struct.h:156
MbsSolvekin::savePeriodCounter
int savePeriodCounter
Counter for checking whether results must be saved.
Definition: mbs_solvekin_struct.h:180
mbs_aux.h
MbsLutRes
Structure for interpolate the trajectories of coordinates.
Definition: lut.h:40