[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
Forum Multirotors et Drones
MikroKopter de kio
Merci de vous connecter ou de vous inscrire.

Connexion avec identifiant, mot de passe et durée de la session

Auteur Sujet: [TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R  (Lu 14059 fois)

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon

Si vous avez suivi le sujet Zaggotelemetry

Le principe est presque le même sauf que la on va décoder le CAN-BUS du Naza

L'avantage est de récupérer beaucoup plus d'information ...
pour n'en citer que quelque un :
Pitch, Roll, Mode de vol, tension Lipo, latitude, longitude, Gps altitude, altitude baro, cog, vitess, vsi,fix gps, nb sat, cap ...


Le schéma est assez simple

CAN-BUS NAZA -> conversion des signaux can -> serie -> Microcontroleur Teensy 3.1 -> S-port Frsky

Voilà a quoi ça ressemble une fois fini :




Coté matériel il faut :

1 Teensy 3.1 moins de 20 Euros



1 Convertiseur CAN / serie moins de 1 Euro




Il faudra le raccourcir un peut pour obtenir quelque chose d'encore plus compact








quelques morceaux de fil et connecteur que vous avez tous dans vos tiroir :)



Coté code j'ai réunis et modifier des morceaux existant sur le Rcgroup

une partie du nazadécodeur de Pawelsky http://www.rcgroups.com/forums/showthread.php?t=1995704

et une partie du code mavlink -> frsky  faite par Rolf Blomgren http://diydrones.com/forum/topics/amp-to-frsky-x8r-sport-converter?id=705844:Topic:1539556&page=1#comments


La partie de code que j'ai écrit et modifié est ici :

http://f8byc1.free.fr/taranis/naza-frsky/Naza-FrSky-V2.zip



Naza-FrSky.ino et FrSkySPort.ino
/*
  DJI Naza (v1/V2 + PMU) CAN data decoder library example
  Outputs data to a serial port
  (c) Pawelsky 20140921
  Not for commercial use

  Requires FlexCan library v0.1-beta (or newer if compatible)
  [url]https://github.com/teachop/FlexCAN_Library/releases/tag/v0.1-beta[/url]

  Requires NazaCanDecoder library by Pawelsky
  http://www.rcgroups.com/forums/showpost.php?p=27129264&postcount=1

  Requires Teensy 3.1 board and CAN transceiver
  Complie with "CPU speed" set to "96MHz (overclock)"
  Refer to naza_can_decoder_wiring.jpg diagram for proper connection
  Connections can be greatly simplified using CAN bus and MicroSD shields by Pawelsky
  (see teensy_shields.jpg for installation and naza_can_decoder_wiring_shields.jpg for wiring)
*/

#include "NazaCanDecoderLib.h"
#include "FlexCAN.h"
#include "FrSkySPort.h"

// Use Serial to output data via USB or Serial1 to use Teensy's first serial port
#define SERIAL_PORT Serial

uint32_t currTime, attiTime, otherTime, clockTime;
char dateTime[20];
uint32_t messageId;

int led = 13;




void setup()
{
  pinMode(led, OUTPUT);
  SERIAL_PORT.begin(115200);
  FrSkySPort_Init();
  NazaCanDecoder.begin();
}

void loop()
{
  messageId = NazaCanDecoder.decode();
//  if(messageId) { SERIAL_PORT.print("Message "); SERIAL_PORT.print(messageId, HEX); SERIAL_PORT.println(" decoded"); }

  currTime = millis();

  // Display attitude at 10Hz rate so every 100 milliseconds
  if(attiTime < currTime)
  {
    attiTime = currTime + 100;
    SERIAL_PORT.print("Pitch: "); SERIAL_PORT.print(NazaCanDecoder.getPitch());
    SERIAL_PORT.print(", Roll: "); SERIAL_PORT.println(NazaCanDecoder.getRoll());
  }

  // Display other data at 5Hz rate so every 200 milliseconds
  if(otherTime < currTime)
  {
    otherTime = currTime + 200;
    SERIAL_PORT.print("Mode: ");
    switch (NazaCanDecoder.getMode())
    {
      case NazaCanDecoderLib::MANUAL:   SERIAL_PORT.print("MAN"); break;
      case NazaCanDecoderLib::GPS:      SERIAL_PORT.print("GPS"); break;
      case NazaCanDecoderLib::FAILSAFE: SERIAL_PORT.print("FS");  break;
      case NazaCanDecoderLib::ATTI:     SERIAL_PORT.print("ATT"); break;
      default:                          SERIAL_PORT.print("UNK");
    }
    SERIAL_PORT.print(", Bat: "); SERIAL_PORT.println(NazaCanDecoder.getBattery() / 1000.0, 2);

    SERIAL_PORT.print("Lat: "); SERIAL_PORT.print(NazaCanDecoder.getLat(), 7);
    SERIAL_PORT.print(", Lon: "); SERIAL_PORT.print(NazaCanDecoder.getLon(), 7);
    SERIAL_PORT.print(", GPS alt: "); SERIAL_PORT.print(NazaCanDecoder.getGpsAlt());
    SERIAL_PORT.print(", COG: "); SERIAL_PORT.print(NazaCanDecoder.getCog());
    SERIAL_PORT.print(", Speed: "); SERIAL_PORT.print(NazaCanDecoder.getSpeed());
    SERIAL_PORT.print(", VSI: "); SERIAL_PORT.print(NazaCanDecoder.getVsi());
    SERIAL_PORT.print(", Fix: ");
    switch (NazaCanDecoder.getFixType())
    {
      case NazaCanDecoderLib::NO_FIX:   SERIAL_PORT.print("No fix"); break;
      case NazaCanDecoderLib::FIX_2D:   SERIAL_PORT.print("2D");     break;
      case NazaCanDecoderLib::FIX_3D:   SERIAL_PORT.print("3D");     break;
      case NazaCanDecoderLib::FIX_DGPS: SERIAL_PORT.print("DGPS");   break;
      default:                          SERIAL_PORT.print("UNK");
    }
    SERIAL_PORT.print(", Sat: "); SERIAL_PORT.println(NazaCanDecoder.getNumSat());

    SERIAL_PORT.print("Alt: "); SERIAL_PORT.print(NazaCanDecoder.getAlt());
    SERIAL_PORT.print(", Heading: "); SERIAL_PORT.println(NazaCanDecoder.getHeading());
  }

  // Display date/time at 1Hz rate so every 1000 milliseconds
  if(clockTime < currTime)
  {
   
   
    clockTime = currTime + 1000;
    sprintf(dateTime, "%4u.%02u.%02u %02u:%02u:%02u",
            NazaCanDecoder.getYear() + 2000, NazaCanDecoder.getMonth(), NazaCanDecoder.getDay(),
            NazaCanDecoder.getHour(), NazaCanDecoder.getMinute(), NazaCanDecoder.getSecond());
    SERIAL_PORT.print("Date/Time: "); SERIAL_PORT.println(dateTime);
   
   

   
   
  }

  NazaCanDecoder.heartbeat();
 
      FrSkySPort_Process();
 
}
#include "FrSkySPort.h"

#define _FrSkySPort_Serial            Serial1
#define _FrSkySPort_C1                UART0_C1
#define _FrSkySPort_C3                UART0_C3
#define _FrSkySPort_S2                UART0_S2
#define _FrSkySPort_BAUD           57600
#define   MAX_ID_COUNT              19

short crc;                         // used for crc calc of frsky-packet
uint8_t lastRx;
uint32_t FR_ID_count = 0;
uint8_t cell_count = 0;
uint8_t latlong_flag = 0;
uint32_t latlong = 0;
uint8_t first=0;

// POUR TEST
int32_t    ap_latitude = 0;              // 585522540;
int32_t    ap_longitude = 0;            // 162344467;
int32_t    ap_gps_altitude = 0;        // 1000 = 1m


// ***********************************************************************
void FrSkySPort_Init(void)  {
      _FrSkySPort_Serial.begin(_FrSkySPort_BAUD);
      _FrSkySPort_C3 = 0x10;            // Tx invert
      _FrSkySPort_C1= 0xA0;            // Single wire mode
      _FrSkySPort_S2 = 0x10;           // Rx Invert
     
}

// ***********************************************************************
void FrSkySPort_Process(void) {
uint8_t data = 0;
        uint32_t temp=0;
uint8_t offset;
        while ( _FrSkySPort_Serial.available())
          {
  data =  _FrSkySPort_Serial.read();
          if (lastRx == START_STOP && ((data == SENSOR_ID1) || (data == SENSOR_ID2) || (data == SENSOR_ID3)  || (data == SENSOR_ID4)))
            {
             
              switch(FR_ID_count) {
                 case 0:
                   FrSkySPort_SendPackage(FR_ID_ALTITUDE,NazaCanDecoder.getAlt() * 100 );  // ALTITUDE ####################################################
                 break;
                 case 1:
                 
                 FrSkySPort_SendPackage(FR_ID_T2 ,NazaCanDecoder.getNumSat()*10 + NazaCanDecoder.getFixType());
                 break;
/*                 
switch (NazaCanDecoder.getFixType())
    {
      case NazaCanDecoderLib::NO_FIX:   FrSkySPort_SendPackage(FR_ID_T2,0 ); break;
      case NazaCanDecoderLib::FIX_2D:   FrSkySPort_SendPackage(FR_ID_T2,2 ); break;
      case NazaCanDecoderLib::FIX_3D:   FrSkySPort_SendPackage(FR_ID_T2,3 ); break;
      case NazaCanDecoderLib::FIX_DGPS: FrSkySPort_SendPackage(FR_ID_T2,4 ); break;
      default:                          FrSkySPort_SendPackage(FR_ID_T2,99 );
    }
                 break;
*/   
                 case 2:
                   FrSkySPort_SendPackage(FR_ID_GPS_ALT,NazaCanDecoder.getGpsAlt()*100);           
                 break; 
                 
                 case 3:
                   FrSkySPort_SendPackage(FR_ID_VFAS,NazaCanDecoder.getBattery() /10);           
                 break;

                case 4:        // Sends the ap_longitude value, setting bit 31 high
                //ap_longitude = abs(NazaCanDecoder.getLon()*10000000);
                ap_longitude = NazaCanDecoder.getLon()*10000000;
                //ap_longitude = 25432100;
                       if(ap_longitude < 0)
                           latlong=((abs(ap_longitude)/100)*6)  | 0xC0000000;
                           else
                           latlong=((abs(ap_longitude)/100)*6)  | 0x80000000;
                       FrSkySPort_SendPackage(FR_ID_LATLONG,latlong);
                       
                   break;
                   
                 case 5:        // Sends the ap_latitude value, setting bit 31 low 
                 //ap_latitude = abs(NazaCanDecoder.getLat()*10000000);
                 ap_latitude = NazaCanDecoder.getLat()*10000000;
                 //ap_latitude =481234500;
                         if(ap_latitude < 0 )
                             latlong=((abs(ap_latitude)/100)*6) | 0x40000000;
                             else
                             latlong=((abs(ap_latitude)/100)*6);
                         FrSkySPort_SendPackage(FR_ID_LATLONG,latlong);
                         
                    break; 
                   
                   
                   
                   
                   
                 case 6:
                   FrSkySPort_SendPackage(FR_ID_HEADING,NazaCanDecoder.getHeading()*100 );           
                 break;                     
                   
                   
     
                      case 7:
switch (NazaCanDecoder.getMode())
    {
      case NazaCanDecoderLib::MANUAL:   FrSkySPort_SendPackage(FR_ID_T1,0 ); break;
      case NazaCanDecoderLib::ATTI:     FrSkySPort_SendPackage(FR_ID_T1,1 ); break;
      case NazaCanDecoderLib::GPS:      FrSkySPort_SendPackage(FR_ID_T1,2 ); break;
      case NazaCanDecoderLib::FAILSAFE: FrSkySPort_SendPackage(FR_ID_T1,3 ); break;

      default:                          FrSkySPort_SendPackage(FR_ID_T1,99 );
    }   
               break;                 
               
               
               case 8:               
               
               FrSkySPort_SendPackage(FR_ID_FUEL,NazaCanDecoder.getCog() ); break;
               
               case 9:               
               
               //FrSkySPort_SendPackage(FR_ID_SPEED,NazaCanDecoder.getSpeed() *100 ); break;
               FrSkySPort_SendPackage(FR_ID_RPM,NazaCanDecoder.getSpeed() *2 *100); break;
               case 10:               
               
               FrSkySPort_SendPackage(FR_ID_VARIO,NazaCanDecoder.getVsi()*100 ); break; 
   
               case 11:               
               
               FrSkySPort_SendPackage(FR_ID_ACCZ,NazaCanDecoder.getHdop()*100 ); break;           
               
               case 12:               
               
               FrSkySPort_SendPackage(FR_ID_ACCX,NazaCanDecoder.getRoll()*100 ); break;             
               
               case 13:               
               
               FrSkySPort_SendPackage(FR_ID_ACCY,NazaCanDecoder.getPitch() *100); break;
               
               
                 
                 
               }
            FR_ID_count++;
            if(FR_ID_count > MAX_ID_COUNT) FR_ID_count = 0; 
            }
          lastRx=data;
          }
}


   // ***********************************************************************
    void FrSkySPort_SendByte(uint8_t byte) {

       if (( byte == START_STOP ) || ( byte == BYTESTUFF )) {
          _FrSkySPort_Serial.write(BYTESTUFF) ;
          _FrSkySPort_Serial.write(byte ^ STUFF_MASK) ;
       } else {
          _FrSkySPort_Serial.write(byte) ;
       }
     
            // CRC update
       crc += byte;         //0-1FE -> commentaire adéquat
       crc += crc >> 8;   //0-1FF -> commentaire adéquat
       crc &= 0x00ff;      // 0-0FF -> commentaire adéquat
    }


    // ***********************************************************************
    void FrSkySPort_SendCrc() {
      //  _FrSkySPort_Serial.write(0xFF-crc);
      crc = 0xFF-crc ;
      if (( crc  == START_STOP ) || ( crc  == BYTESTUFF )) {
         _FrSkySPort_Serial.write(BYTESTUFF) ;
         _FrSkySPort_Serial.write(crc  ^ STUFF_MASK) ;
      }else {
         _FrSkySPort_Serial.write(crc ) ;
      }

      crc = 0;          // CRC reset
    }







/*
// ***********************************************************************
void FrSkySPort_SendByte(uint8_t byte) {

       _FrSkySPort_Serial.write(byte);

        // CRC update
crc += byte;         //0-1FF
crc += crc >> 8;   //0-100
crc &= 0x00ff;
crc += crc >> 8;   //0-0FF
crc &= 0x00ff;
}


// ***********************************************************************
void FrSkySPort_SendCrc() {
_FrSkySPort_Serial.write(0xFF-crc);
        crc = 0;          // CRC reset
}
*/

// ***********************************************************************
void FrSkySPort_SendPackage(uint16_t id, uint32_t value) {
             
// if(MavLink_Connected) {
        if (1==1) {
           
            }
           
        digitalWrite(led,HIGH);   
        _FrSkySPort_C3 |= 32;      //  Transmit direction, to S.Port
FrSkySPort_SendByte(DATA_FRAME);
uint8_t *bytes = (uint8_t*)&id;
FrSkySPort_SendByte(bytes[0]);
FrSkySPort_SendByte(bytes[1]);
bytes = (uint8_t*)&value;
FrSkySPort_SendByte(bytes[0]);
FrSkySPort_SendByte(bytes[1]);
FrSkySPort_SendByte(bytes[2]);
FrSkySPort_SendByte(bytes[3]);
FrSkySPort_SendCrc();
_FrSkySPort_Serial.flush();
_FrSkySPort_C3 ^= 32;      // Transmit direction, from S.Port

        digitalWrite(led,LOW);
       
}




FrskySPort.h
// Frsky Sensor-ID to use.
#define SENSOR_ID1                   0x1B // ID of sensor. Must be something that is polled by FrSky RX
#define SENSOR_ID2                   0x0D
#define SENSOR_ID3                   0x34
#define SENSOR_ID4                   0x67
// Frsky-specific
#define START_STOP               0x7e
#define DATA_FRAME               0x10


//Frsky DATA ID's
#define FR_ID_SPEED               0x0830
#define FR_ID_VFAS                 0x0210
#define FR_ID_CURRENT         0x0200
#define FR_ID_RPM                  0x050F     
#define FR_ID_ALTITUDE         0x0100
#define FR_ID_FUEL                 0x0600   
#define FR_ID_ADC1                0xF102   
#define FR_ID_ADC2                0xF103     
#define FR_ID_LATLONG         0x0800
#define FR_ID_CAP_USED       0x0600
#define FR_ID_VARIO               0x0110
#define FR_ID_CELLS              0x0300     
#define FR_ID_CELLS_LAST   0x030F     
#define FR_ID_HEADING          0x0840
#define FR_ID_ACCX               0x0700
#define FR_ID_ACCY               0x0710
#define FR_ID_ACCZ               0x0720
#define FR_ID_T1                     0x0400
#define FR_ID_T2                     0x0410
#define FR_ID_GPS_ALT          0x0820



Il vous faut utiliser les libraries de ces 2 liens :

la partie Frsky est ici : MavLink_FrSkySPort_1.3.zip

la partie décodeur can est la  NazaDecoder20141130 NazaDecoder library for Arduino v20141130 (86.8 KB) 276 views zip






ATTENTION cela fonctionne en l'état mais tout n'est pas fini de tester :)


