IdentifiantMot de passe
Loading...
Mot de passe oublié ?Je m'inscris ! (gratuit)

Vous êtes nouveau sur Developpez.com ? Créez votre compte ou connectez-vous afin de pouvoir participer !

Vous devez avoir un compte Developpez.com et être connecté pour pouvoir participer aux discussions.

Vous n'avez pas encore de compte Developpez.com ? Créez-en un en quelques instants, c'est entièrement gratuit !

Si vous disposez déjà d'un compte et qu'il est bien activé, connectez-vous à l'aide du formulaire ci-dessous.

Identifiez-vous
Identifiant
Mot de passe
Mot de passe oublié ?
Créer un compte

L'inscription est gratuite et ne vous prendra que quelques instants !

Je m'inscris !

Un quadrirotor réalisé maison sans Arduino/Multiwii
Réalisé par Sylbain Mahe, le code source est disponible

Le , par sylvainmahe

29PARTAGES

11  0 
Bonjour

Pour que vous compreniez le sujet et mon intervention, je fait un bref récapitulatif de ma modeste expérience de l'électronique:

J'ai donc débuté l'électronique amateur il y a 1 an, au départ je ne savais pas à quoi servait un condensateur, je suis donc parti de zéro.
J'ai été comme un peu tout les amateurs qui ne savent pas par ou commencer au départ, j'ai téléchargé Arduino, puis au bout d'une semaine j'ai voulu savoir ce qu'il y avait derrière digitalWrite, et 2 ou 3 fonctions que j'avais utilisé au courant de cette semaine découverte. J'ai été voir la source et j'ai compris qu'il suffisait d'appliquer mes connaissances en programmation C++, de lire les 650 pages du datasheet du 328P (voir ici: http://www.atmel.com/images/Atmel-82...t_Complete.pdf), pour créer ma propre bibliothèque et me passer finalement d'Arduino. Voila en gros le résumé.

Photos de quelques projets en électronique que j'ai réalisé durant l'année
http://sylvainmahe.xyz/forum/

Ceci étant dit, la bibliothèque étant maintenant terminée, je la met à disposition des internautes dans le but qu'ils puissent créer tout comme moi des projets assez complexes très facilement
Voici donc pour télécharger ma bibliothèque (qui n'a pas encore de nom): http://sylvainmahe.xyz/
(mon site dédié au projet est encore en construction)

J'estime le temps de développement de cette bibliothèque à entre 3000 à 4000 heures durant l'année.

Coté performances, ma bibliothèque est plus proche d'avr que d'arduino, par exemple, 1 million de pin toggling donne:
AVR: 651ms
ma bibliothèque: 753ms
Arduino: 4550ms


Le sujet ici présent: J'ai dernièrement construit un quadricoptère (chassis/carte pcb/électronique/programmation) en utilisant les fonctions de ma bibliothèque (voir lien ci-dessus), j'aimerais partager avec vous cette expérience car elle peut être intéressante pour ceux qui souhaitent se lancer dans le quadricoptère fait maison sans utiliser Arduino/Multiwii

Le premier test moteur avec hélices:


Les premiers tests en vol hier:


La puissance peut paraître légère (c'est censé être un quadricoptère de voltige), mais pour les premiers tests j'ai réglé la course des gaz à 50% max pour plus de sécurité, ceci explique cela Demain j'essayerais avec 100% de gaz.

Pour commencer, le code source sans ma bibliothèque (le main.cpp), fait seulement 326 lignes, donc sachez qu'un quadricoptère est en ordre de vol avec seulement 326 lignes dans le main avec ma bibliothèque qui tourne derrière, c'est très peu, ceci avec toutes les sécurités d'avant vol au branchement de la batterie lipo avec buzzer de signalement, à savoir:-vérification que votre radiocommande est bien calibrée-vérification de l'arrivée du pwm de toutes les voies du récepteur-vérification de l'inter coupure moteur activé et du manche de gaz inférieur à 10%

Et également avec la musique au démarrage, ce qui n'est pas indispensable vous en conviendrez

Voila la photo du quadricoptère:


La photo de la carte électronique:



Cette carte maison me sert à tous mes projets en électronique.Le plan de celle-ci se trouve en bas du sujet.

La machine pour réaliser le châssis, si vous le réalisez en tube aluminium le mieux est d'avoir une fraiseuse sous la main:



L'idée de ce topic est de comprendre qu'avec ma bibliothèque on peut en quelques lignes de programmation créer des choses plus ou moins complexes beaucoup plus facilement qu'Arduino et avec une plus grande vitesse d'execution et une quantité de mémoire moindre.

Exemple/Tuto - Potar + Servo avec ma bibliothèque (sans Arduino):

Vous devez déjà savoir programmer et linker une bibliothèque, avoir une petite idée de pourquoi se passer d'Arduino et qu'il faut AVR (l'architecture AVR de l'atmega328p), mais dans l'idéal, le processus est:

-télécharger la bibliothèque, décompresser les fichiers
-avoir une carte arduino uno ou équivalent
-avoir un programmateur (vous pouvez utiliser l'usbasp avec mes batchs windows ou linux inclus dans l'archive de la bibliothèque pour compiler)
-avoir avr c d'installé sur votre ordinateur
-avoir un servo-moteur et un potentiomètre sous la main

J'ai créé une vidéo qui vous montre très exactement la procédure:


Je recopie mon exemple ici (main.cpp):
Code : Sélectionner tout
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
#include "../library/Potentiometer.h"
#include "../library/Servo.h"

using namespace std;

int main()
{
	Servo myServo = Servo (1, 1100, 1900);
	Potentiometer myPotentiometer = Potentiometer (15);
	
	Servo::start (250);
	
	while (true)
	{
		myPotentiometer.state();
		
		myServo.pulse (myPotentiometer.curve (0, 1023, 1100, 1900, 0));
	}
	
	return 0;
}
En premier, remplacer "library" par le dossier dans l'archive qui contient la bibliothèque, encore une fois je ne suis pas encore sûr du nom que je vais lui donner.

A la déclaration de l'objet Servo, le premier paramètre est le numéro de la pin sur la carte (voir ma carte 328P en bas de ce sujet pour connaître la distribution des pins sur votre carte Arduino UNO par rapport à la mienne).
On indique également 1100, c'est le débattement min du servo, et 1900 le max, voyez le datasheet de votre servo-moteur pour connaître ces débattements, ou faites des tests.

A la déclaration de l'objet Potentiometer, on indique juste le numéro de la pin, ici la 15 c'est à dire PC0.
Ensuite on démarre le servo-moteur avec Servo::start et on indique en paramètre la fréquence du servo en Hz. Ici c'est un savox qui va jusqu'à 250Hz.

Dans la boucle principale on récupère l'état du potentiomètre avec state, sa correspond à connaître la tension en valeur 10 bit sur la pin PC0.

Ensuite on indique une position de palonnier de servo-moteur avec pulse, on lui injecte avec la fonction curve du potentiomètre la tension sous la forme d'une valeur de 10 bit (0 à 1023) interpolé de 1100 à 1900 (les débattements en us de notre servo-moteur) tout cela avec une courbe linéaire (le 0 à la fin).

Ensuite compilation avec le compilateur AVR et upload dans l'Atmega 328P avec le programmateur de votre choix, moi j'utilise l'usbasp, voir ici:
http://www.fischl.de/usbasp/

Et normalement ça fonctionne

Photos pour comprendre la distribution des pins sur ma carte 328P faite maison en relation avec la distribution des pins de ma bibliothèque:



Ma carte 328P et ma bibliothèque me servent à réaliser pleins de projets, cette carte n'est pas plus spécialisé dans le quadricoptère qu'autre chose, un exemple d'autre projet avec cette carte:
Un jeu PONG:


Voila ce sera tout pour aujourd'hui, n'hésitez pas si vous avez des interrogations ou des commentaires

Une erreur dans cette actualité ? Signalez-nous-la !

Avatar de sylvainmahe
Membre régulier https://www.developpez.com
Le 14/11/2015 à 21:44
Voila après une 30ène de vols de tests le code source final sans horizon artificiel (pour l'instant):
Main.cpp
Code : Sélectionner tout
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
#include "../library/Timer.h"
#include "../library/Delay.h"
#include "../library/Random.h"
#include "../library/Math.h"
#include "../library/Buzzer.h"
#include "../library/Servo.h"
#include "../library/Cycle.h"
#include "../library/Gyroscope.h"

using namespace std;

int main()
{
	uint8_t n = 0;
	Gyroscope mpu6050 = Gyroscope (0);
	Cycle channelThrottle = Cycle (1, false);
	uint16_t slowChannelThrottle = 0;
	uint16_t centerChannelThrottle = 0;
	Cycle channelPitch = Cycle (2, false);
	uint16_t centerChannelPitch = 0;
	Cycle channelRoll = Cycle (3, false);
	uint16_t centerChannelRoll = 0;
	Cycle channelYaw = Cycle (4, false);
	uint16_t centerChannelYaw = 0;
	Cycle channelHold = Cycle (5, false);
	uint16_t centerChannelHold = 0;
	Cycle channelOption = Cycle (6, false);
	uint16_t centerChannelOption = 0;
	Servo motor1 = Servo (7, 0, 0, 0);
	Servo motor2 = Servo (8, 0, 0, 0);
	Servo motor3 = Servo (9, 0, 0, 0);
	Servo motor4 = Servo (10, 0, 0, 0);
	Delay delaySoundStartCondition = Delay (1000, false);
	uint16_t mixThrottle = 0;
	int16_t mixThrustPitchGain = 0;
	int16_t mixThrustRollGain = 0;
	int16_t mixInertiaYawGain = 0;
	int16_t mixMinClearancePitch = 0;
	int16_t mixMaxClearancePitch = 0;
	int16_t mixMinClearanceRoll = 0;
	int16_t mixMaxClearanceRoll = 0;
	int16_t mixMinClearanceYaw = 0;
	int16_t mixMaxClearanceYaw = 0;
	const uint16_t SPEED_GYRO = 1000;
	int16_t speedPitch = 0;
	int16_t speedRoll = 0;
	int16_t speedYaw = 0;
	int16_t mixPitchOffsetGyro = 0;
	int16_t mixRollOffsetGyro = 0;
	int16_t mixYawOffsetGyro = 0;
	uint8_t thrustGainPitch = 0;
	uint8_t thrustGainRoll = 0;
	uint8_t inertiaGainYaw = 0;
	uint16_t gainMinRxGyro = 0;
	uint16_t gainMaxRxGyro = 0;
	uint16_t gainMinRyGyro = 0;
	uint16_t gainMaxRyGyro = 0;
	uint16_t gainMinRzGyro = 0;
	uint16_t gainMaxRzGyro = 0;
	int16_t mixMinRxGyro = 0;
	int16_t mixMaxRxGyro = 0;
	int16_t mixMinRyGyro = 0;
	int16_t mixMaxRyGyro = 0;
	int16_t mixMinRzGyro = 0;
	int16_t mixMaxRzGyro = 0;
	uint16_t mixMotor1 = 0;
	uint16_t mixMotor2 = 0;
	uint16_t mixMotor3 = 0;
	uint16_t mixMotor4 = 0;
	const uint16_t SETUP_MIN_CHANNEL_THROTTLE = 1000;
	const uint16_t SETUP_MAX_CHANNEL_THROTTLE = 2000;
	const uint16_t SETUP_MIN_CHANNEL_PITCH = 1000;
	const uint16_t SETUP_MAX_CHANNEL_PITCH = 2000;
	const uint16_t SETUP_MIN_CHANNEL_ROLL = 1000;
	const uint16_t SETUP_MAX_CHANNEL_ROLL = 2000;
	const uint16_t SETUP_MIN_CHANNEL_YAW = 1000;
	const uint16_t SETUP_MAX_CHANNEL_YAW = 2000;
	const uint16_t SETUP_MIN_CHANNEL_HOLD = 1000;
	const uint16_t SETUP_MAX_CHANNEL_HOLD = 2000;
	const uint16_t SETUP_MIN_CHANNEL_OPTION = 1500;
	const uint16_t SETUP_MAX_CHANNEL_OPTION = 2000;
	const int16_t SETUP_ZERO_PITCH = 38;
	const int16_t SETUP_ZERO_ROLL = -11;
	const int16_t SETUP_ZERO_YAW = -46;
	const uint16_t SETUP_FREQUENCY_ESC = 100;
	const uint16_t SETUP_HOLD_ESC = 950;
	const uint16_t SETUP_MIN_ESC = 1050;
	const uint16_t SETUP_MAX_ESC = 1950;
	const uint16_t SETUP_TRAVEL_PITCH = 300;
	const uint16_t SETUP_TRAVEL_ROLL = 300;
	const uint16_t SETUP_TRAVEL_YAW = 300;
	const uint16_t SETUP_SPEED_PITCH = 300;
	const uint16_t SETUP_SPEED_ROLL = 300;
	const uint16_t SETUP_SPEED_YAW = 200;
	const uint8_t SETUP_GAIN_PITCH = 87;
	const uint8_t SETUP_GAIN_ROLL = 83;
	const uint8_t SETUP_GAIN_YAW = 92;
	const uint8_t SETUP_THRUST_PROPELLER = 60;
	const uint8_t SETUP_INERTIA_PROPELLER = 100;
	
	Timer::pause (1000);
	
	slowChannelThrottle = round (double (SETUP_MIN_CHANNEL_THROTTLE) + ((double (SETUP_MAX_CHANNEL_THROTTLE) - double (SETUP_MIN_CHANNEL_THROTTLE)) / double (10)));
	centerChannelThrottle = round (double (SETUP_MAX_CHANNEL_THROTTLE) - ((double (SETUP_MAX_CHANNEL_THROTTLE) - double (SETUP_MIN_CHANNEL_THROTTLE)) / double (2)));
	centerChannelPitch = round (double (SETUP_MAX_CHANNEL_PITCH) - ((double (SETUP_MAX_CHANNEL_PITCH) - double (SETUP_MIN_CHANNEL_PITCH)) / double (2)));
	centerChannelRoll = round (double (SETUP_MAX_CHANNEL_ROLL) - ((double (SETUP_MAX_CHANNEL_ROLL) - double (SETUP_MIN_CHANNEL_ROLL)) / double (2)));
	centerChannelYaw = round (double (SETUP_MAX_CHANNEL_YAW) - ((double (SETUP_MAX_CHANNEL_YAW) - double (SETUP_MIN_CHANNEL_YAW)) / double (2)));
	centerChannelHold = round (double (SETUP_MAX_CHANNEL_HOLD) - ((double (SETUP_MAX_CHANNEL_HOLD) - double (SETUP_MIN_CHANNEL_HOLD)) / double (2)));
	centerChannelOption = round (double (SETUP_MAX_CHANNEL_OPTION) - ((double (SETUP_MAX_CHANNEL_OPTION) - double (SETUP_MIN_CHANNEL_OPTION)) / double (2)));
	
	Buzzer::pin (11);
	
	while (centerChannelThrottle == 0 || centerChannelPitch == 0 || centerChannelRoll == 0 || centerChannelYaw == 0 || centerChannelHold == 0 || centerChannelOption == 0)
	{
		delaySoundStartCondition.state();
		
		if (delaySoundStartCondition.update == true)
		{
			Buzzer::play (200, 100);
		}
	}
	
	delaySoundStartCondition.reset();
	
	Cycle::start (100);
	
	while (channelThrottle.us == 0 || channelPitch.us == 0 || channelRoll.us == 0 || channelYaw.us == 0 || channelHold.us == 0 || channelHold.us == 0)
	{
		channelThrottle.state();
		channelPitch.state();
		channelRoll.state();
		channelYaw.state();
		channelHold.state();
		channelOption.state();
		
		delaySoundStartCondition.state();
		
		if (delaySoundStartCondition.update == true)
		{
			Buzzer::key (200, 100);
			Buzzer::key (0, 100);
			Buzzer::key (200, 100);
			Buzzer::playKey();
		}
	}
	
	delaySoundStartCondition.reset();
	
	while (channelThrottle.us > slowChannelThrottle || channelHold.us < centerChannelHold)
	{
		channelThrottle.state();
		channelHold.state();
		
		delaySoundStartCondition.state();
		
		if (delaySoundStartCondition.update == true)
		{
			Buzzer::key (200, 100);
			Buzzer::key (0, 100);
			Buzzer::key (200, 100);
			Buzzer::key (0, 100);
			Buzzer::key (200, 100);
			Buzzer::playKey();
		}
	}
	
	Random::seed (15);
	
	for (n = 0; n < 16; n++)
	{
		if (n != 0)
		{
			Buzzer::key (0, Random::integer (25, 75));
		}
		
		Buzzer::key (Random::integer (70, 3000), Random::integer (25, 75));
	}
	
	Buzzer::playKey();
	
	speedPitch = Math::curve (0, SETUP_SPEED_PITCH, SPEED_GYRO, 0, 32767, 0);
	speedRoll = Math::curve (0, SETUP_SPEED_ROLL, SPEED_GYRO, 0, 32767, 0);
	speedYaw = Math::curve (0, SETUP_SPEED_YAW, SPEED_GYRO, 0, 32767, 0);
	
	thrustGainPitch = Math::curve (0, SETUP_THRUST_PROPELLER, 100, 0, SETUP_GAIN_PITCH, 0);
	gainMinRxGyro = Math::curve (0, thrustGainPitch, 100, 32767, 0, 0);
	gainMaxRxGyro = Math::curve (0, SETUP_GAIN_PITCH, 100, 32767, 0, 0);
	
	thrustGainRoll = Math::curve (0, SETUP_THRUST_PROPELLER, 100, 0, SETUP_GAIN_ROLL, 0);
	gainMinRyGyro = Math::curve (0, thrustGainRoll, 100, 32767, 0, 0);
	gainMaxRyGyro = Math::curve (0, SETUP_GAIN_ROLL, 100, 32767, 0, 0);
	
	inertiaGainYaw = Math::curve (0, SETUP_INERTIA_PROPELLER, 100, 0, SETUP_GAIN_YAW, 0);
	gainMinRzGyro = Math::curve (0, inertiaGainYaw, 100, 32767, 0, 0);
	gainMaxRzGyro = Math::curve (0, SETUP_GAIN_YAW, 100, 32767, 0, 0);
	
	mpu6050.setZero (SETUP_ZERO_PITCH, SETUP_ZERO_ROLL, SETUP_ZERO_YAW);
	
	motor1.hold (SETUP_HOLD_ESC);
	motor1.min (SETUP_MIN_ESC);
	motor1.max (SETUP_MAX_ESC);
	motor2.hold (SETUP_HOLD_ESC);
	motor2.min (SETUP_MIN_ESC);
	motor2.max (SETUP_MAX_ESC);
	motor3.hold (SETUP_HOLD_ESC);
	motor3.min (SETUP_MIN_ESC);
	motor3.max (SETUP_MAX_ESC);
	motor4.hold (SETUP_HOLD_ESC);
	motor4.min (SETUP_MIN_ESC);
	motor4.max (SETUP_MAX_ESC);
	
	motor1.moveHold();
	motor2.moveHold();
	motor3.moveHold();
	motor4.moveHold();
	
	Servo::start (SETUP_FREQUENCY_ESC);
	
	while (true)
	{
		mpu6050.state();
		channelThrottle.state();
		channelPitch.state();
		channelRoll.state();
		channelYaw.state();
		channelHold.state();
		channelOption.state();
		
		if (channelHold.us > centerChannelHold)
		{
			motor1.moveHold();
			motor2.moveHold();
			motor3.moveHold();
			motor4.moveHold();
		}
		else
		{
			mixThrottle = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, SETUP_MIN_ESC, SETUP_MAX_ESC, 0);
			
			mixMotor1 = mixThrottle;
			mixMotor2 = mixThrottle;
			mixMotor3 = mixThrottle;
			mixMotor4 = mixThrottle;
			
			mixMinClearancePitch = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, 0, SETUP_TRAVEL_PITCH, 0);
			mixMaxClearancePitch = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, SETUP_TRAVEL_PITCH, 0, 0);
			mixPitchOffsetGyro = Math::curve (SETUP_MIN_CHANNEL_PITCH, channelPitch.us, SETUP_MAX_CHANNEL_PITCH, -speedPitch, speedPitch, 0);
			mixThrustPitchGain = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, gainMaxRxGyro, gainMinRxGyro, 0);
			mixMinRxGyro = Math::wurve (-mixThrustPitchGain, mpu6050.rx + mixPitchOffsetGyro, mixThrustPitchGain, -mixMaxClearancePitch, 0, mixMinClearancePitch, 0, 0);
			mixMaxRxGyro = Math::wurve (-mixThrustPitchGain, mpu6050.rx + mixPitchOffsetGyro, mixThrustPitchGain, -mixMinClearancePitch, 0, mixMaxClearancePitch, 0, 0);
			
			mixMotor1 -= mixMinRxGyro;
			mixMotor2 -= mixMinRxGyro;
			mixMotor3 += mixMaxRxGyro;
			mixMotor4 += mixMaxRxGyro;
			
			mixMinClearanceRoll = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, 0, SETUP_TRAVEL_ROLL, 0);
			mixMaxClearanceRoll = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, SETUP_TRAVEL_ROLL, 0, 0);
			mixRollOffsetGyro = Math::curve (SETUP_MIN_CHANNEL_ROLL, channelRoll.us, SETUP_MAX_CHANNEL_ROLL, -speedRoll, speedRoll, 0);
			mixThrustRollGain = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, gainMaxRyGyro, gainMinRyGyro, 0);
			mixMinRyGyro = Math::wurve (-mixThrustRollGain, mpu6050.ry - mixRollOffsetGyro, mixThrustRollGain, -mixMaxClearanceRoll, 0, mixMinClearanceRoll, 0, 0);
			mixMaxRyGyro = Math::wurve (-mixThrustRollGain, mpu6050.ry - mixRollOffsetGyro, mixThrustRollGain, -mixMinClearanceRoll, 0, mixMaxClearanceRoll, 0, 0);
			
			mixMotor1 -= mixMinRyGyro;
			mixMotor2 += mixMaxRyGyro;
			mixMotor3 -= mixMinRyGyro;
			mixMotor4 += mixMaxRyGyro;
			
			mixMinClearanceYaw = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, 0, SETUP_TRAVEL_YAW, 0);
			mixMaxClearanceYaw = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, SETUP_TRAVEL_YAW, 0, 0);
			mixYawOffsetGyro = Math::curve (SETUP_MIN_CHANNEL_YAW, channelYaw.us, SETUP_MAX_CHANNEL_YAW, -speedYaw, speedYaw, 0);
			mixInertiaYawGain = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, gainMaxRzGyro, gainMinRzGyro, 0);
			mixMinRzGyro = Math::wurve (-mixInertiaYawGain, mpu6050.rz + mixYawOffsetGyro, mixInertiaYawGain, -mixMaxClearanceYaw, 0, mixMinClearanceYaw, 0, 0);
			mixMaxRzGyro = Math::wurve (-mixInertiaYawGain, mpu6050.rz + mixYawOffsetGyro, mixInertiaYawGain, -mixMinClearanceYaw, 0, mixMaxClearanceYaw, 0, 0);
			
			mixMotor1 -= mixMinRzGyro;
			mixMotor2 += mixMaxRzGyro;
			mixMotor3 += mixMaxRzGyro;
			mixMotor4 -= mixMinRzGyro;
			
			motor1.pulse (mixMotor1);
			motor2.pulse (mixMotor2);
			motor3.pulse (mixMotor3);
			motor4.pulse (mixMotor4);
		}
	}
	
	return 0;
}
Pour quadricoptère avec:
Moteur1 = avant gauche
Moteur2 = avant droit
Moteur3 = arrière gauche
Moteur4 = arrière droit

