source: flair-src/branches/mavlink/lib/FlairSimulator/src/X4.cpp@ 85

Last change on this file since 85 was 15, checked in by Bayard Gildas, 9 years ago

sources reformatted with flair-format-dir script

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