A cela il faudra rajouter de beau scripts LUA (en cours de modification car c'est pas le même combat que la Dropix :)  )


Bonne lecture


Sylvain
« Modifié: 29 mai 2016 à 18:08:04 par djsyl »
IP archivée

Snakesrules

  • Membre Confirmé
  • ***
  • Hors ligne Hors ligne
  • Messages: 194
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #1 le: 23 janvier 2015 à 22:13:18 »

Ca c'est du Tuto !! Merci  :doublepouce:

Je me permet juste une question : pourquoi ne pas utiliser une interface à base de PIC 18F par exemple intégrant directement un CAN ?
IP archivée
Plein de trucs qui volent , ou pas ...

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #2 le: 23 janvier 2015 à 23:00:35 »

libre a toi ...

en fait il y a déjà beaucoup de partie de code qui existe en arduino / teensy

jer_pf

  • Nouveau
  • *
  • Hors ligne Hors ligne
  • Messages: 5
    • DroneGo - Photographies Aeriennes à Mayotte
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #3 le: 20 février 2015 à 15:41:43 »

Bonjour,

je viens d'effectuer le montage et l'envoi de code dans le teensy. Le message est décodé par le Can, compris par le teensy et envoyé par le X8R à la Taranis.
Par contre, petit souci au niveau de l'envoi de la trame GPS, j'ai une erreur sur la latitude, elle indique 12°N alors que je suis à 12°S (à Mayotte). Si je corrige le signe, cela me positionne correctement sur une carte. Je vais donc explorer le code pour y trouver la coquille. Cela dit, j'ai utilisé le code suivant:

- pour le teensy: Naza-FrSky.ino du 23/01/2015
la librairie flexcan d'ici: https://github.com/teachop/FlexCAN_Library/releases/tag/v0.1-beta
et la librairie NazaCandecoder d'ici: http://www.rcgroups.com/forums/showatt.php?attachmentid=7561821&d=1423683343

cela peut pourrait provenir d'une erreur de ma part sur le choix des librairies...qu'en pensez-vous?
IP archivée
TBS Discovery AerialMob Pixhawk
DJI S800 Wookon-G M
DJI F550 DJI NAZA MV2 IOSD MK2 LK24 S1/S2
Quadri TBS DJI NAZA MV2 S1/S2/S3
Xugong 8" DJI NAZA M lite
Porket Racer 240 Naze 32 Accro
MicroQuad HK
Quadri KK2 LCD maison

Télépilote DGAC

EPP FPV Electronique EagleTree (Guardian - OSDPro - GPS - Alti ...)
Helico Belt CP

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #4 le: 20 février 2015 à 15:53:50 »

Possible tu a pas tester avec les codes que j'ai mis en lignes ici ?

il faut regarder sur la ligne serie ce que renvoie le décodage naza

celà a peut'être été travaillé pas des gens du nord qui ont oublié de vérifier le signe ...

tiens moi au courant si il faut on corrigera :)
« Modifié: 20 février 2015 à 15:58:52 par djsyl »
IP archivée

