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

Last change on this file since 157 was 157, checked in by Sanahuja Guillaume, 8 years ago

iadded isready to iodevice:
avoid problem of imu not ready in ardrone2

File size: 12.3 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 "Simulator.h"
19#include <SimuBldc.h>
20#include <TabWidget.h>
21#include <Tab.h>
22#include <DoubleSpinBox.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(const Simulator *parent, std::string name, int dev_id)
49 : Model(parent, name) {
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 motors = new SimuBldc(this, name, 4, dev_id);
78
79 SetIsReady(true);
80}
81
82X4::~X4() {
83 // les objets irrlicht seront automatiquement detruits (moteurs, helices,
84 // pales) par parenté
85}
86
87#ifdef GL
88
89void X4::Draw(void) {
90 // create unite (1m=100cm) UAV; scale will be adapted according to arm_length
91 // parameter
92 // note that the frame used is irrlicht one:
93 // left handed, North East Up
94 const IGeometryCreator *geo;
95 geo = getGui()->getSceneManager()->getGeometryCreator();
96
97 // cylinders are aligned with y axis
98 red_arm = geo->createCylinderMesh(2.5, 100, 16, SColor(0, 255, 0, 0));
99 black_arm = geo->createCylinderMesh(2.5, 100, 16, SColor(0, 128, 128, 128));
100 motor = geo->createCylinderMesh(7.5, 15, 16); //,SColor(0, 128, 128, 128));
101 // geo->drop();
102
103 ITexture *texture = getGui()->getTexture("carbone.jpg");
104 fl_arm = new MeshSceneNode(this, red_arm, vector3df(0, 0, 0),
105 vector3df(0, 0, -135));
106 fr_arm = new MeshSceneNode(this, red_arm, vector3df(0, 0, 0),
107 vector3df(0, 0, -45));
108 rl_arm = new MeshSceneNode(this, black_arm, vector3df(0, 0, 0),
109 vector3df(0, 0, 135), texture);
110 rr_arm = new MeshSceneNode(this, black_arm, vector3df(0, 0, 0),
111 vector3df(0, 0, 45), texture);
112
113 texture = getGui()->getTexture("metal047.jpg");
114 fl_motor = new MeshSceneNode(this, motor, vector3df(70.71, -70.71, 2.5),
115 vector3df(90, 0, 0), texture);
116 fr_motor = new MeshSceneNode(this, motor, vector3df(70.71, 70.71, 2.5),
117 vector3df(90, 0, 0), texture);
118 rl_motor = new MeshSceneNode(this, motor, vector3df(-70.71, -70.71, 2.5),
119 vector3df(90, 0, 0), texture);
120 rr_motor = new MeshSceneNode(this, motor, vector3df(-70.71, 70.71, 2.5),
121 vector3df(90, 0, 0), texture);
122
123 fl_blade = new Blade(this, vector3df(70.71, -70.71, 17.5));
124 fr_blade = new Blade(this, vector3df(70.71, 70.71, 17.5), true);
125 rl_blade = new Blade(this, vector3df(-70.71, -70.71, 17.5), true);
126 rr_blade = new Blade(this, vector3df(-70.71, 70.71, 17.5));
127
128 motor_speed_mutex = new Mutex(this);
129 for (int i = 0; i < 4; i++)
130 motor_speed[i] = 0;
131 ExtraDraw();
132}
133
134void X4::AnimateModel(void) {
135 motor_speed_mutex->GetMutex();
136 fl_blade->SetRotationSpeed(K_MOT * motor_speed[0]);
137 fr_blade->SetRotationSpeed(-K_MOT * motor_speed[1]);
138 rl_blade->SetRotationSpeed(-K_MOT * motor_speed[2]);
139 rr_blade->SetRotationSpeed(K_MOT * motor_speed[3]);
140 motor_speed_mutex->ReleaseMutex();
141
142 // adapt UAV size
143 if (arm_length->ValueChanged() == true) {
144 setScale(arm_length->Value());
145 }
146}
147
148size_t X4::dbtSize(void) const {
149 return 6 * sizeof(float) + 4 * sizeof(float); // 6ddl+4helices
150}
151
152void X4::WritedbtBuf(
153 char *dbtbuf) { /*
154 float *buf=(float*)dbtbuf;
155 vector3df vect=getPosition();
156 memcpy(buf,&vect.X,sizeof(float));
157 buf++;
158 memcpy(buf,&vect.Y,sizeof(float));
159 buf++;
160 memcpy(buf,&vect.Z,sizeof(float));
161 buf++;
162 vect=getRotation();
163 memcpy(buf,&vect.X,sizeof(float));
164 buf++;
165 memcpy(buf,&vect.Y,sizeof(float));
166 buf++;
167 memcpy(buf,&vect.Z,sizeof(float));
168 buf++;
169 memcpy(buf,&motors,sizeof(rtsimu_motors));*/
170}
171
172void X4::ReaddbtBuf(
173 char *dbtbuf) { /*
174 float *buf=(float*)dbtbuf;
175 vector3df vect;
176 memcpy(&vect.X,buf,sizeof(float));
177 buf++;
178 memcpy(&vect.Y,buf,sizeof(float));
179 buf++;
180 memcpy(&vect.Z,buf,sizeof(float));
181 buf++;
182 setPosition(vect);
183 memcpy(&vect.X,buf,sizeof(float));
184 buf++;
185 memcpy(&vect.Y,buf,sizeof(float));
186 buf++;
187 memcpy(&vect.Z,buf,sizeof(float));
188 buf++;
189 ((ISceneNode*)(this))->setRotation(vect);
190 memcpy(&motors,buf,sizeof(rtsimu_motors));
191 AnimateModele();*/
192}
193#endif // GL
194
195// states are computed on fixed frame NED
196// x north
197// y east
198// z down
199void X4::CalcModel(void) {
200 float fl_speed, fr_speed, rl_speed, rr_speed;
201 float u_roll, u_pitch, u_yaw, u_thrust;
202#ifdef GL
203 motor_speed_mutex->GetMutex();
204#endif // GL
205 motors->GetSpeeds(motor_speed);
206#ifdef GL
207 motor_speed_mutex->ReleaseMutex();
208#endif // GL
209 fl_speed = motor_speed[0];
210 fr_speed = motor_speed[1];
211 rl_speed = motor_speed[2];
212 rr_speed = motor_speed[3];
213
214 /*
215 ** ===================================================================
216 ** u roll: roll torque
217 **
218 ** ===================================================================
219 */
220 u_roll = arm_length->Value() * k_mot->Value() *
221 (fl_speed * fl_speed + rl_speed * rl_speed - fr_speed * fr_speed -
222 rr_speed * rr_speed) *
223 sqrtf(2) / 2;
224
225 /// Classical Nonlinear model of a quadrotor ( This is the w_x angular speed
226 /// of the quadri in the body frame). It is a discrete integrator
227 state[0].W.x =
228 (dT() / j_roll->Value()) *
229 ((j_yaw->Value() - j_pitch->Value()) * state[-1].W.y * state[-1].W.z +
230 u_roll) +
231 state[-1].W.x;
232
233 // 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;
234 // 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;
235
236 /*
237 ** ===================================================================
238 ** u pitch : pitch torque
239 **
240 ** ===================================================================
241 */
242 u_pitch = arm_length->Value() * k_mot->Value() *
243 (fl_speed * fl_speed + fr_speed * fr_speed - rl_speed * rl_speed -
244 rr_speed * rr_speed) *
245 sqrtf(2) / 2;
246
247 /// Classical Nonlinear model of a quadrotor ( This is the w_y angular speed
248 /// of the quadri in the body frame). It is a discrete integrator
249 state[0].W.y =
250 (dT() / j_pitch->Value()) *
251 ((j_roll->Value() - j_yaw->Value()) * state[-1].W.x * state[-1].W.z +
252 u_pitch) +
253 state[-1].W.y;
254
255 // 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;
256 // 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;
257
258 /*
259 ** ===================================================================
260 ** u yaw : yaw torque
261 **
262 ** ===================================================================
263 */
264 u_yaw = c_mot->Value() * (fl_speed * fl_speed + rr_speed * rr_speed -
265 fr_speed * fr_speed - rl_speed * rl_speed);
266
267 /// Classical Nonlinear model of a quadrotor ( This is the w_z angular speed
268 /// of the quadri in the body frame). It is a discrete integrator
269 state[0].W.z = (dT() / j_yaw->Value()) * u_yaw + state[-1].W.z;
270
271 // u_yaw=c_mot->Value()*(fl_speed*fl_speed+rr_speed*rr_speed-fr_speed*fr_speed-rl_speed*rl_speed);
272 // state[0].W.z=(dT()/j_yaw->Value())*(u_yaw-f_air_lat->Value()*state[-1].W.z)+state[-1].W.z;
273
274 // compute quaternion from W
275 // Quaternion derivative: dQ = 0.5*(Q*Qw)
276 Quaternion dQ = state[-1].Quat.GetDerivative(state[0].W);
277
278 // Quaternion integration
279 state[0].Quat = state[-1].Quat + dQ * dT();
280 state[0].Quat.Normalize();
281
282 // Calculation of the thrust from the reference speed of motors
283 u_thrust = k_mot->Value() * (fl_speed * fl_speed + fr_speed * fr_speed +
284 rl_speed * rl_speed + rr_speed * rr_speed);
285 Vector3D vect(0, 0, -u_thrust);
286 vect.Rotate(state[0].Quat);
287
288 /*
289 ** ===================================================================
290 ** x double integrator
291 **
292 ** ===================================================================
293 */
294 state[0].Pos.x =
295 (dT() * dT() / m->Value()) *
296 (vect.x -
297 f_air_lat->Value() * (state[-1].Pos.x - state[-2].Pos.x) / dT()) +
298 2 * state[-1].Pos.x - state[-2].Pos.x;
299 state[0].Vel.x = (state[0].Pos.x - state[-1].Pos.x) / dT();
300
301 /*
302 ** ===================================================================
303 ** y double integrator
304 **
305 ** ===================================================================
306 */
307 state[0].Pos.y =
308 (dT() * dT() / m->Value()) *
309 (vect.y -
310 f_air_lat->Value() * (state[-1].Pos.y - state[-2].Pos.y) / dT()) +
311 2 * state[-1].Pos.y - state[-2].Pos.y;
312 state[0].Vel.y = (state[0].Pos.y - state[-1].Pos.y) / dT();
313
314 /*
315 ** ===================================================================
316 ** z double integrator
317 **
318 ** ===================================================================
319 */
320 state[0].Pos.z =
321 (dT() * dT() / m->Value()) *
322 (vect.z +
323 f_air_vert->Value() * (state[-1].Pos.z - state[-2].Pos.z) / dT() +
324 m->Value() * G) +
325 2 * state[-1].Pos.z - state[-2].Pos.z;
326 state[0].Vel.z = (state[0].Pos.z - state[-1].Pos.z) / dT();
327
328#ifndef GL
329 if (state[0].Pos.z < 0)
330 state[0].Pos.z = 0;
331#endif
332}
333
334} // end namespace simulator
335} // end namespace flair
Note: See TracBrowser for help on using the repository browser.