Les paramètres à adapter selon votre quad commencent par le préfixe SETUP.
La gestion des moteurs prends en compte le rendement des hélices (paramètre THRUST), cette gestion est asymétrique de sorte que vous avez votre plein ralenti et plein gaz avec 100% des ordres pitch/roll/yaw disponible même manche de gaz (THROTTLE) en butée mini ou maxi.

Le quad est très verrouillé sur ses axes, la voltige passe sans aucune difficulté, j'ai testé pleins de choses: plein gaz vers le bas, boucles carrés, etc...

Il y a bien-sûr les trois sécurités d'avant démarrage que j'ai cité dans ce sujet.

Ma config actuelle est:
tiger motors mn2206
kiss esc 18A
lipo 4s 2200mAh
hélices hq 6x4.5"

Le code est très robuste, vous pouvez-y aller sans problème N'hésitez pas si vous avez un soucis ou des questions.
2  0 
Avatar de sylvainmahe
Membre régulier https://www.developpez.com
Le 02/01/2016 à 16:51
Nouvelle vidéo avec un peu de voltige
(soyez indulgents c'est pas facile de piloter avec les pouces gelés :p)






N'hésitez pas si vous avez des interrogations coté réalisation ou autre.
2  0 
Avatar de sylvainmahe
Membre régulier https://www.developpez.com
Le 16/01/2016 à 11:12
Après quelques mois de recherches infructueuses en ce qui concerne le nom et le logo de mon projet cartes+bibliothèque, j'ai finalement réussi à en dessiner un qui me convient:



Module integrated = module intégré (pour les non anglophones)
Module pour modulable, mais aussi pour génération de signal modulé (pulse width modulation), d’où la forme du logo (onde carrée). GPL pour General Public Licence (https://fr.wikipedia.org/wiki/Licenc...%C3%A9rale_GNU).

J'ai aussi travaillé sur le site aujourd'hui pour que cela soit cohérent niveau formes et couleurs, mais il me faudra d'autres week-end pour finaliser ce site
http://sylvainmahe.xyz/

Encore une fois n'hésitez pas pour les commentaires et si vous avez des questions pour le fonctionnement de la bibliothèque, et/ou idées que vous pouvez apporter
2  0 
Avatar de nikko34
Membre éprouvé https://www.developpez.com
Le 01/02/2016 à 3:12
Comme dans avr-gcc il y a un compilateur C++11, tu peux t'amuser aussi.

Ya une technique en utilisant des templates pour ne pas avoir à gérer des pointeurs sur les pins par ex., mais juste changer directement la pin que tu veux. Dans ce doc : http://www.open-std.org/jtc1/sc22/wg...cs/TR18015.pdf à partir de la page 137. Je l'ai implementé, ça marchait nickel.

Bon en gros, pour faire simple, sans rentrer dans le détail, au lieu d'avoir:

LED myLed( pinPtr );

tu aurais plutôt un objet io_pin que tu changerais directement!

// ici la définition générale de tous tes pins avec juste des typedefs
typedef io_pin< PortB, 5 > DebugLed;

et dans le code (dans un objet spécifique "LED DE DEBUG" si tu veux aussi: )

DebugLed::set( true );

par ex.

Comme le cablage ne changera pas trop dynamiquement, tu as un pointeur et une indirection en moins. Bon je sais pas si c'est très clair, c'est pas évident à mettre en place.

Oui, j'ai une petite idée de faire une librairie C++ embedded aussi
1  0 
Avatar de sylvainmahe
Membre régulier https://www.developpez.com
Le 24/06/2016 à 11:15
Exemple de radiocommande une voie avec ma bibliothèque et le composant nrf24l01p ! ^_^

Imaginons que vous voulez transmettre la valeur d'un potentiomètre à votre modèle, ça donne ceci:

Code : Sélectionner tout
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
#include "../module/Nrf24L01P.h"
#include "../module/AnalogRead.h"

int main()
{
	Nrf24L01P canal = Nrf24L01P (1);
	AnalogRead potar = AnalogRead (15);
	
	Nrf24L01P::start (1, 86400312, true);
	
	while (true)
	{
		potar.state();
		
		canal.transmit (potar.value);
	}
	
	return 0;
}
Et à l'autre bout, on fait bouger un servo avec la valeur du potentiomètre qu'on reçois par radio:

Code : Sélectionner tout
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
#include "../module/Nrf24L01P.h"
#include "../module/PwmWrite.h"

int main()
{
	Nrf24L01P canal = Nrf24L01P (1);
	PwmWrite servo = PwmWrite (1, 0, 500, 1000);
	
	Nrf24L01P::start (1, 86400312, true);
	PwmWrite::start (50);
	
	while (true)
	{
		canal.receive();
		
		servo.pulse (canal.value);
	}
	
	return 0;
}
C'est pas plus compliqué que ça, mais avec ce modeste code vous avez déjà une radiocommande 1 voie

A noter que "86400312" c'est un identifiant unique sur 32 bits (une clé réseau si vous voulez), que vous choisissez à votre guise pour sécuriser la communication entre les deux nrf24l01p.

Les possibilités sont vraiment grandes, vous pouvez émettre, transmettre à la suite dans n'importe quel ordre, j'ai essayé par exemple des configurations un peu délicates à savoir:
incrément d'une valeur (par exemple le temps qui passe)
transmission de cette valeur d'un module 1 à un autre module 2
réception de la valeur depuis le module 2 puis émission vers le module 1
réémission de la valeur reçue du module 1 vers le module 2
réémission de la valeur du module 2 vers le module 1
affichage de la valeur sur un afficheur à leds via le module 1

Et ça marche vraiment impec sans bugs, avec une latence de l'ordre du millième de secondes, et avec une portée d'au moins 1km bien-sûr

Les données utiles qui transitent sont sur 32 bits signés (+ 8 bit pour le canal ou l'adresse).

A vous de jouer
1  0 
Avatar de sylvainmahe
Membre régulier https://www.developpez.com
Le 28/06/2016 à 14:53
J'ai bien avancé dans mon histoire de quadri auto-stable sur l'horizon, j'ai testé hier un nouveau code qui utilise la rapidité du mpu6050 (le mode de vol normal c'est à dire acrobaties), et la fusion gyro+magnétomètre du bno055 pour avoir un pitch/roll verrouillé (le mode de vol horizon).

On passe de l'un a l'autre avec un inter sur la radio, ça permet de voler en mode débutant (horizon), c'est vraiment très très facile à piloter pour le coup, et quand on bascule l'inter on peut faire de la voltige (le roll et le pitch ne suivent plus l'horizon et ne sont plus bloqués a des angles min/max qu'on prédéfini).
Cet inter permet aussi de sauver le modèle si jamais on est perdu dans nos manches (ca remet le quadri a plat), j'ai pas encore testé ça en vol, mettre le quadri sur le dos et basculer l'inter horizon, mais ça ne serait tarder.

J'ai fait une vidéo pour vous montrer ce mode:



Et une nouveauté sinon: à la "demande" d'un youtubeur, j'ai créé le bout de code qu'il faut pour faire fonctioner le magnétomètre Hmc5883L.
-> https://cdn-shop.adafruit.com/datasheet ... ass_IC.pdf

C'est maintenant inclus dans ma bibliothèque: http://sylvainmahe.xyz/data/module.zip
Cela retourne les valeurs en gauss (puisque le datasheet parle de gauss j'ai mi ça dans cette unité), à noter que 1 gauss = 100 micro tesla.

Voila pour l'instant (en presque 2 ans de travail en solo) tout ce qui est créé comme classes dans ma bibliothèque:
Code : Sélectionner tout
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
#include "../module/GpioRead.h"
#include "../module/GpioWrite.h"
#include "../module/AnalogRead.h"
#include "../module/InterruptRead.h"
#include "../module/PwmRead.h"
#include "../module/PwmWrite.h"
#include "../module/SoundWrite.h"

#include "../module/Timer.h"
#include "../module/Delay.h"

#include "../module/Math.h"
#include "../module/Iteration.h"
#include "../module/Average.h"
#include "../module/Hysteresis.h"
#include "../module/Random.h"

#include "../module/Max7219.h"
#include "../module/Mpu6050.h"
#include "../module/Bno055.h"
#include "../module/Hmc5883L.h"
#include "../module/Bmp180.h"
#include "../module/Nrf24L01P.h"

#include "../module/Network.h"

#include "../module/Memory.h"
#include "../module/Power.h"
#include "../module/Tool.h"
Vous pouvez faire beaucoup de projets avec ça et l'atmega328p-pu.
1  0 
Avatar de sylvainmahe
Membre régulier https://www.developpez.com
Le 16/07/2016 à 23:49


1  0 
Avatar de sylvainmahe
Membre régulier https://www.developpez.com
Le 23/08/2016 à 18:25
Bonjour theoldisgood, merci pour le commentaire.

Alors désolé pour les liens cassés, il doit y en avoir beaucoup car j'ai refait (ou fait le mot est plus juste vu ce que c'était avant) un nouveau site internet sous la forme d'un blog.

Du coup je copie colle le code source du quadri ici:
Code : Sélectionner tout
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
#include "../module/Delay.h"
#include "../module/Random.h"
#include "../module/Math.h"
#include "../module/Filter.h"
#include "../module/SoundWrite.h"
#include "../module/PwmWrite.h"
#include "../module/PwmRead.h"
#include "../module/Mpu6050.h"

int main()
{
	unsigned char n = 0;
	Delay delaySoundStartCondition = Delay (1000, false);
	Mpu6050 gyroscope = Mpu6050 (0x68);
	PwmRead channelThrottle = PwmRead (1, false);
	float slowChannelThrottle = 0;
	PwmRead channelPitch = PwmRead (2, false);
	PwmRead channelRoll = PwmRead (3, false);
	PwmRead channelYaw = PwmRead (4, false);
	PwmRead channelHold = PwmRead (5, false);
	float centerChannelHold = 0;
	PwmWrite motor1 = PwmWrite (8, 0, 0, 0);
	PwmWrite motor2 = PwmWrite (9, 0, 0, 0);
	PwmWrite motor3 = PwmWrite (10, 0, 0, 0);
	PwmWrite motor4 = PwmWrite (11, 0, 0, 0);
	float mixThrottle = 0;
	float mixThrustPitchGainSpeed = 0;
	Filter mixLockPitchGainSpeed = Filter (20);
	float mixThrustRollGainSpeed = 0;
	Filter mixLockRollGainSpeed = Filter (20);
	float mixInertiaYawGainSpeed = 0;
	Filter mixLockYawGainSpeed = Filter (100);
	float mixMinClearancePitch = 0;
	float mixMaxClearancePitch = 0;
	float mixMinClearanceRoll = 0;
	float mixMaxClearanceRoll = 0;
	float mixMinClearanceYaw = 0;
	float mixMaxClearanceYaw = 0;
	float mixPitchOffsetSpeed = 0;
	float mixRollOffsetSpeed = 0;
	float mixYawOffsetSpeed = 0;
	float thrustGainSpeedPitch = 0;
	float thrustGainSpeedRoll = 0;
	float inertiaGainSpeedYaw = 0;
	float gainMinRxSpeed = 0;
	float gainMaxRxSpeed = 0;
	float gainLockRxSpeed = 0;
	float gainMinRySpeed = 0;
	float gainMaxRySpeed = 0;
	float gainLockRySpeed = 0;
	float gainMinRzSpeed = 0;
	float gainMaxRzSpeed = 0;
	float gainLockRzSpeed = 0;
	float mixMinRxMotor = 0;
	float mixMaxRxMotor = 0;
	float mixMinRyMotor = 0;
	float mixMaxRyMotor = 0;
	float mixMinRzMotor = 0;
	float mixMaxRzMotor = 0;
	float mixMotor1 = 0;
	float mixMotor2 = 0;
	float mixMotor3 = 0;
	float mixMotor4 = 0;
	const unsigned int SETUP_MIN_CHANNEL_THROTTLE = 1000;
	const unsigned int SETUP_MAX_CHANNEL_THROTTLE = 2000;
	const unsigned int SETUP_MIN_CHANNEL_PITCH = 1000;
	const unsigned int SETUP_MAX_CHANNEL_PITCH = 2000;
	const unsigned int SETUP_MIN_CHANNEL_ROLL = 1000;
	const unsigned int SETUP_MAX_CHANNEL_ROLL = 2000;
	const unsigned int SETUP_MIN_CHANNEL_YAW = 1000;
	const unsigned int SETUP_MAX_CHANNEL_YAW = 2000;
	const unsigned int SETUP_MIN_CHANNEL_HOLD = 1000;
	const unsigned int SETUP_MAX_CHANNEL_HOLD = 2000;
	const unsigned int SETUP_FREQUENCY_ESC = 125;
	const unsigned int SETUP_HOLD_ESC = 950;
	const unsigned int SETUP_MIN_ESC = 1050;
	const unsigned int SETUP_MAX_ESC = 1950;
	const unsigned int SETUP_TRAVEL_PITCH = 250;
	const unsigned int SETUP_TRAVEL_ROLL = 250;
	const unsigned int SETUP_TRAVEL_YAW = 400;
	const signed int SETUP_SPEED_PITCH = 320;
	const signed int SETUP_SPEED_ROLL = 320;
	const signed int SETUP_SPEED_YAW = 320;
	const unsigned char SETUP_GAIN_SPEED_PITCH = 95;
	const unsigned char SETUP_GAIN_SPEED_ROLL = 93;
	const unsigned char SETUP_GAIN_SPEED_YAW = 96;
	const unsigned char SETUP_THRUST_PROPELLER = 80;
	const unsigned char SETUP_INERTIA_PROPELLER = 100;
	const unsigned char SETUP_LOCK = 60;
	
	SoundWrite::pin (13);
	
	PwmRead::start (100);
	
	while (channelThrottle.us == 0 || channelPitch.us == 0 || channelRoll.us == 0 || channelYaw.us == 0 || channelHold.us == 0)
	{
		channelThrottle.read();
		channelPitch.read();
		channelRoll.read();
		channelYaw.read();
		channelHold.read();
		
		delaySoundStartCondition.state();
		
		if (delaySoundStartCondition.update == true)
		{
			SoundWrite::key (200, 100);
			SoundWrite::key (0, 100);
			SoundWrite::key (200, 100);
			SoundWrite::playKey();
		}
	}
	
	slowChannelThrottle = float (SETUP_MIN_CHANNEL_THROTTLE) + ((float (SETUP_MAX_CHANNEL_THROTTLE) - float (SETUP_MIN_CHANNEL_THROTTLE)) / 10.0);
	centerChannelHold = Math::center (SETUP_MIN_CHANNEL_HOLD, SETUP_MAX_CHANNEL_HOLD);
	
	delaySoundStartCondition.reset();
	
	while (channelThrottle.us > slowChannelThrottle || channelHold.us < centerChannelHold)
	{
		channelThrottle.read();
		channelHold.read();
		
		delaySoundStartCondition.state();
		
		if (delaySoundStartCondition.update == true)
		{
			SoundWrite::key (200, 100);
			SoundWrite::key (0, 100);
			SoundWrite::key (200, 100);
			SoundWrite::key (0, 100);
			SoundWrite::key (200, 100);
			SoundWrite::playKey();
		}
	}
	
	thrustGainSpeedPitch = Math::curve (0, SETUP_THRUST_PROPELLER, 100, 0, SETUP_GAIN_SPEED_PITCH, 0);
	gainMinRxSpeed = Math::curve (0, thrustGainSpeedPitch, 100, 2000, 0, 0);
	gainMaxRxSpeed = Math::curve (0, SETUP_GAIN_SPEED_PITCH, 100, 2000, 0, 0);
	gainLockRxSpeed = Math::curve (0, SETUP_LOCK, 100, 1, 0, 0);
	
	thrustGainSpeedRoll = Math::curve (0, SETUP_THRUST_PROPELLER, 100, 0, SETUP_GAIN_SPEED_ROLL, 0);
	gainMinRySpeed = Math::curve (0, thrustGainSpeedRoll, 100, 2000, 0, 0);
	gainMaxRySpeed = Math::curve (0, SETUP_GAIN_SPEED_ROLL, 100, 2000, 0, 0);
	gainLockRySpeed = Math::curve (0, SETUP_LOCK, 100, 1, 0, 0);
	
	inertiaGainSpeedYaw = Math::curve (0, SETUP_INERTIA_PROPELLER, 100, 0, SETUP_GAIN_SPEED_YAW, 0);
	gainMinRzSpeed = Math::curve (0, inertiaGainSpeedYaw, 100, 2000, 0, 0);
	gainMaxRzSpeed = Math::curve (0, SETUP_GAIN_SPEED_YAW, 100, 2000, 0, 0);
	gainLockRzSpeed = Math::curve (0, SETUP_LOCK, 100, 1, 0, 0);
	
	motor1.hold (SETUP_HOLD_ESC);
	motor1.min (SETUP_MIN_ESC);
	motor1.max (SETUP_MAX_ESC);
	motor2.hold (SETUP_HOLD_ESC);
	motor2.min (SETUP_MIN_ESC);
	motor2.max (SETUP_MAX_ESC);
	motor3.hold (SETUP_HOLD_ESC);
	motor3.min (SETUP_MIN_ESC);
	motor3.max (SETUP_MAX_ESC);
	motor4.hold (SETUP_HOLD_ESC);
	motor4.min (SETUP_MIN_ESC);
	motor4.max (SETUP_MAX_ESC);
	
	PwmWrite::start (SETUP_FREQUENCY_ESC);
	
	motor1.moveHold();
	motor2.moveHold();
	motor3.moveHold();
	motor4.moveHold();
	
	Random::seed (15);
	
	for (n = 0; n < 16; n++)
	{
		if (n != 0)
		{
			SoundWrite::key (0, Random::integer (25, 75));
		}
		
		SoundWrite::key (Random::integer (70, 3000), Random::integer (25, 75));
	}
	
	SoundWrite::playKey();
	
	while (true)
	{
		channelThrottle.read();
		channelPitch.read();
		channelRoll.read();
		channelYaw.read();
		channelHold.read();
		
		if (channelHold.us > centerChannelHold)
		{
			motor1.moveHold();
			motor2.moveHold();
			motor3.moveHold();
			motor4.moveHold();
		}
		else
		{
			gyroscope.readRotation();
			
			mixThrottle = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, SETUP_MIN_ESC, SETUP_MAX_ESC, 0);
			
			mixMotor1 = mixThrottle;
			mixMotor2 = mixThrottle;
			mixMotor3 = mixThrottle;
			mixMotor4 = mixThrottle;
			
			mixMinClearancePitch = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, 0, SETUP_TRAVEL_PITCH, 0);
			mixMaxClearancePitch = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, SETUP_TRAVEL_PITCH, 0, 0);
			mixPitchOffsetSpeed = Math::curve (SETUP_MIN_CHANNEL_PITCH, channelPitch.us, SETUP_MAX_CHANNEL_PITCH, -SETUP_SPEED_PITCH, SETUP_SPEED_PITCH, 0);
			mixThrustPitchGainSpeed = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, gainMaxRxSpeed, gainMinRxSpeed, 0);
			mixLockPitchGainSpeed.set (Math::wurve (SETUP_MIN_CHANNEL_PITCH, channelPitch.us, SETUP_MAX_CHANNEL_PITCH, gainLockRxSpeed, 1, gainLockRxSpeed, 0, 0));
			mixThrustPitchGainSpeed *= mixLockPitchGainSpeed.value;
			mixMinRxMotor = Math::wurve (-mixThrustPitchGainSpeed, gyroscope.rx + mixPitchOffsetSpeed, mixThrustPitchGainSpeed, -mixMaxClearancePitch, 0, mixMinClearancePitch, 0, 0);
			mixMaxRxMotor = Math::wurve (-mixThrustPitchGainSpeed, gyroscope.rx + mixPitchOffsetSpeed, mixThrustPitchGainSpeed, -mixMinClearancePitch, 0, mixMaxClearancePitch, 0, 0);
			
			mixMotor1 -= mixMinRxMotor;
			mixMotor2 -= mixMinRxMotor;
			mixMotor3 += mixMaxRxMotor;
			mixMotor4 += mixMaxRxMotor;
			
			mixMinClearanceRoll = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, 0, SETUP_TRAVEL_ROLL, 0);
			mixMaxClearanceRoll = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, SETUP_TRAVEL_ROLL, 0, 0);
			mixRollOffsetSpeed = Math::curve (SETUP_MIN_CHANNEL_ROLL, channelRoll.us, SETUP_MAX_CHANNEL_ROLL, -SETUP_SPEED_ROLL, SETUP_SPEED_ROLL, 0);
			mixThrustRollGainSpeed = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, gainMaxRySpeed, gainMinRySpeed, 0);
			mixLockRollGainSpeed.set (Math::wurve (SETUP_MIN_CHANNEL_ROLL, channelRoll.us, SETUP_MAX_CHANNEL_ROLL, gainLockRySpeed, 1, gainLockRySpeed, 0, 0));
			mixThrustRollGainSpeed *= mixLockRollGainSpeed.value;
			mixMinRyMotor = Math::wurve (-mixThrustRollGainSpeed, gyroscope.ry - mixRollOffsetSpeed, mixThrustRollGainSpeed, -mixMaxClearanceRoll, 0, mixMinClearanceRoll, 0, 0);
			mixMaxRyMotor = Math::wurve (-mixThrustRollGainSpeed, gyroscope.ry - mixRollOffsetSpeed, mixThrustRollGainSpeed, -mixMinClearanceRoll, 0, mixMaxClearanceRoll, 0, 0);
			
			mixMotor1 -= mixMinRyMotor;
			mixMotor2 += mixMaxRyMotor;
			mixMotor3 -= mixMinRyMotor;
			mixMotor4 += mixMaxRyMotor;
			
			mixMinClearanceYaw = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, 0, SETUP_TRAVEL_YAW, 0);
			mixMaxClearanceYaw = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, SETUP_TRAVEL_YAW, 0, 0);
			mixYawOffsetSpeed = Math::curve (SETUP_MIN_CHANNEL_YAW, channelYaw.us, SETUP_MAX_CHANNEL_YAW, -SETUP_SPEED_YAW, SETUP_SPEED_YAW, 0);
			mixInertiaYawGainSpeed = Math::curve (SETUP_MIN_CHANNEL_THROTTLE, channelThrottle.us, SETUP_MAX_CHANNEL_THROTTLE, gainMaxRzSpeed, gainMinRzSpeed, 0);
			mixLockYawGainSpeed.set (Math::wurve (SETUP_MIN_CHANNEL_YAW, channelYaw.us, SETUP_MAX_CHANNEL_YAW, gainLockRzSpeed, 1, gainLockRzSpeed, 0, 0));
			mixInertiaYawGainSpeed *= mixLockYawGainSpeed.value;
			mixMinRzMotor = Math::wurve (-mixInertiaYawGainSpeed, gyroscope.rz + mixYawOffsetSpeed, mixInertiaYawGainSpeed, -mixMaxClearanceYaw, 0, mixMinClearanceYaw, 0, 0);
			mixMaxRzMotor = Math::wurve (-mixInertiaYawGainSpeed, gyroscope.rz + mixYawOffsetSpeed, mixInertiaYawGainSpeed, -mixMinClearanceYaw, 0, mixMaxClearanceYaw, 0, 0);
			
			mixMotor1 -= mixMinRzMotor;
			mixMotor2 += mixMaxRzMotor;
			mixMotor3 += mixMaxRzMotor;
			mixMotor4 -= mixMinRzMotor;
			
			motor1.us (Math::round (mixMotor1));
			motor2.us (Math::round (mixMotor2));
			motor3.us (Math::round (mixMotor3));
			motor4.us (Math::round (mixMotor4));
		}
	}
	
	return 0;
}
Les paramètres (SETUP) sont réglés pour mon quadri 400x400mm, moteur mn2206, hélices 6 pouces.

Normalement si j'ai le temps, prochainement sur mon blog je devrais faire un article sur le quadri, en gros à la suite du dernier article: http://sylvainmahe.xyz/

N'hésites pas si tu as des questions
1  0 
Avatar de prgasp77
Membre émérite https://www.developpez.com
Le 09/09/2015 à 10:11
Merci pour ce partage d'information. N'hésite pas à faire un tour dans le forum systèmes embarqués, tu feras des heureux .
0  0 
Avatar de sylvainmahe
Membre régulier https://www.developpez.com
Le 09/09/2015 à 12:12
Ok ca marche Tu penses que je peux laisser le lien de ce topic sur le forum des systèmes embarqués?
0  0