jer_pf

  • Nouveau
  • *
  • Hors ligne Hors ligne
  • Messages: 5
    • DroneGo - Photographies Aeriennes à Mayotte
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #5 le: 20 février 2015 à 16:59:35 »

J'ai trouvé, il y a deux valeurs absolues en trop:

case 4:        // Sends the ap_longitude value, setting bit 31 high
--->>>                ap_longitude = abs(NazaCanDecoder.getLon()*10000000);
                 
                       if(ap_longitude < 0)
                           latlong=((abs(ap_longitude)/100)*6)  | 0xC0000000;
                           else
                           latlong=((abs(ap_longitude)/100)*6)  | 0x80000000;
                       FrSkySPort_SendPackage(FR_ID_LATLONG,latlong);
                       
                   break;
                   
                 case 5:        // Sends the ap_latitude value, setting bit 31 low 
--->>>                 ap_latitude = abs(NazaCanDecoder.getLat()*10000000);   
                         if(ap_latitude < 0 )
                             latlong=((abs(ap_latitude)/100)*6) | 0x40000000;
                             else
                             latlong=((abs(ap_latitude)/100)*6);
                         FrSkySPort_SendPackage(FR_ID_LATLONG,latlong);
                         
                    break; 


il suffit de les enlever, et dans ce cas les habitants de l'ouest et du sud existeront  ;)

