Heureusement qu'il y a des retraités névrosés.
Super, le déambulateur . . .
Posté par Oracid - 31 août 2023 - 01:28
Cliquez moi.
Voici une nouvelle version de 8DOF-Q6 qui se caractérise par une diminution de la longueur du fémur et du tibia qui s'établit à 168mm, contre 184mm précédemment.
J'ai également modifié la structure des pattes. Et j'en ai profité par lui donner une livrée blanche qui, je trouve, lui donne un coté sympathique.
Il s'est légèrement empatté, à 1650g.
J'ai limité sa vitesse à 7 secondes les 10m, pour garder un minimum de stabilité. De ce coté, c'est beaucoup mieux, mais c'est loin d'être satisfaisant.
Posté par Oracid - 26 août 2023 - 10:21
Cliquez moi.
Voici la dernière version de mon banc de test pour mesurer le couple des servos.
Ici, on peut voir le GeekServo Gris en action avec une course perpétuelle de 0° à 180° qui soulève un panier dans lequel, je mets des écrous.
Le bras est une barre Lego de 13L. Soit un entraxe de 8mm x 12 = 96mm (environ 10cm . . .)
N'hésiter pas à me faire part de vos remarques.
Voici le résultat des deux servos que j'ai testé ce matin :
- le GeekServo gris, 283g.
- le SPT 2065W, 162g
Il n'y a pas photo !
Posté par Oracid - 24 août 2023 - 03:35
Cliquez moi.
Voici mon dernier né.
Ce n'est pas un grand quadrupède comme 8DOF-Q5, https://www.robot-ma...upede/?p=118867, mais un quadrupède de taille moyenne.
Sa voie est de 170mm, et l'écartement des pattes, avants et arrières, est de 290mm, contre 210mm et 380mm précédemment.
Les longueurs du fémur et le tibia sont de 184mm, contre 200mm.
La hauteur du garrot est identique à 355mm.
Tout cela donne une allure beaucoup plus ramassée et une impression de puissance.
Le rapport longueur/largeur est empirique, et est le résultat du choix des pièces Lego, en particulier les trois grands cadres qui donnent la longueur et la largeur du châssis.
J'ai fait un petit test à faible vitesse. Avec sa petite largeur et ses pattes très hautes, il se comporte plutôt bien et ne se renverse pas, ce qui est l'objectif principal de ce nouveau quadrupède.
Posté par Oracid - 24 août 2023 - 12:57
J'ai un servo qui est beaucoup moins réactif que les autres . Là il y a possibilité de faire quelque chose ?
Je ne crois pas, désolé, mais ouvre le pour apprécier le montage interne.
Tu sais, j'ai beaucoup de servos hors d'usage, bien venu au club.
Posté par Oracid - 11 août 2023 - 06:01
Malheureusement, l'extrémité du fémur se casse au passage de l'axe de la patte.
Cela est critique pour la poursuite du projet.
Patrick a démontré la faisabilité d'un grand quadrupède avec des servos RC. C'est cela le plus important.
J'ai voulu relever le défi en proposant une alternative en Lego. La vitesse de 10m en 5 secondes est atteinte, c'était mon objectif.
Malheureusement mon quadrupède n'est pas stable et je suis obligé de le maintenir dans sa trajectoire en courant après lui.
Je ne vais pas m'acharner.
Demain, je pars à la mer avec toute la famille. C'est bien ça, le plus important.
Posté par Oracid - 09 août 2023 - 06:23
Voici mon nouveau châssis. Il est basé sur deux longerons tubulaires à section ovale. Cette nouvelle structure est très rigide.
De plus, j'ai collé une fixation d'axe à l'arrière des servos. Cela renforce et équilibre énormément la structure de la patte.
Evidemment, on a rien sans rien, le poids est passé à 2kg.
J'ai testé à faible vitesse, ce n'est pas trop mal, mais pas miraculeux. Peut-être que je vais être obligé de baisser le garrot.
Un truc dingue, je viens de réaliser que ma terrasse est inclinée pour l'écoulement des eaux de pluie. J'avais oublié, ce détail !
Un centimètre par mètre, ce n'est pas beaucoup, mais suffisant pour tomber, à grande vitesse.
Posté par Oracid - 06 août 2023 - 01:52
Bingo !
10 mètres en 5 secondes.
Sur les conseilles de Patrick, j'ai fait une version du programme où les calculs sont effectués en avance dans la fonction setup().
Puis dans le loop(), une moulinette lit les tableaux où sont ranger les valeurs des positions, en microsecondes.
J'avais déjà fait cela en deux programmes séparés, alors qu'ici, tout est regrouper dans le même programme.
Je n'y croyais pas beaucoup, mais les précédentes versions avaient été utilisées sur des quadrupèdes beaucoup moins rapides. Le gain était nul.
Aujourd'hui, à cette vitesse, le gain est perceptible, mais j'utilise un Arduino Nano. Avec un Pico, par exemple, je pense qu'il n'y aurait pas de différence.
Je n'ai pas réussi à rentrer dans le code de Patrick. J'ai toujours eu du mal à lire le code de quelqu'un d'autre.
Voilà, l'objectif est atteint, j'ai fait 3 essais. Le problème, c'est que je ne vais pas faire une vidéo, avec moi, à califourchon sur le quadrupède, pour éviter qu'il tombe.
J'ai déjà fait un nouveau châssis. Mon objectif maintenant est qu'il fasse ce record, seul.
Les paramètres : delayMicroseconds(2050), foulée = 200mm, longueur itération = 15mm.
Le code. J'ai mis tous les print en commentaire. Ce code peut être exécuté, même sans quadrupède, mais il faut un bouton sur A0 et décommenter les print.
// based on 8DOF-Q5-Bis-V3 - 01/08/2023 - void(* resetFunc) (void) = 0; // soft reset function #include <Servo.h> // Servo library int Speed=2050; // delay between 2 orders int LS_A, RS_A, pb=A0, st; // Left and Right Servo Angle, stop button, start time const int Ax=100, Bx=-100, Y=15, lg_Itr=15, F_tr=0, B_tr=-50; // Ax Bx Y rectangle coordinates, iteration length , front and back translation const int nb=8; // number of servos Servo Srv[nb]; // Servos table int Smin[nb]={ 550, 500, 540, 500, 500, 590, 510, 510}; // all servos values for 0° int Smax[nb]={2650,2560,2550,2500,2500,2520,2550,2600}; // all servos values for 180° int OnOff[nb]={1,1,1,1,1,1,1,1}; // on/off Servos table int FRLS=0, FRRS=1, FLLS=2, FLRS=3, BRLS=4, BRRS=5, BLLS=6, BLRS=7; //servos FRLS FRRS FLLS FLRS BRLS BRRS BLLS BLRS // you must modify these values according to your servos int Err[nb]={ -2, -2, -2, -4, -2, 1, 0, -2 }; // 90° correction error const int lgTab=((Ax-Bx)*2/lg_Itr)+2; int FRL[lgTab], FRR[lgTab], FLL[lgTab], FLR[lgTab], BRL[lgTab], BRR[lgTab], BLL[lgTab], BLR[lgTab]; // Angles tables void setup() { delay(400); // for reset consideration Serial.begin(9600); Serial.print("\n\n\n\t REFRESH_INTERVAL="); Serial.print(REFRESH_INTERVAL); //Serial.print("\n\t lgTab="); Serial.print(lgTab); pinMode(pb,INPUT_PULLUP); // start/stop/reset button attachment Init_Tabs_Angles(); int a=65; // Servos angle initialization if(OnOff[FRLS]) { Srv[FRLS].attach( 2,Smin[FRLS],Smax[FRLS]); Srv[FRLS].writeMicroseconds(map( a+Err[FRLS],0,180,Smin[FRLS],Smax[FRLS])); } // FR Front Right leg - LS Left Servo if(OnOff[FRRS]) { Srv[FRRS].attach( 3,Smin[FRRS],Smax[FRRS]); Srv[FRRS].writeMicroseconds(map(180-a+Err[FRRS],0,180,Smin[FRRS],Smax[FRRS])); } // FR Front Right leg - RS Right Servo if(OnOff[FLLS]) { Srv[FLLS].attach( 4,Smin[FLLS],Smax[FLLS]); Srv[FLLS].writeMicroseconds(map( a+Err[FLLS],0,180,Smin[FLLS],Smax[FLLS])); } // FL Front Left leg - LS Left Servo if(OnOff[FLRS]) { Srv[FLRS].attach( 5,Smin[FLRS],Smax[FLRS]); Srv[FLRS].writeMicroseconds(map(180-a+Err[FLRS],0,180,Smin[FLRS],Smax[FLRS])); } // FL Front Left leg - RS Right Servo if(OnOff[BRLS]) { Srv[BRLS].attach(10,Smin[BRLS],Smax[BRLS]); Srv[BRLS].writeMicroseconds(map( a+Err[BRLS],0,180,Smin[BRLS],Smax[BRLS])); } // BR Back Right leg - LS Left Servo if(OnOff[BRRS]) { Srv[BRRS].attach(11,Smin[BRRS],Smax[BRRS]); Srv[BRRS].writeMicroseconds(map(180-a+Err[BRRS],0,180,Smin[BRRS],Smax[BRRS])); } // BR Back Right leg - RS Right Servo if(OnOff[BLLS]) { Srv[BLLS].attach(12,Smin[BLLS],Smax[BLLS]); Srv[BLLS].writeMicroseconds(map( a+Err[BLLS],0,180,Smin[BLLS],Smax[BLLS])); } // BL Back Left leg - LS Left Servo if(OnOff[BLRS]) { Srv[BLRS].attach(13,Smin[BLRS],Smax[BLRS]); Srv[BLRS].writeMicroseconds(map(180-a+Err[BLRS],0,180,Smin[BLRS],Smax[BLRS])); } // BL Back Left leg - RS Right Servo Serial.print("\n\t To start, click on the Start button"); while( digitalRead(pb) ); delay(400); Serial.print("\n\t Started"); st=millis(); } void loop() { if( millis()-st >= 5000) resetFunc(); Walk(); } void Init_Tabs_Angles(){ int i; i=0; //Serial.print("\n\t Init_Tabs_Angles - Front right paw"); // Front right paw for( int p=Ax;p>=Bx;p=p-lg_Itr ){ IK(+p+F_tr,-Y,FRLS,FRRS); FRL[i]=LS_A; FRR[i]=RS_A; //Serial.print("\n\t p="); Serial.print(p);Serial.print("\t i="); Serial.print(i); //Serial.print("\t FRL[i]="); Serial.print(FRL[i]); Serial.print("\t FRR[i]="); Serial.print(FRR[i]); i++; } for( int p=Bx;p<=Ax;p=p+lg_Itr ){ IK(+p+F_tr,+Y,FRLS,FRRS); FRL[i]=LS_A; FRR[i]=RS_A; //Serial.print("\n\t p="); Serial.print(p);Serial.print("\t i="); Serial.print(i); //Serial.print("\t FRL[i]="); Serial.print(FRL[i]); Serial.print("\t FRR[i]="); Serial.print(FRR[i]); i++; } i=0; //Serial.print("\n\t Init_Tabs_Angles Front left paw"); // Front left paw for( int p=Ax;p>=Bx;p=p-lg_Itr ){ IK(+p-F_tr,+Y,FLLS,FLRS); FLL[i]=LS_A; FLR[i]=RS_A; //Serial.print("\n\t p="); Serial.print(p);Serial.print("\t i="); Serial.print(i); //Serial.print("\t FLL[i]="); Serial.print(FLL[i]); Serial.print("\t FLR[i]="); Serial.print(FLR[i]); i++; } for( int p=Bx;p<=Ax;p=p+lg_Itr ){ IK(+p-F_tr,-Y,FLLS,FLRS); FLL[i]=LS_A; FLR[i]=RS_A; //Serial.print("\n\t p="); Serial.print(p);Serial.print("\t i="); Serial.print(i); //Serial.print("\t FLL[i]="); Serial.print(FLL[i]); Serial.print("\t FLR[i]="); Serial.print(FLR[i]); i++; } i=0; //Serial.print("\n\t Init_Tabs_Angles Back right paw"); // Back right paw for( int p=Ax;p>=Bx;p=p-lg_Itr ){ IK(-p+B_tr,+Y,BLLS,BLRS); BRL[i]=LS_A; BRR[i]=RS_A; //Serial.print("\n\t p="); Serial.print(p);Serial.print("\t i="); Serial.print(i); //Serial.print("\t BRL[i]="); Serial.print(BRL[i]); Serial.print("\t BRR[i]="); Serial.print(BRR[i]); i++; } for( int p=Bx;p<=Ax;p=p+lg_Itr ){ IK(-p+B_tr,-Y,BLLS,BLRS); BRL[i]=LS_A; BRR[i]=RS_A; //Serial.print("\n\t p="); Serial.print(p);Serial.print("\t i="); Serial.print(i); //Serial.print("\t BRL[i]="); Serial.print(BRL[i]); Serial.print("\t BRR[i]="); Serial.print(BRR[i]); i++; } i=0; //Serial.print("\n\t Init_Tabs_Angles Back left paw"); // Back left paw for( int p=Ax;p>=Bx;p=p-lg_Itr ){ IK(-p-B_tr,-Y,BRLS,BRRS); BLL[i]=LS_A; BLR[i]=RS_A; //Serial.print("\n\t p="); Serial.print(p);Serial.print("\t i="); Serial.print(i); //Serial.print("\t BLL[i]="); Serial.print(BLL[i]); Serial.print("\t BLR[i]="); Serial.print(BLR[i]); i++; } for( int p=Bx;p<=Ax;p=p+lg_Itr ){ IK(-p-B_tr,+Y,BRLS,BRRS); BLL[i]=LS_A; BLR[i]=RS_A; //Serial.print("\n\t p="); Serial.print(p);Serial.print("\t i="); Serial.print(i); //Serial.print("\t BLL[i]="); Serial.print(BLL[i]); Serial.print("\t BLR[i]="); Serial.print(BLR[i]); i++; } } void Walk(){ for( int i=0;i<=lgTab-1;i++){ if (! digitalRead(pb)) resetFunc(); if (OnOff[FRLS]) Srv[FRLS].writeMicroseconds(FRL[i]); // Front right paw, left servo if (OnOff[FRRS]) Srv[FRRS].writeMicroseconds(FRR[i]); // Front right paw, right servo delayMicroseconds(Speed); //Serial.print("\n\t Walk Front Right");Serial.print("\t i=");Serial.print(i); //Serial.print("\t FRL="); Serial.print(FRL[i]);Serial.print("\t FRR="); Serial.print(FRR[i]); if (OnOff[BLLS]) Srv[BLLS].writeMicroseconds(BLL[i]); // Back left paw, left servo if (OnOff[BLRS]) Srv[BLRS].writeMicroseconds(BLR[i]); // Back left paw, right servo delayMicroseconds(Speed); //Serial.print("\n\t Walk Back Left");Serial.print("\t i=");Serial.print(i); //Serial.print("\t BLL="); Serial.print(BLL[i]);Serial.print("\t BLR="); Serial.print(BLR[i]); if (OnOff[FLLS]) Srv[FLLS].writeMicroseconds(FLL[i]); // Front left paw, left servo if (OnOff[FLRS]) Srv[FLRS].writeMicroseconds(FLR[i]); // Front left paw, right servo delayMicroseconds(Speed); //Serial.print("\n\t Walk Front left");Serial.print("\t i=");Serial.print(i); //Serial.print("\t FLL="); Serial.print(FLL[i]);Serial.print("\t FLR="); Serial.print(FLR[i]); if (OnOff[BRLS]) Srv[BRLS].writeMicroseconds(BRL[i]); // Back right paw, left servo if (OnOff[BRRS]) Srv[BRRS].writeMicroseconds(BRR[i]); // Back right paw, right servo delayMicroseconds(Speed); //Serial.print("\n\t Walk Back right paw");Serial.print("\t i=");Serial.print(i); //Serial.print("\t BRL="); Serial.print(BRL[i]);Serial.print("\t BRR="); Serial.print(BRR[i]); } } void IK(int Px, int Py, int LS, int RS){ // Inverse Kinematics function if (! digitalRead(pb)) resetFunc(); float Ax=0, Ay=355, c=200; // position of the main paw axis and length of femur and tibia float d=Ay-Py, e=Ax-Px; // d and e, sides of rectangle triangle float h=sqrt((d*d)+(e*e)); // h, hypotenuse of rectangle triangle float B=asin(d/h); if(e<0)B=(PI-B); // B is the top angle of the rectangle triangle float A=acos(h/(2*c)); // A is the Diamond half top angle (cosin law) LS_A=round(degrees(B-A))+Err[LS]; // LS_A is the left servo angle in degrees +Err RS_A=round(degrees(B+A))+Err[RS]; // RS_A is the right servo angle in degrees +Err //DEBUG // Serial.print("\n\t Px="); Serial.print(Px);Serial.print(" Py=");Serial.print(Py);Serial.print("\t\tLeg servos : LS=");Serial.print(LS);Serial.print(" RS=");Serial.print(RS); // Serial.print("\n\t Inverse Kinematics values : B°= ");Serial.print(round(degrees(B)));Serial.print(" A°= ");Serial.print(round(degrees(A))); // Serial.print("\n\t Servo angles results : LS_A= ");Serial.print(LS_A);Serial.print("°\t\tRS_A= ");Serial.print(RS_A);Serial.print("°"); // - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - if (h>(c+c)){Serial.print("\n\t Target : Px=");Serial.print(Px);Serial.print(" Py=");Serial.print(Py);Serial.print("\t h=");Serial.print(h);Serial.print(" > ");Serial.print(c+c);Serial.print(" is too long !!!!!");return;} if (LS_A<0) {Serial.print("\n\t Target : Px=");Serial.print(Px);Serial.print(" Py=");Serial.print(Py);Serial.print("\t LS=");Serial.print(LS);Serial.print("\t angle LS_A=");Serial.print(LS_A);Serial.print(" <0° is not reachable !!!!!");return;} if (RS_A>180) {Serial.print("\n\t Target : Px=");Serial.print(Px);Serial.print(" Py=");Serial.print(Py);Serial.print("\t RS=");Serial.print(RS);Serial.print("\t angle RS_A=");Serial.print(RS_A);Serial.print(" >180° is not reachable !!!!!");return;} // - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - RESTRICTED AREA CONTROL - LS_A=map(LS_A,0,180,Smin[LS],Smax[LS]); RS_A=map(RS_A,0,180,Smin[RS],Smax[RS]); }
Posté par Oracid - 06 août 2023 - 06:26
Avec ton "robot semeur", tu as déjà pas mal exploré le terrain . . . https://www.robot-ma...glais/?p=109098
Penses tu qu'avec ta caméra, tu pourrais faire de la reconnaissante de plantes ?
Posté par Oracid - 04 août 2023 - 06:31
Ici, il ne s'agit pas d'un projet industriel, mais d'un défi personnel.
Je me revois, il y a quelque années maintenant, à me lancer dans la réalisation d'un quadrupède. Quel était l'intérêt ?
Franchement, je ne pense pas qu'il y ait beaucoup d'intérêt à faire un quadrupède. A part, militaire, et encore, j'ai un gros doute, par rapport à du matériel roulant.
Rien que de réussir à faire marcher ou courir, un quadrupède, sans rien faire d'autre, c'est déjà énorme.
Ce projet, réalisé avec un roulant, serait déjà une très belle réussite.
Le faire avec un multi pattes, c'est très tentant, mais rien que d'imaginer la force qu'il faut pour tourner un tire bouchon (voir plus haut) et on comprend tout de suite que c'est le robot qui va tourner, pas le tire bouchon.
Oui, je pense qu'il faudra revoir l'ambition du projet, à la baisse. C'est souvent comme ça en robotique.
Retirer les mauvaise herbes sur un stade avec un roulant, cela est déjà un projet très ambitieux.
Quoique, avec un drone . . .
Posté par Oracid - 04 août 2023 - 07:22
J'ai moi-même un jardin et comme pmdd, je viens rarement à bout de l'arrachage d'une mauvaise herbe.
Peu importe, plusieurs chemins mènent à la robotique, mais à mon avis, tu dois avoir conscience que ton projet se situe en haut de l'échelle de la complexité.
- alors non, je ne pense pas qu'un roulant consomme plus qu'un multi pattes, bien au contraire. Un roulant nécessite 2 moteurs, alors que pour un multi pattes, c'est de 2 à 12 moteurs, en fonction de la complexité.
- le multi pattes aura de grosses difficultés à franchir le moindre obstacle, alors que le roulant pourra facilement monter une pente à 30° ou escalader des petites pierres.
- non, je ne pense pas qu'un roulant ait besoin d'une route, mais tout est une question de taille.
- le choix de l'échelle, la taille, est très importante. Un robot de moins de 15cm de coté, quel qu'il soit, va poser de gros problèmes de miniaturisation. Alors qu'à partir de 15cm, les solutions existent et pour un poids qui n'aura que peu d'incidence sur la végétation alentour.
- je pense que pour pouvoir choisir, il faut avoir la connaissance. Ton projet ne sera pas une belle ligne droite. Peut-être, devras tu faire un roulant, puis un multi pattes, puis peut-être un drone . . .
- il est préférable de commencer doucement, sinon ton projet va s'étirer sur de longs mois, voir des années, et tu te lasseras. Parfois, on se lasse, même d'un projet qui avance et fonctionne bien.
Voici plusieurs exemples de robot "simple" qui pourraient t'inspirer :
https://www.robot-ma...ipede/?p=118960
https://www.robot-ma...os-v3/?p=116276
https://www.robot-ma...-nano/?p=115109
https://www.robot-ma...ylens/?p=115145
https://www.robot-ma...ylens/?p=115607
Posté par Oracid - 03 août 2023 - 08:17
C'est un projet un peu fou ! Fonce !
Je ne suis pas certain qu'un robot multi pattes soit plus adapté qu'un petit robot roulant.
J'ai fait quelques quadrupèdes, mais jamais de la taille du lien du scorpion.
Attention, l'araignée est grosse, très grosse.
Pour l'argent, je te conseille de faire un budget mensuel et de t'y tenir . . .
Bon courage.
Posté par Oracid - 31 juillet 2023 - 06:45
Pour mon anniversaire, 70 ans, le Père-Noel m'a apporté ça.
Sympa, le Père-Noel . . .
https://www.studiosp...a24750.html#top
Cela va me donner du blé à moudre pour la rentrée.
Posté par Oracid - 27 juillet 2023 - 09:41
J'ai mis REFRESH_INTERVAL 10000 , dans Servo.h
J'ai recompilé mon programme en prenant soin, préalablement, de relancer l'IDE. Comme je l'ai lu, je ne sais plus où.
Résultat, 9,85m en 5,5 secondes
Puis j'ai mis REFRESH_INTERVAL 5000 , c'était beaucoup plus rapide et un palonnier s'est cassé.
Je vais faire un nouveau palonnier, mais il faut que la colle sèche bien, soit 24h d'attente.
La suite à demain, donc.
Merci Patrick.