source: flair-src/trunk/lib/FlairSimulator/src/X4.cpp @ 214

Last change on this file since 214 was 214, checked in by Sanahuja Guillaume, 4 years ago

matrix

File size: 12.8 KB
Line 
1// %flair:license{
2// This file is part of the Flair framework distributed under the
3// CECILL-C License, Version 1.0.
4// %flair:license}
5//  created:    2012/08/21
6//  filename:   X4.cpp
7//
8//  author:     Osamah Saif, Guillaume Sanahuja
9//              Copyright Heudiasyc UMR UTC/CNRS 7253
10//
11//  version:    $Id: $
12//
13//  purpose:    classe definissant un x4
14//
15/*********************************************************************/
16
17#include "X4.h"
18#include <SimuBldc.h>
19#include <TabWidget.h>
20#include <Tab.h>
21#include <DoubleSpinBox.h>
22#include <SpinBox.h>
23#include <GroupBox.h>
24#include <math.h>
25#ifdef GL
26#include <ISceneManager.h>
27#include "Blade.h"
28#include "MeshSceneNode.h"
29#include "Gui.h"
30#include <Mutex.h>
31#endif
32
33#define K_MOT 0.4f    // blade animation
34#define G (float)9.81 // gravity ( N/(m/s²) )
35
36#ifdef GL
37using namespace irr::video;
38using namespace irr::scene;
39using namespace irr::core;
40#endif
41using namespace flair::core;
42using namespace flair::gui;
43using namespace flair::actuator;
44
45namespace flair {
46namespace simulator {
47
48X4::X4(std::string name, uint32_t modelId)
49    : Model(name,modelId) {
50  Tab *setup_tab = new Tab(GetTabWidget(), "model");
51  m = new DoubleSpinBox(setup_tab->NewRow(), "mass (kg):", 0, 20, 0.1);
52  arm_length = new DoubleSpinBox(setup_tab->LastRowLastCol(), "arm length (m):",
53                                 0, 2, 0.1);
54  // l_cg=new DoubleSpinBox(setup_tab,"position G
55  // (m):",0,2,-0.5,0.5,0.02);//position du centre de gravité/centre de poussé
56  k_mot =
57      new DoubleSpinBox(setup_tab->NewRow(), "k_mot:", 0, 1, 0.001,
58                        3); // vitesse rotation² (unité arbitraire) -> force (N)
59  c_mot = new DoubleSpinBox(
60      setup_tab->LastRowLastCol(), "c_mot:", 0, 1, 0.001,
61      3); // vitesse rotation moteur -> couple (N.m/unité arbitraire)
62  f_air_vert = new DoubleSpinBox(setup_tab->NewRow(), "f_air_vert:", 0, 10,
63                                 1); // frottements air depl. vertical, aussi
64                                     // utilisé pour les rotations ( N/(m/s) )
65                                     // (du aux helices en rotation)
66  f_air_lat =
67      new DoubleSpinBox(setup_tab->LastRowLastCol(), "f_air_lat:", 0, 10,
68                        1); // frottements air deplacements lateraux ( N/(m/s) )
69  j_roll = new DoubleSpinBox(setup_tab->NewRow(), "j_roll:", 0, 1, 0.001,
70                             5); // moment d'inertie d'un axe (N.m.s²/rad)
71  j_pitch =
72      new DoubleSpinBox(setup_tab->LastRowLastCol(), "j_pitch:", 0, 1, 0.001,
73                        5); // moment d'inertie d'un axe (N.m.s²/rad)
74  j_yaw = new DoubleSpinBox(setup_tab->LastRowLastCol(), "j_yaw:", 0, 1, 0.001,
75                            5); // moment d'inertie d'un axe (N.m.s²/rad)
76                           
77  motorTimeout = new SpinBox(setup_tab->NewRow(), "motor timeout:","ms", 0, 1000, 100,100);
78
79  motors = new SimuBldc(this, name, 4, modelId,0);
80 
81  SetIsReady(true);
82}
83
84X4::~X4() {
85  // les objets irrlicht seront automatiquement detruits (moteurs, helices,
86  // pales) par parenté
87}
88
89#ifdef GL
90
91void X4::Draw(void) {
92  // create unite (1m=100cm) UAV; scale will be adapted according to arm_length
93  // parameter
94  // note that the frame used is irrlicht one:
95  // left handed, North East Up
96  const IGeometryCreator *geo;
97  geo = getGui()->getSceneManager()->getGeometryCreator();
98
99  // cylinders are aligned with y axis
100  IMesh *red_arm = geo->createCylinderMesh(2.5, 100, 16, SColor(0, 255, 0, 0));
101  IMesh *black_arm = geo->createCylinderMesh(2.5, 100, 16, SColor(0, 128, 128, 128));
102  IMesh *motor = geo->createCylinderMesh(7.5, 15, 16); //,SColor(0, 128, 128, 128));
103  // geo->drop();
104
105  ITexture *texture = getGui()->getTexture("carbone.jpg");
106  MeshSceneNode *fl_arm = new MeshSceneNode(this, red_arm, vector3df(0, 0, 0),
107                             vector3df(0, 0, -135));
108  MeshSceneNode *fr_arm = new MeshSceneNode(this, red_arm, vector3df(0, 0, 0),
109                             vector3df(0, 0, -45));
110  MeshSceneNode *rl_arm = new MeshSceneNode(this, black_arm, vector3df(0, 0, 0),
111                             vector3df(0, 0, 135), texture);
112  MeshSceneNode *rr_arm = new MeshSceneNode(this, black_arm, vector3df(0, 0, 0),
113                             vector3df(0, 0, 45), texture);
114
115  texture = getGui()->getTexture("metal047.jpg");
116  MeshSceneNode *fl_motor = new MeshSceneNode(this, motor, vector3df(70.71, -70.71, 2.5),
117                               vector3df(90, 0, 0), texture);
118  MeshSceneNode *fr_motor = new MeshSceneNode(this, motor, vector3df(70.71, 70.71, 2.5),
119                               vector3df(90, 0, 0), texture);
120  MeshSceneNode *rl_motor = new MeshSceneNode(this, motor, vector3df(-70.71, -70.71, 2.5),
121                               vector3df(90, 0, 0), texture);
122  MeshSceneNode *rr_motor = new MeshSceneNode(this, motor, vector3df(-70.71, 70.71, 2.5),
123                               vector3df(90, 0, 0), texture);
124
125  fl_blade = new Blade(this, vector3df(70.71, -70.71, 17.5));
126  fr_blade = new Blade(this, vector3df(70.71, 70.71, 17.5), true);
127  rl_blade = new Blade(this, vector3df(-70.71, -70.71, 17.5), true);
128  rr_blade = new Blade(this, vector3df(-70.71, 70.71, 17.5));
129
130  motor_speed_mutex = new Mutex(this);
131  for (int i = 0; i < 4; i++)
132    motor_speed[i] = 0;
133  ExtraDraw();
134}
135
136void X4::AnimateModel(void) {
137  motor_speed_mutex->GetMutex();
138  fl_blade->SetRotationSpeed(K_MOT * motor_speed[0]);
139  fr_blade->SetRotationSpeed(-K_MOT * motor_speed[1]);
140  rl_blade->SetRotationSpeed(-K_MOT * motor_speed[2]);
141  rr_blade->SetRotationSpeed(K_MOT * motor_speed[3]);
142  motor_speed_mutex->ReleaseMutex();
143
144  // adapt UAV size
145  if (arm_length->ValueChanged() == true) {
146    setScale(arm_length->Value());
147  }
148}
149
150size_t X4::dbtSize(void) const {
151  return 6 * sizeof(float) + 4 * sizeof(float); // 6ddl+4helices
152}
153
154void X4::WritedbtBuf(
155    char *dbtbuf) { /*
156                       float *buf=(float*)dbtbuf;
157                       vector3df vect=getPosition();
158                       memcpy(buf,&vect.X,sizeof(float));
159                       buf++;
160                       memcpy(buf,&vect.Y,sizeof(float));
161                       buf++;
162                       memcpy(buf,&vect.Z,sizeof(float));
163                       buf++;
164                       vect=getRotation();
165                       memcpy(buf,&vect.X,sizeof(float));
166                       buf++;
167                       memcpy(buf,&vect.Y,sizeof(float));
168                       buf++;
169                       memcpy(buf,&vect.Z,sizeof(float));
170                       buf++;
171                       memcpy(buf,&motors,sizeof(rtsimu_motors));*/
172}
173
174void X4::ReaddbtBuf(
175    char *dbtbuf) { /*
176                       float *buf=(float*)dbtbuf;
177                       vector3df vect;
178                       memcpy(&vect.X,buf,sizeof(float));
179                       buf++;
180                       memcpy(&vect.Y,buf,sizeof(float));
181                       buf++;
182                       memcpy(&vect.Z,buf,sizeof(float));
183                       buf++;
184                       setPosition(vect);
185                       memcpy(&vect.X,buf,sizeof(float));
186                       buf++;
187                       memcpy(&vect.Y,buf,sizeof(float));
188                       buf++;
189                       memcpy(&vect.Z,buf,sizeof(float));
190                       buf++;
191                       ((ISceneNode*)(this))->setRotation(vect);
192                       memcpy(&motors,buf,sizeof(rtsimu_motors));
193                       AnimateModele();*/
194}
195#endif // GL
196
197// states are computed on fixed frame NED
198// x north
199// y east
200// z down
201void X4::CalcModel(void) {
202  float fl_speed, fr_speed, rl_speed, rr_speed;
203  float u_roll, u_pitch, u_yaw, u_thrust;
204  Time motorTime;
205#ifdef GL
206  motor_speed_mutex->GetMutex();
207#endif // GL
208  motors->GetSpeeds(motor_speed,&motorTime);
209  if((GetTime()-motorTime)/1000000>motorTimeout->Value()) {
210    for(int i=0;i<4;i++) {
211      if(motor_speed[i]!=0) {
212         //Printf("timout\n");
213        for(int i=0;i<4;i++) motor_speed[i]=0;
214        break;
215      }
216    }
217  }
218#ifdef GL
219  motor_speed_mutex->ReleaseMutex();
220#endif // GL
221 
222  fl_speed = motor_speed[0];
223  fr_speed = motor_speed[1];
224  rl_speed = motor_speed[2];
225  rr_speed = motor_speed[3];
226
227  /*
228  ** ===================================================================
229  **    u roll: roll torque
230  **
231  ** ===================================================================
232  */
233  u_roll = arm_length->Value() * k_mot->Value() *
234           (fl_speed * fl_speed + rl_speed * rl_speed - fr_speed * fr_speed -
235            rr_speed * rr_speed) *
236           sqrtf(2) / 2;
237
238  /// Classical Nonlinear model of a quadrotor ( This is the w_x angular speed
239  /// of the quadri in the body frame). It is a discrete integrator
240  state[0].W.x =
241      (dT() / j_roll->Value()) *
242          ((j_yaw->Value() - j_pitch->Value()) * state[-1].W.y * state[-1].W.z +
243           u_roll) +
244      state[-1].W.x;
245
246  // u_roll=arm_length->Value()*k_mot->Value()*(fl_speed*fl_speed+rl_speed*rl_speed-fr_speed*fr_speed-rr_speed*rr_speed)*sqrtf(2)/2;
247  // state[0].W.x=(dT()/j_roll->Value())*(u_roll-m->Value()*G*l_cg->Value()*sinf(state[-2].W.x)-f_air_vert->Value()*arm_length->Value()*arm_length->Value()*state[-1].W.x)+state[-1].W.x;
248
249  /*
250  ** ===================================================================
251  **   u pitch : pitch torque
252  **
253  ** ===================================================================
254  */
255  u_pitch = arm_length->Value() * k_mot->Value() *
256            (fl_speed * fl_speed + fr_speed * fr_speed - rl_speed * rl_speed -
257             rr_speed * rr_speed) *
258            sqrtf(2) / 2;
259
260  /// Classical Nonlinear model of a quadrotor ( This is the w_y angular speed
261  /// of the quadri in the body frame). It is a discrete integrator
262  state[0].W.y =
263      (dT() / j_pitch->Value()) *
264          ((j_roll->Value() - j_yaw->Value()) * state[-1].W.x * state[-1].W.z +
265           u_pitch) +
266      state[-1].W.y;
267
268  // u_pitch=arm_length->Value()*k_mot->Value()*(fl_speed*fl_speed+fr_speed*fr_speed-rl_speed*rl_speed-rr_speed*rr_speed)*sqrtf(2)/2;
269  // state[0].W.y=(dT()/j_pitch->Value())*(u_pitch-m->Value()*G*l_cg->Value()*sinf(state[-2].W.y)-f_air_vert->Value()*arm_length->Value()*arm_length->Value()*state[-1].W.y)+state[-1].W.y;
270
271  /*
272  ** ===================================================================
273  **    u yaw : yaw torque
274  **
275  ** ===================================================================
276  */
277  u_yaw = c_mot->Value() * (fl_speed * fl_speed + rr_speed * rr_speed -
278                            fr_speed * fr_speed - rl_speed * rl_speed);
279
280  /// Classical Nonlinear model of a quadrotor ( This is the w_z angular speed
281  /// of the quadri in the body frame). It is a discrete integrator
282  state[0].W.z = (dT() / j_yaw->Value()) * u_yaw + state[-1].W.z;
283
284  // u_yaw=c_mot->Value()*(fl_speed*fl_speed+rr_speed*rr_speed-fr_speed*fr_speed-rl_speed*rl_speed);
285  // state[0].W.z=(dT()/j_yaw->Value())*(u_yaw-f_air_lat->Value()*state[-1].W.z)+state[-1].W.z;
286
287  // compute quaternion from W
288  // Quaternion derivative: dQ = 0.5*(Q*Qw)
289  Quaternion dQ = state[-1].Quat.GetDerivative(state[0].W);
290
291  // Quaternion integration
292  state[0].Quat = state[-1].Quat + dQ * dT();
293  state[0].Quat.Normalize();
294
295  // Calculation of the thrust from the reference speed of motors
296  u_thrust = k_mot->Value() * (fl_speed * fl_speed + fr_speed * fr_speed +
297                               rl_speed * rl_speed + rr_speed * rr_speed);
298  Vector3D<double> vect(0, 0, -u_thrust);
299  vect.Rotate(state[0].Quat);
300
301  /*
302      ** ===================================================================
303      **     x double integrator
304      **
305      ** ===================================================================
306      */
307     
308  state[0].Pos.x =
309      (dT() * dT() / m->Value()) *
310          (vect.x - f_air_lat->Value() * (state[-1].Pos.x - state[-2].Pos.x) / dT()) +
311      2 * state[-1].Pos.x - state[-2].Pos.x;
312  state[0].Vel.x = (state[0].Pos.x - state[-1].Pos.x) / dT();
313 
314  /*
315  ** ===================================================================
316  **     y double integrator
317  **
318  ** ===================================================================
319  */
320  state[0].Pos.y =
321      (dT() * dT() / m->Value()) *
322          (vect.y -
323           f_air_lat->Value() * (state[-1].Pos.y - state[-2].Pos.y) / dT()) +
324      2 * state[-1].Pos.y - state[-2].Pos.y;
325  state[0].Vel.y = (state[0].Pos.y - state[-1].Pos.y) / dT();
326
327  /*
328  ** ===================================================================
329  **     z double integrator
330  **
331  ** ===================================================================
332  */
333  state[0].Pos.z =
334      (dT() * dT() / m->Value()) *
335          (vect.z +
336           f_air_vert->Value() * (state[-1].Pos.z - state[-2].Pos.z) / dT() +
337           m->Value() * G) +
338      2 * state[-1].Pos.z - state[-2].Pos.z;
339  state[0].Vel.z = (state[0].Pos.z - state[-1].Pos.z) / dT();
340
341#ifndef GL
342  if (state[0].Pos.z < 0)
343    state[0].Pos.z = 0;
344#endif
345}
346
347} // end namespace simulator
348} // end namespace flair
Note: See TracBrowser for help on using the repository browser.