j'ai testé sur le Naza et cela fonctionne.

J'utilise le Teensy sur le pixhawk également, et ça donne de supers résultats.
A mon avis, il faudrait mettre des conditions à l'envoi des coordonnées GPS, dès que tu as un fix 3D par exemple, sinon tu es obligé d'éteindre et rallumer la Taranis pour avoir la distance au pilote correcte.

Voilà le morceau de code:

case 4:        // Sends the ap_longitude value, setting bit 31 high
                ap_longitude = (NazaCanDecoder.getLon()*10000000);
                 
                       if(ap_longitude < 0)
                           latlong=((abs(ap_longitude)/100)*6)  | 0xC0000000;
                           else
                           latlong=((abs(ap_longitude)/100)*6)  | 0x80000000;
                       FrSkySPort_SendPackage(FR_ID_LATLONG,latlong);
                       
                   break;
                   
                 case 5:        // Sends the ap_latitude value, setting bit 31 low 
                 ap_latitude = (NazaCanDecoder.getLat()*10000000);   
                         if(ap_latitude < 0 )
                             latlong=((abs(ap_latitude)/100)*6) | 0x40000000;
                             else
                             latlong=((abs(ap_latitude)/100)*6);
                         FrSkySPort_SendPackage(FR_ID_LATLONG,latlong);
                         
                    break; 
IP archivée
TBS Discovery AerialMob Pixhawk
DJI S800 Wookon-G M
DJI F550 DJI NAZA MV2 IOSD MK2 LK24 S1/S2
Quadri TBS DJI NAZA MV2 S1/S2/S3
Xugong 8" DJI NAZA M lite
Porket Racer 240 Naze 32 Accro
MicroQuad HK
Quadri KK2 LCD maison

Télépilote DGAC

EPP FPV Electronique EagleTree (Guardian - OSDPro - GPS - Alti ...)
Helico Belt CP

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #6 le: 20 février 2015 à 17:31:54 »

on peut mais moi je  fait un reset télémétrie en général avant de partir comme ça ça remet tout a zéro i compris l'altitude et le point pilote ...

Et merci pour les habitants de l'ouest et du sud   ;)


corrigé dans le 1er post :

case 4:
ap_longitude = (NazaCanDecoder.getLon()*10000000);
---------------------------------------------------------------         
                   
case 5:        // Sends the ap_latitude value, setting bit 31 low 
ap_latitude = (NazaCanDecoder.getLat()*10000000);
-----------------------------------------------------------
« Modifié: 20 février 2015 à 17:41:48 par djsyl »
IP archivée

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #7 le: 20 février 2015 à 18:34:02 »

Fait attention dans la nouvelle version j'ai combiné le nb de sat et le type de fixe dans une même case par mesure d'économie :


                 case 1:
                 
                 FrSkySPort_SendPackage(FR_ID_T2 ,NazaCanDecoder.getNumSat()*10 + NazaCanDecoder.getFixType());
                 break;
/*                 
switch (NazaCanDecoder.getFixType())
    {
      case NazaCanDecoderLib::NO_FIX:   FrSkySPort_SendPackage(FR_ID_T2,0 ); break;
      case NazaCanDecoderLib::FIX_2D:   FrSkySPort_SendPackage(FR_ID_T2,2 ); break;
      case NazaCanDecoderLib::FIX_3D:   FrSkySPort_SendPackage(FR_ID_T2,3 ); break;
      case NazaCanDecoderLib::FIX_DGPS: FrSkySPort_SendPackage(FR_ID_T2,4 ); break;
      default:                          FrSkySPort_SendPackage(FR_ID_T2,99 );
    }
                 break;
*/


Et comme je vois que tu a bien avancé voici un script de mixes qui est a peaufiner

-- MODE VOCAL POUR DROPIX --
-- CHEMIN /SCRIPT/MIXES/
-- BETA VERSION 0.02 --
-- SB 17/JANVIER/2015
-- Annonces Mode de vol, armement moteur, distance, hauteur, tension
-- Recuperation des affichages par action sur bouton SA


local valuemode
local memmode
local gps
local memgps
local armed
local memarmed
local altitude
local memaltitude
local distance
local memdistance
local tension
local memtension
local cap
local memcap
local element
local memelement
local nbfix
local memnbfix
local cog
local memcog

local boucle
local boucle2
local fix


local function init_func()
                valuemode = 0
                memmode = 0
gps = 0
memgps = 0
armed = 0
memarmed = 0


altitude = 0
memaltitude = 0
distance = 0
memdistance = 0
tension = 0
memtension =0
cap = 0
memcap = 0
element = 0
memelement = 0
nbfix = 0
memnbfix = 0
cog = 0
memcog = 0


fix = 0
boucle = 0
boucle2 = 0

end

local function run_func()


-- ########################################################################################
--                     RECUPERATION DES DONNEES
-- ########################################################################################

            valuemode = getValue("temp1") --  (mode de vol) manuel atti gps rth
gps =       getValue("temp2") / 10 --  T2 XXY XX = nombre sat , Y type de fixe
nbfix =     getValue("temp2") - (math.floor(getValue("temp2") / 10)*10)
cog =       getValue("fuel") -- 
armed =     0  -- getValue("temp2") --  T2
altitude =  getValue("gps-altitude") --  Altitude GPS
distance =  getValue("distance") --  DISTANCE
tension =   getValue("vfas") --  tension (vfas)
cap =     getValue("heading") --  cap
element =   getValue("cell-min-min") --  element le plus faible nécessite le module tension frsky

-- ########## DEBUG ######################

if (boucle2 > 1000 ) then
-- altitude = math.random(1, 150)
-- distance = math.random(0, 9999)
boucle2 = 0
end

-- #############################





boucle = boucle + 1   -- pour ralentir les annonces GPS qui parlent trop
boucle2 = boucle2 + 1

-- ########################################################################################
--                     PARTIE VOCAL
-- ########################################################################################






-- GESTION element


if not ( element == memelement ) then
                   
   playNumber(element * 10 , 1, PREC1)
   
memelement = element
end




-- GESTION du cap


if (cap - 10 > memcap ) or (cap + 10 < memcap ) then
                   
   playNumber(cap ,7,0)
   
memcap = cap
end


-- GESTION de la tension


if  (tension - 0.2 > memtension ) or (tension + 0.2 < memtension)  then
                   
   playNumber(tension * 10,1,PREC1)
   
memtension = tension
end




-- GESTION de l altitude

if (altitude - 10 > memaltitude ) or (altitude + 10 < memaltitude ) then
                   playFile("/SOUNDS/fr/altitude.wav")
   playNumber(altitude,0,0)
   playFile("/SOUNDS/fr/SYSTEM/0130.wav")
memaltitude = altitude
end





-- GESTION de la distance

if (distance - 10 > memdistance ) or (distance + 10 < memdistance ) then
                   playFile("/SOUNDS/fr/distance.wav")
   playNumber(distance,0,0)
   playFile("/SOUNDS/fr/SYSTEM/0130.wav")
memdistance = distance
end





-- GESTION ARMEMENT MOTEURS

if not (armed == memarmed) then

if (armed == 0)  then 
playFile("/SOUNDS/fr/engoff.wav")
end
if (armed == 1)  then 
playFile("/SOUNDS/fr/engon.wav")
end

memarmed = armed
end

-- GESTION nombre de satellite et du type de fix

if (boucle > 500 ) then

if not (gps == memgps) then
playNumber(gps,0,0)
playFile("/SOUNDS/fr/sat.wav")
playNumber(nbfix,0,0)
playFile("/SOUNDS/fr/dfix.wav")

memgps = gps
end
boucle = 0
end


-- GESTION DES MODES DE VOL

if not (valuemode == memmode) then
               
if (valuemode == 0)  then 
playFile("/SOUNDS/fr/manual.wav")
end

if (valuemode == 1)  then 
playFile("/SOUNDS/fr/atti.wav")
end

if (valuemode == 2)  then 
playFile("/SOUNDS/fr/gps.wav")
end

if (valuemode == 3)  then 
playFile("/SOUNDS/fr/rth.wav")
end

if (valuemode == 99)  then  -- si on detecte une valeur differente de ces 4
playFile("/SOUNDS/fr/SYSTEM/0099.wav")
end


memmode = valuemode

end







-- #################################   AFFICHAGE SUR ACTION BOUTON SA ################################################
if (getValue(92) ==  0 ) then

lcd.lock()
lcd.clear()

-- ################# DESSIN CADRILLAGE ###################
if (0 == 0 ) then




  lcd.drawLine(52, -1, 52, 64, SOLID, 0)    -- Vertical 1
  lcd.drawLine(106, -1, 106, 64, SOLID, 0)  -- Vertical 2
  lcd.drawLine(159, -1, 159, 64, SOLID, 0)  -- Vertical 3

  lcd.drawLine(0, 21, 211, 21, SOLID, 0)   -- Horizointal 1
  lcd.drawLine(0, 42, 211, 42, SOLID,0 )   -- Horizontal 2 GREY_DEFAULT


-- lcd.drawTimer(50, 55, gps , DBLSIZE)



-- ################### MODE DISPLAY NAZA ########################

-- lcd.drawPixmap(46, 3, "/SCRIPTS/BMP/fm.bmp")

-- custom_mode

local Mode = getValue("temp1")
if Mode == 0  then  lcd.drawText(54, 5, "MANUEL", MIDSIZE) end
if Mode == 1  then  lcd.drawText(63, 5, "ATTI", MIDSIZE) end
if Mode == 2  then  lcd.drawText(67, 5, "GPS", MIDSIZE) end
if Mode == 3  then  lcd.drawText(67, 5, "RTH", BLINK + MIDSIZE) end
if Mode == 99  then  lcd.drawText(54, 5,"******", MIDSIZE) end




lcd.drawNumber(70,46,gps,MIDSIZE )                            -- sat
lcd.drawText(lcd.getLastPos(), 47, " SAT", MIDSIZE)

lcd.drawNumber(37,5,tension * 100,PREC2 + MIDSIZE )          -- tension
lcd.drawText(lcd.getLastPos(), 5, "v", MIDSIZE)

lcd.drawNumber(117, 5, altitude, LEFT+MIDSIZE)                -- altitude
lcd.drawText(lcd.getLastPos(), 9, "Alt", SMLSIZE)

lcd.drawNumber(117, 26, distance, LEFT+MIDSIZE)                -- distance
lcd.drawText(lcd.getLastPos(), 30, "Dis", SMLSIZE)

lcd.drawNumber(120, 47, cap, LEFT+MIDSIZE)                -- cap
lcd.drawText(lcd.getLastPos(), 45, "cap", SMLSIZE)

lcd.drawNumber(170, 47, cap, LEFT+MIDSIZE)                -- cog
lcd.drawText(lcd.getLastPos(), 45, "cog", SMLSIZE)


end  -- if (1 < 0 ) then

end




if (getValue(92) > 0 ) then

lcd.lock()
lcd.clear()


-- ################ Phantom Battery Display ############### A FINIR DE TRAVAILLER



-- Max Batt lt Taranis = 12,2V entspricht 12,6v Phantom => Spannung wird 0,4v zu niedrig angezeigt
-- Min Batt lt Taranis = 10,8V entspricht 11,2v Phantom => Spannung wird 0,4v zu niedrig angezeigt

   
  local myCurrent = getValue("216")                     -- zuz¸glich 0,4v zum Ausgleich   
       
--  local myCurrent = 12.4                                    -- f¸r Taranis Simulations Mode
                               
   local myMaxV = 25.2                                       -- Maximale Spannung des Akkus
   local myMinV = 21.5                                        -- Minimale Spannung des Akkus
   local myRangeV = myMaxV - myMinV                           -- Nutzspannung berechnen
   local myAvailV = myCurrent - myMinV                        -- Restliche Nutzspannung berechnen
   local myPercent = math.floor(myAvailV / myRangeV * 100)    -- Restliche Nutzspannung in Prozent
   
   if myAvailV < 0 then myAvailV = 0 end                      -- Fehlerhafte Werte abfangen
   if myPercent < 0 then myPercent = 0 end                    -- Fehlerhafte Werte abfangen
   if myPercent > 100 then myPercent = 100 end                -- Fehlerhafte Werte abfangen
   
   local myPxHeight = math.floor(myPercent * 0.37)            -- Benˆtigte Zeilenhˆhe ermitteln
   local myPxY = 11 + 37 - myPxHeight

   lcd.drawPixmap(3, 1, "/SCRIPTS/BMP/battery.bmp")           -- Leere Batterie anzeigen

if myPercent > 0 then
    lcd.drawFilledRectangle(8, myPxY, 21, myPxHeight, FILL_WHITE )
   end


   local i = 36
   while (i > 0) do
    lcd.drawLine(7, 11 + i, 27, 11 +i, SOLID, GREY_DEFAULT)
    i= i-2
   end

   if (myCurrent > myMaxV) or (myCurrent < myMinV) then
    lcd.drawNumber(4,55, myCurrent * 100  ,PREC2 + LEFT + BLINK)
   else
  lcd.drawNumber(4,55, myCurrent * 100  ,PREC2 + LEFT)
   end
   lcd.drawText(lcd.getLastPos(), 55, "v", 0)


-- ################### MODE DISPLAY NAZA ########################

-- lcd.drawPixmap(46, 3, "/SCRIPTS/BMP/fm.bmp")

-- custom_mode

local Mode = getValue("temp1")
if Mode == 0  then  lcd.drawText(54, 5, "MANUEL", MIDSIZE) end
if Mode == 1  then  lcd.drawText(54, 5, "ATTI", MIDSIZE) end
if Mode == 2  then  lcd.drawText(54, 5, "GPS", MIDSIZE) end
if Mode == 3  then  lcd.drawText(54, 5, "RTH", BLINK + MIDSIZE) end
if Mode == 99  then  lcd.drawText(54, 5, "*****", MIDSIZE) end


-- ####################### CHRONO  ##########################



  lcd.drawPixmap(46, 46, "/SCRIPTS/BMP/timer.bmp")
  lcd.drawTimer(50, 46, getValue(196) , DBLSIZE)                  -- Timer 1 value [seconds]

 

-- ############## Distance ########################################

   lcd.drawPixmap(110, 0, "/SCRIPTS/BMP/dist.bmp")
   lcd.drawNumber(130, 4, getValue(212), LEFT+MIDSIZE)                -- 212 Distance
   lcd.drawText(lcd.getLastPos(), 4, "m", MIDSIZE)


-- ############## GPS ALTITUDE ########################################

         lcd.drawPixmap(110, 46, "/SCRIPTS/BMP/hgt.bmp")
lcd.drawNumber(130,49,getValue(213), MIDSIZE  + LEFT )-- gps-altitude
lcd.drawText(lcd.getLastPos(), 53, "m" , 0)



-- ################# GPS Quality ##################################
   local myNumSat =  getValue(209)                                   -- Temp1=209 ist Anzahl Sats
   local myQualSat =  getValue(210)                                  -- Temp2=210 ist Qualit‰t des Satfix
   
-- myNumSat =5                                                       -- f¸r Taranis Simulations Mode
-- myQualSat =3                                                      -- f¸r Taranis Simulations Mode
   
   if myQualSat == 0 then
  lcd.drawPixmap(46, 24, "/SCRIPTS/BMP/sat0.bmp")                -- kein Fix
   elseif myQualSat == 2 then
lcd.drawPixmap(46, 24, "/SCRIPTS/BMP/sat1.bmp")                -- 2D Fix
   elseif myQualSat == 3 then
lcd.drawPixmap(46, 24, "/SCRIPTS/BMP/sat2.bmp")                -- 3D Fix
   elseif myQualSat == 4 then
lcd.drawPixmap(46, 24, "/SCRIPTS/BMP/sat3.bmp")                -- Differenzial GPS (DGPS)
end



if myNumSat > 5 then
lcd.drawPixmap(66, 25, "/SCRIPTS/BMP/gps_6.bmp")               -- 6 oder mehr Sats
elseif myNumSat > 4 then
lcd.drawPixmap(66, 25, "/SCRIPTS/BMP/gps_5.bmp")               -- 5 Sats
elseif myNumSat > 3 then
lcd.drawPixmap(66, 25, "/SCRIPTS/BMP/gps_4.bmp")               -- 4 Sats
elseif myNumSat > 2 then
  lcd.drawPixmap(66, 25, "/SCRIPTS/BMP/gps_3.bmp")               -- 3 Sats
elseif myNumSat > 1 then
lcd.drawPixmap(66, 25, "/SCRIPTS/BMP/gps_2.bmp")               -- 2 Sats
elseif myNumSat > 0 then
lcd.drawPixmap(66, 25, "/SCRIPTS/BMP/gps_1.bmp")               -- 1 Sat
else
lcd.drawPixmap(66, 25, "/SCRIPTS/BMP/gps_0.bmp")                 -- kein Sat
end
   lcd.drawNumber(73, 24, myNumSat,  SMLSIZE)                        -- Anzahl anzeigen



-- ################### Home Point ######################################
-- ### wenn Pilot Position bekannt HP setzen                 ###########
-- ### muss noch korrigiert werden da NAZA erst sp‰ter setzt ###########
   
   if getValue("pilot-longitude") == getValue("pilot-latitude") then
      lcd.drawPixmap(110, 24, "/SCRIPTS/BMP/home1.bmp")
      lcd.drawText(132, 26, "?", MIDSIZE + BLINK)
   elseif myNumSat > 5 then
      lcd.drawPixmap(110, 24, "/SCRIPTS/BMP/home.bmp")
      lcd.drawPixmap(130, 24, "/SCRIPTS/BMP/check.bmp")
   else
      lcd.drawPixmap(110, 24, "/SCRIPTS/BMP/home.bmp")
      lcd.drawText(132, 26, "X",  BLINK+ MIDSIZE)
   end

-- ####################### Logging display ############################

-- Enregistrement des log actif ( bizard le get 100 ??? )

-- ###  Logging auf logischem Schalter LS1 = source 100   #############

   if getValue(100) > 0 then                                         
      lcd.drawText(155,28,"O", SMLSIZE + BLINK) -- Clignotement sur la disquette
      lcd.drawPixmap(152, 30, "/SCRIPTS/BMP/save.bmp") -- Logo disquette
   end









-- ############### RSSI ##############################################



  if getValue(200) > 38 then
   percent = ((math.log(getValue(200)-28, 10)-1)/(math.log(72, 10)-1))*100
  else
   percent = 0
  end

  if percent > 90 then
    lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI10.bmp")
  elseif percent > 80 then
lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI09.bmp")
  elseif percent > 70 then
lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI08.bmp")
  elseif percent > 60 then
lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI07.bmp")
  elseif percent > 50 then
lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI06.bmp")
elseif percent > 40 then
lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI05.bmp")
  elseif percent > 30 then
lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI04.bmp")
  elseif percent > 20 then
lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI03.bmp")
  elseif percent > 10 then
lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI02.bmp")
  elseif percent > 0 then
lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI01.bmp")
  else
    lcd.drawPixmap(164, 1, "/SCRIPTS/BMP/RSSI00.bmp")
  end

  lcd.drawChannel(178, 55, 200, LEFT)
  lcd.drawText(lcd.getLastPos(), 56, "dB", SMLSIZE)




end -- AFFICHAGES



                return memmode
end  --run_func()

return { init=init_func, run=run_func, output= {"MODE"} }

Si il te manque des sons ou des images j'ai recopier ma SD ici :

http://f8byc1.free.fr/taranis/masd2
« Modifié: 20 février 2015 à 19:16:43 par djsyl »
IP archivée

JMMaupin

  • Membre Senior
  • *****
  • Hors ligne Hors ligne
  • Messages: 861
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #8 le: 20 février 2015 à 22:12:49 »

 :doublepouce: :respect: Mecrci pour ce magnifique partage, j'avais vu il y un mois ce bricolage sans m'y arrêter car je vole avec un Wookong.
Mais pour avoir maintenant le nez dans le Teensy ce sujet m’intéresse grandement.
IP archivée
Multi: Phantom 1 H3-2D, iOSD Blacksnapper X8
DJI Mavic Pro
TBS Gemini    Banc de test, base Reptile.
Medias: Youtube / Flickr
Hobbyist, fan de technos et d'images depuis l'enfance.

jer_pf

  • Nouveau
  • *
  • Hors ligne Hors ligne
  • Messages: 5
    • DroneGo - Photographies Aeriennes à Mayotte
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #9 le: 20 février 2015 à 22:17:23 »

Ok, c'est top. Je flashe le teensy demain et j'essaie une petite mission photogrammetrie pour voir si c'est facilement exploitable. Merci encore!
IP archivée
TBS Discovery AerialMob Pixhawk
DJI S800 Wookon-G M
DJI F550 DJI NAZA MV2 IOSD MK2 LK24 S1/S2
Quadri TBS DJI NAZA MV2 S1/S2/S3
Xugong 8" DJI NAZA M lite
Porket Racer 240 Naze 32 Accro
MicroQuad HK
Quadri KK2 LCD maison

Télépilote DGAC

EPP FPV Electronique EagleTree (Guardian - OSDPro - GPS - Alti ...)
Helico Belt CP

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #10 le: 21 février 2015 à 07:23:24 »

Ok, c'est top. Je flashe le teensy demain et j'essaie une petite mission photogrammetrie pour voir si c'est facilement exploitable. Merci encore!

Pas de quoi, le partage voila l'essence qui fait vivre le forum et surtout merci a toi d'avoir expérimenté et apporté des solutions et corrections au sujet.



@JMM excellente occasion de tester sur wookong j'espere que les codes sont les mêmes


Attention tout de même le script lua est en 3 partie

1 une vocale qui fonctionne pas trop mal.

2 autres parties (affichage) sont actionnable par le bouton SA

ce sont des affichages ... sur celui le plus graphique je me suis rendu compte de dégradation des sons lors de l'affichage des BMP

ce qui m'a conduit a faire un écran plus simpliste qui n'est pas totalement fini


A vous de voir  :dots:

Belov

  • Membre Junior
  • **
  • Hors ligne Hors ligne
  • Messages: 84
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #11 le: 24 février 2015 à 16:04:06 »

Hello Sylvain

As tu un lien pour les convertisseurs CAN ?
Absent chez Banggood et à part acheter un chip NCV7351, je ne trouve rien :-(
IP archivée
Phantom V1, Nacelle Tarot 2D, GoPro HD4 BE, FPV FatShark, ezOSD
DJI Y550 en reconstruction, Naza V2, Zenmuse H3 3D, radio FrSky Taranis + télémétrie
Création d'un X8 slowfly
Vortex Racer et ZigMaR250

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #12 le: 24 février 2015 à 16:14:36 »

il me semble avoir acheter ça sur aliexpress de mémoire

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #13 le: 24 février 2015 à 16:16:25 »

EN voilà un mais il me semble pas l'avoir payer autant ...

http://www.aliexpress.com/item/Sn65hvd230-can-module-can-bus-module-communication-module-can-bus-transceiver-development-board/1245936884.html


Si non tu met can bus transceiver SN65HVD230 dans les moteurs de recherche ...
« Modifié: 24 février 2015 à 16:22:44 par djsyl »
IP archivée

Belov

  • Membre Junior
  • **
  • Hors ligne Hors ligne
  • Messages: 84
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #14 le: 24 février 2015 à 16:32:59 »

j'ai vu celui là au moins cher http://www.ebay.fr/itm/SN65HVD230-CAN-Board-Network-Communication-3-3V-CAN-Module-ESD-Protection-/361146358603?pt=LH_DefaultDomain_3&hash=item5416001b4b
mais c'est loin des 1 euro
Tout augmente avec l'euro
;-))

Il doit y avoir un moyen de récupérer des samples gratos
IP archivée
Phantom V1, Nacelle Tarot 2D, GoPro HD4 BE, FPV FatShark, ezOSD
DJI Y550 en reconstruction, Naza V2, Zenmuse H3 3D, radio FrSky Taranis + télémétrie
Création d'un X8 slowfly
Vortex Racer et ZigMaR250

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #15 le: 24 février 2015 à 16:49:51 »

Si non il faut acheter les CI en DIP8 et les monter sur des plaques a trous

Belov

  • Membre Junior
  • **
  • Hors ligne Hors ligne
  • Messages: 84
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #16 le: 24 février 2015 à 18:08:49 »

C'est le même prix voire plus cher. C'est pour ça que je regarderai si TI peut envoyer des samples.
J'ai récupéré comme ça un paquet de microcontroleurs de chez microchip (pic vs atmel, apple vs windows, poire vs fromage :-))
IP archivée
Phantom V1, Nacelle Tarot 2D, GoPro HD4 BE, FPV FatShark, ezOSD
DJI Y550 en reconstruction, Naza V2, Zenmuse H3 3D, radio FrSky Taranis + télémétrie
Création d'un X8 slowfly
Vortex Racer et ZigMaR250

vinadre

  • Membre Junior
  • **
  • Hors ligne Hors ligne
  • Messages: 12
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #17 le: 08 mai 2016 à 13:57:32 »

djsyl je te remercie pour le tuto tout fonctionne bien du premier coup.
Tu crois que tu pourrais remette à dispo le zip de la carte SD pour les images et sons du script LUA ?
IP archivée
DJI F450 V3 / Naza V2 / X8R / TS832 /Tarot T-2D V2 Xiaomi Yi /iOSD Mini
ZMR 250 en cours : Naze32 / Cobra 2204 / DYS BL20A Mini / D4R II / MinimOSD
Taranis Plus EU LBT

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #18 le: 08 mai 2016 à 14:28:32 »

Faut que je regarde ou j'ai ranger cela :)

ne t'attarde pas trop sur la partie graphique car plus on affiche de dessins plus le son s'en trouve dégradé

je suis donc dans les dernières corrections a ne plus faire de graphique !

djsyl

  • Modérateur Global
  • Membre Héroïque
  • ******
  • Hors ligne Hors ligne
  • Messages: 13 634
  • Sylvain - F8byc
    • Club-Aquilon
[TUTO] Naza Can-Bus -> Télémetrie FrSky recepteur X4R X6R X8R
« Réponse #19 le: 08 mai 2016 à 14:49:47 »



regarde si tu trouve ton bonheur ici mais c'est du vrac ;)

http://f8byc1.free.fr/taranis/archive-bmp.zip