Direct Frsky telemtry data from MW FC

Post Reply
mahowik
Posts: 332
Joined: Sun Apr 10, 2011 6:26 pm

Re: Direct Frsky telemtry data from MW FC

Post by mahowik »

So I tested this and can say that is works fine (take no more than 2-3ms in jumps!), but have not checked this in real flight though...

I made some changes according to V2.0 of "Frame Protocol of FrSky Telemetry Hub System" http://www.frsky-rc.com/uploadfile/2012 ... 254960.pdf
- e.g. it doesn't make sense to send GPS_speed and Course every 500ms because frsky receiver will send it every 1 sec.

and also taking into account er9x-frsky firmware:
- it doesn't need to send E/W and N/S for GPS position, as it's not displayed with er9x-frsky. Instead of that it's possible not remove the sign for values before point and sign will be displayed before '=' ...
- Temperature1 was used for "Distance_to_home" because it's displayed by default with er9x-frsky (custom screen is not stored to eeprom unfortunaly... i have er9x-r767 version)
- Start_altitude don't need with er9x-frsky because it's possible do the same by pressing 'Menu' button and it takes an offset to know zero point

other:
- also removed unnecessary data send, e.g. zero values after point
- as for me more usefull to have rcCommand[THROTTLE] as RPM, e.g. to know the real hover point to set MID throttle expo...

Code: Select all


    // **********************
    // FrSky telemetry
    // **********************

    #if defined(TELEMETRY_FRSKY)
      // Serial config datas
      #define TELEMETRY_FRSKY_SERIAL 3
      #define TELEMETRY_FRSKY_BAUD 9600

      // Interrupt
       #define ISR_FRSKY ISR(USART3_UDRE_vect)

      // Ringbuffer   
      #define FRSKY_BUFFER_SIZE 150
      static uint8_t bufFrSky[FRSKY_BUFFER_SIZE];
      static volatile uint8_t headTXFrSky;
      static volatile uint8_t tailTXFrSky;
     
      // Timing
      #define Time_telemetry_send 125000
      static uint8_t cycleCounter = 0;
      static uint32_t FrSkyTime  = 0;

      // Frame protocol
      #define Protocol_Header   0x5E
      #define Protocol_Tail      0x5E
     
     
      // Data Ids  (bp = before point; af = after point)
      // Official data IDs
      #define ID_GPS_altidute_bp   0x01
      #define ID_GPS_altidute_ap   0x09
      #define ID_Temprature1      0x02
      #define ID_RPM            0x03
      #define ID_Fuel_level         0x04
      #define ID_Temprature2      0x05
      #define ID_Volt            0x06
      #define ID_Altitude_bp      0x10
      #define ID_Altitude_ap      0x21
      #define ID_GPS_speed_bp      0x11
      #define ID_GPS_speed_ap      0x19
      #define ID_Longitude_bp      0x12
      #define ID_Longitude_ap      0x1A
      #define ID_E_W            0x22
      #define ID_Latitude_bp      0x13
      #define ID_Latitude_ap      0x1B
      #define ID_N_S            0x23
      #define ID_Course_bp         0x14
      #define ID_Course_ap         0x24
      #define ID_Date_Month         0x15
      #define ID_Year            0x16
      #define ID_Hour_Minute      0x17
      #define ID_Second            0x18
      #define ID_Acc_X            0x24
      #define ID_Acc_Y            0x25
      #define ID_Acc_Z            0x26
      #define ID_Voltage_Amp_bp      0x3A
      #define ID_Voltage_Amp_ap      0x3B
      #define ID_Current         0x28
      // User defined data IDs
      #define ID_Gyro_X            0x40
      #define ID_Gyro_Y            0x41
      #define ID_Gyro_Z            0x42

       void configure_FrSky()
       {         
          SerialOpen(TELEMETRY_FRSKY_SERIAL,TELEMETRY_FRSKY_BAUD);     
       }
       
       // Interrupt
       ISR_FRSKY
       {
          uint8_t Tail = tailTXFrSky;
          if (headTXFrSky != Tail)
          {
            if (++Tail >= FRSKY_BUFFER_SIZE)
            {
               Tail = 0;
            }
            tailTXFrSky = Tail;
            UDR3 = bufFrSky[Tail];  // Transmit next byte in the ring       
          }
          if (Tail == headTXFrSky) UCSR3B &= ~(1<<UDRIE3); // Check if all data is transmitted . if yes disable transmitter UDRE interrupt
        }

       // Main function FrSky telemetry
        void telemetry_frsky()
       {         
          if (currentTime > FrSkyTime ) //
          {         
             FrSkyTime = currentTime + Time_telemetry_send;
             cycleCounter++;
             // Datas sent every 125 ms
                //send_Accel();
                //sendDataTail();   

             if ((cycleCounter % 4) == 0)
             {     
                // Datas sent every 500ms
                send_Altitude();
                send_RPM();
                //send_Cell_volt();     
                sendDataTail();   
             }
             if ((cycleCounter % 8) == 0)
             {     
                // Datas sent every 1s           
                //send_Time();
            //send_Course();
                send_GPS_speed();
                send_GPS_position();
                send_GPS_altitude();
                send_Temperature1();  // Distance_to_home
                //send_Fuel_level();
               // send_Voltage_ampere();
                sendDataTail();           
             }

             if (cycleCounter == 40)
             {
                // Datas sent every 5s
                send_Temperature2();  // num of Sats
                sendDataTail();
                cycleCounter = 0;       
             }
          }
       }
         
       void write_FrSky8(uint8_t Data)
       {
            uint8_t Head = headTXFrSky;
            if (++Head >= FRSKY_BUFFER_SIZE) Head = 0;
            bufFrSky[Head] = Data;
            headTXFrSky = Head;
            UCSR3B |= (1<<UDRIE3); // Enable Interrupt   
       }

       void write_FrSky16(uint16_t Data)
       {
          uint8_t Data_send;
          Data_send = Data;
          write_FrSky8(Data_send);
          Data_send = Data >> 8 & 0xff;
          write_FrSky8(Data_send);
       }
         
       static void sendDataHead(uint8_t Data_id)
       {
          write_FrSky8(Protocol_Header);
          write_FrSky8(Data_id);
       }

       static void sendDataTail(void)
       {
          write_FrSky8(Protocol_Tail);     
       }


       //*********************************************************************************
       //-----------------   Telemetrie Datas   ------------------------------------------   
       //*********************************************************************************

       // GPS altitude
       void send_GPS_altitude(void)
       {         
          if (f.GPS_FIX && GPS_numSat >= 4)
          {
             int16_t Datas_GPS_altidute_bp;
             //uint16_t Datas_GPS_altidute_ap;

             Datas_GPS_altidute_bp = GPS_altitude;
             //Datas_GPS_altidute_ap = 0;

             sendDataHead(ID_GPS_altidute_bp);
             write_FrSky16(Datas_GPS_altidute_bp);
             //sendDataHead(ID_GPS_altidute_ap);
             //write_FrSky16(Datas_GPS_altidute_ap);
          }
       }
       
       // Temperature
       void send_Temperature2(void)
       {
          int16_t Datas_Temprature2;

          Datas_Temprature2 = GPS_numSat;  // Number of Satalits alias Temp2

          sendDataHead(ID_Temprature2);
          write_FrSky16(Datas_Temprature2);
       }

       // RPM
       void send_RPM(void)
       {
          uint16_t Datas_RPM = 0;     
          /*for (uint8_t i=0;i<NUMBER_MOTOR;i++)
          {
             Datas_RPM += motor[i];
          }
          Datas_RPM = (Datas_RPM / NUMBER_MOTOR) / 30;   // RPM
          */
         
          Datas_RPM = rcCommand[THROTTLE] / 3;

          sendDataHead(ID_RPM);
          write_FrSky16(Datas_RPM);
       }

       // Fuel level
       void send_Fuel_level(void)
       {
          uint16_t Datas_Fuel_level;

          Datas_Fuel_level = 0;

          sendDataHead(ID_Fuel_level);
          write_FrSky16(Datas_Fuel_level);
       }

       // Temperature 1
       void send_Temperature1(void)
       {
          if (f.GPS_FIX_HOME)
          {
             int16_t Datas_Temprature1;

             Datas_Temprature1 = GPS_distanceToHome; // Distance to home alias Temp1

             sendDataHead(ID_Temprature1);
             write_FrSky16(Datas_Temprature1);
          }     
       }

       // Cell voltage
       void send_Cell_volt(void)
       {
          uint16_t Datas_Volt;

          Datas_Volt = 0; // 0.01v / 0 ~ 4.2v

          sendDataHead(ID_Volt);
          write_FrSky16(Datas_Volt);
       }

       // Altitude
       void send_Altitude(void)
       {
          uint16_t Datas_altitude_bp;
          //uint16_t Datas_altitude_ap;
         
        /*static uint16_t Start_altitude;

          if (!f.ARMED)
          {
             Start_altitude = EstAlt / 100;
          }

          Datas_altitude_bp = (EstAlt / 100) - Start_altitude;
          Datas_altitude_ap = (EstAlt % 100);*/
       
        Datas_altitude_bp = (EstAlt / 100);

          sendDataHead(ID_Altitude_bp);
          write_FrSky16(Datas_altitude_bp);
          //sendDataHead(ID_Altitude_ap);
          //write_FrSky16(Datas_altitude_ap);
       }

       // GPS speed
       void send_GPS_speed(void)
       {
          if (f.GPS_FIX && GPS_numSat >= 4)
          {           
             uint16_t Datas_GPS_speed_bp;
             //uint16_t Datas_GPS_speed_ap;
             
             Datas_GPS_speed_bp = GPS_speed * 0.036;
             //Datas_GPS_speed_ap = 0;
         
             sendDataHead(ID_GPS_speed_bp);
             write_FrSky16(Datas_GPS_speed_bp);
             //sendDataHead(ID_GPS_speed_ap);
             //write_FrSky16(Datas_GPS_speed_ap);
          }
       }

       // GPS position
       void send_GPS_position(void)
       {
          if (f.GPS_FIX && GPS_numSat >= 4)
          {
             uint16_t Datas_Longitude_bp;
             uint16_t Datas_Longitude_ap;
             //uint16_t Datas_E_W;
             uint16_t Datas_Latitude_bp;
             uint16_t Datas_Latitude_ap;
             //uint16_t Datas_N_S;

             Datas_Longitude_bp = (GPS_coord[LON]) / 100000;
             Datas_Longitude_ap = abs((GPS_coord[LON])/10)  % 10000;
             //Datas_E_W = GPS_coord[LON] < 0 ? 'W' : 'E';
             Datas_Latitude_bp = (GPS_coord[LAT]) / 100000;
             Datas_Latitude_ap = abs((GPS_coord[LAT])/10) % 10000;
             //Datas_N_S = GPS_coord[LAT] < 0 ? 'S' : 'N';

             sendDataHead(ID_Longitude_bp);
             write_FrSky16(Datas_Longitude_bp);
             sendDataHead(ID_Longitude_ap);
             write_FrSky16(Datas_Longitude_ap);
             //sendDataHead(ID_E_W);
             //write_FrSky16(Datas_E_W);

             sendDataHead(ID_Latitude_bp);
             write_FrSky16(Datas_Latitude_bp);
             sendDataHead(ID_Latitude_ap);
             write_FrSky16(Datas_Latitude_ap);
             //sendDataHead(ID_N_S);
             //write_FrSky16(Datas_N_S);
          }
       }

       // Course
       void send_Course(void)
       {
          uint16_t Datas_Course_bp;
          uint16_t Datas_Course_ap;

          Datas_Course_bp = heading;
          Datas_Course_ap = 0;

          sendDataHead(ID_Course_bp);
          write_FrSky16(Datas_Course_bp);
          sendDataHead(ID_Course_ap);
          write_FrSky16(Datas_Course_ap);
       }

       // Time
       void send_Time(void)
       {
          uint32_t seconds_since_start = millis() / 1000;
               
          uint16_t Datas_Date_month;
          uint16_t Datas_Year;
          uint16_t Datas_Minutes_hours;
          uint16_t Datas_seconds;
               
          Datas_Date_month = 0;
          Datas_Year = 12;
          Datas_Minutes_hours = (seconds_since_start / 60) % 60;
          Datas_seconds = seconds_since_start % 60;     
         
          sendDataHead(ID_Hour_Minute);
          write_FrSky16(Datas_Minutes_hours);
          sendDataHead(ID_Second);
          write_FrSky16(Datas_seconds);
       }

       // ACC
       void send_Accel(void)
       {
          int16_t Datas_Acc_X;
          int16_t Datas_Acc_Y;
          int16_t Datas_Acc_Z;

          Datas_Acc_X = ((float)accSmooth[0] / acc_1G) * 1000;
          Datas_Acc_Y = ((float)accSmooth[1] / acc_1G) * 1000;
          Datas_Acc_Z = ((float)accSmooth[2] / acc_1G) * 1000;

          sendDataHead(ID_Acc_X);
          write_FrSky16(Datas_Acc_X);
          sendDataHead(ID_Acc_Y);
          write_FrSky16(Datas_Acc_Y);
          sendDataHead(ID_Acc_Z);
          write_FrSky16(Datas_Acc_Z);     
       }

       // Voltage (Ampere Sensor)
       void send_Voltage_ampere(void)
       {
          uint16_t Datas_Voltage_Amp_bp;
          uint16_t Datas_Voltage_Amp_ap;     
          uint16_t Datas_Current;   

          Datas_Voltage_Amp_bp = 0;
          Datas_Voltage_Amp_ap = 0;   
          Datas_Current = 0;

          sendDataHead(ID_Voltage_Amp_bp);
          write_FrSky16(Datas_Voltage_Amp_bp);
          sendDataHead(ID_Voltage_Amp_ap);
          write_FrSky16(Datas_Voltage_Amp_ap);   
          sendDataHead(ID_Current);
          write_FrSky16(Datas_Current);   
       }
    #endif


tobi86
Posts: 9
Joined: Fri Jun 15, 2012 11:09 pm

Re: Direct Frsky telemtry data from MW FC

Post by tobi86 »

mahowik wrote:- e.g. it doesn't make sense to send GPS_speed and Course every 500ms because frsky receiver will send it every 1 sec.

No, YOU can decide how often the Datas will be send. Only if you use the FrSky sensor hub, the Datas will be send as defined in the source code of this hub. If you copy GPS speed for example in the section 125 ms it will of course be send every 125ms.

mahowik
Posts: 332
Joined: Sun Apr 10, 2011 6:26 pm

Re: Direct Frsky telemtry data from MW FC

Post by mahowik »

tobi86 wrote:
mahowik wrote:- e.g. it doesn't make sense to send GPS_speed and Course every 500ms because frsky receiver will send it every 1 sec.

No, YOU can decide how often the Datas will be send. Only if you use the FrSky sensor hub, the Datas will be send as defined in the source code of this hub. If you copy GPS speed for example in the section 125 ms it will of course be send every 125ms.

We can simple check this practically but i suppose that frsky send the frames (1, 2, 3) according to hub protocol timeouts because as I remember it has only 1200 baud downlink with transmitter, but not 9600 which is used for communication with receiver...

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: Direct Frsky telemtry data from MW FC

Post by timecop »

mahowik - there's a bug in the baseflight implementation of frsky tele and yours - you need to do xor-stuffing when the output sequence has 0x5e in it - check the pDF and er9x implementation for example. Ive been meaning to fix this in my code, not often occuring condition but still needs to be taken care of.

mahowik
Posts: 332
Joined: Sun Apr 10, 2011 6:26 pm

Re: Direct Frsky telemtry data from MW FC

Post by mahowik »

dongs wrote:mahowik - there's a bug in the baseflight implementation of frsky tele and yours - you need to do xor-stuffing when the output sequence has 0x5e in it - check the pDF and er9x implementation for example. Ive been meaning to fix this in my code, not often occuring condition but still needs to be taken care of.

hi dongs,

yes, you are right! thanks, we need to take this into account... from "Frame Protocol of FrSky Telemetry Hub System (V2.0)" doc:
2. Byte stuffing method:
2.1 Output:
Byte in frame has value 0x5E is changed into 2 bytes: 0x5D 0x3E
Byte in frame has value 0x5D is changed into 2 bytes: 0x5D 0x3D
2.2 Input:
When byte 0x5D is received, discard this byte, and the next byte is XORed with 0x60.

mahowik
Posts: 332
Joined: Sun Apr 10, 2011 6:26 pm

Re: Direct Frsky telemtry data from MW FC

Post by mahowik »

@tobi86: you was right... frsky receiver not so clever as I supposed before ;) I have success with passing GPS speed every 125ms...

wilco1967
Posts: 156
Joined: Thu Aug 18, 2011 6:04 pm
Location: Winterswijk, Netherlands

Re: Direct Frsky telemtry data from MW FC

Post by wilco1967 »

Hi.

First of all.... thanks all for yet another improvement to the MultiWii code :!:

I have a Flyduino Mega and a FrSky equipped 9x with ER9X firmware. My receiver is a D8R-II

I went ahead and made a small transistor based inverter.
Image

It gets 5V from the Flyduino, and I took the GND from the D8R-II, because that way, I could use a normal 3wire servo lead on the Flyduino. The Flyduino and the receiver share the GND already through the PPM lead.

I soldered the transistor and the two resistors straight together, inline in a servo cable. Isolated all with some heatshrink. All working fine. (just need to label one side, so you know which side goes where next time you disconnect everything). :roll:

Just came back from a flight.... some observations

GPS data shows fine.
Distance from home(T1) also seems correct (units shown are probably in meters)
Ground speed show what I think is Km/h. The units on the GPS screen show as kts, even though I set it to metric.

ALT does receive data, but it seems there's a mixup between units in the ER9X firmware (r767).
Alt on the GPS lat/lon page is different from Alt or Galt on the custom screen. Alt on the custom screen seems to represent meters, but it does not start from zero (mine started at -39 (meters?).
I guess this is ER9X related.... The Alt on the custom screen seems to behave correctly, and show meters. It just does not reset to zero on start.
<EDIT> After a look in the code, it seems the Alt is the altitude from the Baro. Galt = GPS altitude....<END EDIT>


The RPM are shown as a 5 digit number, which represent throttle stick microseconds. It does not show baro PID adjustments. The version from tobi86 showed it as a 4 digit number, which seemed to represent motor speed. I liked tobi's version better (also because its only 4 digits, so 'fits' better on the screen), but that just my opinion....

Having this live data stream coming back from the copter, also proved what I was suspecting already for some time.....
My GPS seems to loose lock quite often, or may suddenly jump a lot..... On a few occasions, the location moved by nearly a 100 meters.... when RTH, it would move to somewere else.... Wherever it went to, once it arrived there, the distance to home was indeed 0...so it assumed that was home....
This all seems GPS related.... the FrSky telemetry just made it possible to actually see what was going on all the time.

Regarding the ER9X code..... the custom screen is nice.... just a shame in the current version it is not stored in eprom...

Some thoughts for possible improvements:
- there are 6 voltage reported (V1..V6). I guess they are cell voltages. Could we put the battery voltage, as measured by the multiwii on one of them (from the Vbat code) ? I'm also using the A2 input for the battery voltage, but why not show both.
- Could we show the powermeter reading as Mah2 (or 'fuel'). I assume, the amp sensor, once implemented, will show up on Mah1 ?
<EDIT> made some small modification to do just that..... seems to work, I get the powermeter sum in the fuel.... 8-)
I also put vbat in amps.... could not get it working in one of the voltages, but hey.... it works for me :roll: <END EDIT>

Let's hope Alex will include this in the next release :roll:

Thanks again for this great code !

tobi86
Posts: 9
Joined: Fri Jun 15, 2012 11:09 pm

Re: Direct Frsky telemtry data from MW FC

Post by tobi86 »

wilco1967 wrote:Regarding the ER9X code..... the custom screen is nice.... just a shame in the current version it is not stored in eprom...

Yes, this is a problem of er9x, actually I switched to open9x because it stores the datas in eeprom and you have more possibilities with FrSky telemetry, for example telemetry bars or more values like the actual course of the magnometer.

wilco1967 wrote:- there are 6 voltage reported (V1..V6). I guess they are cell voltages. Could we put the battery voltage, as measured by the multiwii on one of them (from the Vbat code) ? I'm also using the A2 input for the battery voltage, but why not show both.

The six voltages are the datas of the FLVS-01. I will integate the possibilty to connect this sensor and/or the FAS100 current sensor to the FC that these values will also send down to the transmitter.

mahowik
Posts: 332
Joined: Sun Apr 10, 2011 6:26 pm

Re: Direct Frsky telemtry data from MW FC

Post by mahowik »

i hope in r769 it stores the datas in eeprom already... last changes:

http://code.google.com/p/er9x/source/br ... /frsky.cpp
FAS100 fixes,Voice on A1/A2
fixes,Inactivity alarm fix,TelemetrEZ
support, flash saving


but need to try to make sure though...

Actually open9x in most cases the same or it's fully another firmware (features, gui etc.)?

tobi86
Posts: 9
Joined: Fri Jun 15, 2012 11:09 pm

Re: Direct Frsky telemtry data from MW FC

Post by tobi86 »

dongs wrote:mahowik - there's a bug in the baseflight implementation of frsky tele and yours - you need to do xor-stuffing when the output sequence has 0x5e in it - check the pDF and er9x implementation for example. Ive been meaning to fix this in my code, not often occuring condition but still needs to be taken care of.


I'm not sure, if I understood the byte stuffing method correctly, if not, can anyone explain me how it works??? I implementated it in the following code version V0.2 of frSky_telemetry.ino (the other changes as explained in my post on page 2 are also still necessary). I also added the possibility to send the vbat value to the transmitter (Data ID 0x3A FAS100). I will do the implementation of FrSky voltage sensor FLVS01 and current sensor FAS100 the next days ;) .

Code: Select all

// ****************************************************************
// FrSky telemetry
// Version: 0.2
// Date: 14/08/2012
// Changes: V0.2: - Byte stuffing added
//                - vBat will be send, if "#define FAS_100" is comment out
//                V0.1: - First release
// ****************************************************************

#if defined(TELEMETRY_FRSKY)
  // user defines
  //#define FAS_100  //if commment out, MultiWii vBat voltage will be send instead of FrSky FAS 100 voltage


  // Serial config datas
  #define TELEMETRY_FRSKY_SERIAL 3
  #define TELEMETRY_FRSKY_BAUD 9600 

  // Interrupt
   #define ISR_FRSKY ISR(USART3_UDRE_vect) 

  // Ringbuffer   
  #define FRSKY_BUFFER_SIZE 150 
  static uint8_t bufFrSky[FRSKY_BUFFER_SIZE];
  static volatile uint8_t headTXFrSky;
  static volatile uint8_t tailTXFrSky;
 
  // Timing
  #define Time_telemetry_send 125000
  static uint8_t cycleCounter = 0;
  static uint32_t FrSkyTime  = 0;

  // Frame protocol
  #define Protocol_Header   0x5E
  #define Protocol_Tail      0x5E
 
 
  // Data Ids  (bp = before point; af = after point)
  // Official data IDs
  #define ID_GPS_altidute_bp    0x01
  #define ID_GPS_altidute_ap    0x09
  #define ID_Temprature1        0x02
  #define ID_RPM                0x03
  #define ID_Fuel_level         0x04
  #define ID_Temprature2        0x05
  #define ID_Volt               0x06
  #define ID_Altitude_bp        0x10
  #define ID_Altitude_ap        0x21
  #define ID_GPS_speed_bp       0x11
  #define ID_GPS_speed_ap       0x19
  #define ID_Longitude_bp       0x12
  #define ID_Longitude_ap       0x1A
  #define ID_E_W                0x22
  #define ID_Latitude_bp        0x13
  #define ID_Latitude_ap        0x1B
  #define ID_N_S                0x23
  #define ID_Course_bp          0x14
  #define ID_Course_ap          0x24
  #define ID_Date_Month         0x15
  #define ID_Year               0x16
  #define ID_Hour_Minute        0x17
  #define ID_Second             0x18
  #define ID_Acc_X              0x24
  #define ID_Acc_Y              0x25
  #define ID_Acc_Z              0x26
  #define ID_Voltage_Amp_bp     0x3A
  #define ID_Voltage_Amp_ap     0x3B
  #define ID_Current            0x28
  // User defined data IDs
  #define ID_Gyro_X             0x40
  #define ID_Gyro_Y             0x41
  #define ID_Gyro_Z             0x42

   void configure_FrSky()
   {         
      SerialOpen(TELEMETRY_FRSKY_SERIAL,TELEMETRY_FRSKY_BAUD);      
   }
   
   // Interrupt
   ISR_FRSKY
   {
      uint8_t Tail = tailTXFrSky;
      if (headTXFrSky != Tail)
      {
        if (++Tail >= FRSKY_BUFFER_SIZE)
        {
           Tail = 0;
        }
        tailTXFrSky = Tail;
        UDR3 = bufFrSky[Tail];  // Transmit next byte in the ring       
      }
      if (Tail == headTXFrSky) UCSR3B &= ~(1<<UDRIE3); // Check if all data is transmitted . if yes disable transmitter UDRE interrupt
    }

   // Main function FrSky telemetry
    void telemetry_frsky()
   {         
      if (currentTime > FrSkyTime ) //
      {          
         FrSkyTime = currentTime + Time_telemetry_send;
         cycleCounter++;
         // Datas sent every 125 ms
            send_Accel();
            sendDataTail();   

         if ((cycleCounter % 4) == 0)
         {     
            // Datas sent every 500ms
            send_Altitude();
            send_RPM();
            send_Course();
            send_GPS_speed();
            //send_Cell_volt();       todo
            sendDataTail();   

         }
         if ((cycleCounter % 8) == 0)
         {     
            // Datas sent every 1s            
            //send_Time();
            send_GPS_position();
            send_GPS_altitude();
            send_Temperature2();  // Distance_to_home
            //send_Fuel_level();
            send_Voltage_ampere();
            send_Temperature1();  // num of Sats
            sendDataTail();            
         }

         if (cycleCounter == 40)
         {
            // Datas sent every 5s
            cycleCounter = 0;       
         }
      }
   }

   void write_FrSky8(uint8_t Data)
   {
    uint8_t Head = headTXFrSky;
   if (++Head >= FRSKY_BUFFER_SIZE) Head = 0;
    bufFrSky[Head] = Data; 
    headTXFrSky = Head;
   UCSR3B |= (1<<UDRIE3); // Enable Interrupt   
   }

   void write_FrSky16(uint16_t Data)
   {
      uint8_t Data_send;
      Data_send = Data;      
      check_FrSky_stuffing(Data_send);
      Data_send = Data >> 8 & 0xff;
      check_FrSky_stuffing(Data_send);
   }
   
   void check_FrSky_stuffing(uint8_t Data) //byte stuffing
   {
      if (Data == 0x5E)   
      {
         write_FrSky8(0x5D);
         write_FrSky8(0x3E);
      }
      else if (Data == 0x5D)   
      {
         write_FrSky8(0x5D);
         write_FrSky8(0x3D);
      }
      else
      {
         write_FrSky8(Data);         
      }
   }

   static void sendDataHead(uint8_t Data_id)
   {
      write_FrSky8(Protocol_Header);
      write_FrSky8(Data_id);
   }

   static void sendDataTail(void)
   {
      write_FrSky8(Protocol_Tail);      
   }


   //*********************************************************************************
   //-----------------   Telemetrie Datas   ------------------------------------------   
   //*********************************************************************************

   // GPS altitude
   void send_GPS_altitude(void)
   {         
      if (f.GPS_FIX && GPS_numSat >= 4)
      {
         int16_t Datas_GPS_altidute_bp;
         uint16_t Datas_GPS_altidute_ap;

         Datas_GPS_altidute_bp = GPS_altitude;
         Datas_GPS_altidute_ap = 0;

         sendDataHead(ID_GPS_altidute_bp);
         write_FrSky16(Datas_GPS_altidute_bp);
         sendDataHead(ID_GPS_altidute_ap);
         write_FrSky16(Datas_GPS_altidute_ap);
      }
   }
   
   // Temperature
   void send_Temperature1(void)
   {
      int16_t Datas_Temprature1;

      Datas_Temprature1 = GPS_numSat;  // Number of Satalits alias Temp1

      sendDataHead(ID_Temprature1);
      write_FrSky16(Datas_Temprature1);
   }

   // RPM
   void send_RPM(void)
   {
      uint16_t Datas_RPM = 0;      
      for (uint8_t i=0;i<NUMBER_MOTOR;i++)
      {
         Datas_RPM += motor[i];
      }
      Datas_RPM = (Datas_RPM / NUMBER_MOTOR) / 30;   // RPM

      sendDataHead(ID_RPM);
      write_FrSky16(Datas_RPM);
   }

   // Fuel level
   void send_Fuel_level(void)
   {
      uint16_t Datas_Fuel_level;

      Datas_Fuel_level = 0;

      sendDataHead(ID_Fuel_level);
      write_FrSky16(Datas_Fuel_level);
   }

   // Temperature 2
   void send_Temperature2(void)
   {
      if (f.GPS_FIX_HOME)
      {
         int16_t Datas_Temprature2;

         Datas_Temprature2 = GPS_distanceToHome; // Distance to home alias Temp2

         sendDataHead(ID_Temprature2);
         write_FrSky16(Datas_Temprature2); 
      }      
   }

   // Cell voltage  todo !!!!!!!!!!!!!!!!!!
   void send_Cell_volt(void) // Datas FrSky FLVS-01 voltage sensor
   {
      uint16_t Datas_Volt;
      uint8_t number_of_cells = 0;   // LiPo 3S = 3; LiPo 4S = 4 ...
      static uint8_t cell = 0;
      if (cell >= number_of_cells); cell = 0;
      
      Datas_Volt = 0; // 0.01v / 0 ~ 4.2v

      sendDataHead(ID_Volt);
      write_FrSky16(Datas_Volt);
   }

   // Altitude
   void send_Altitude(void)
   {
      uint16_t Datas_altitude_bp;
      uint16_t Datas_altitude_ap;
      static uint16_t Start_altitude;

      if (!f.ARMED)
      {
         Start_altitude = EstAlt / 100;
      }

      Datas_altitude_bp = (EstAlt / 100) - Start_altitude;
      Datas_altitude_ap = (EstAlt % 100);

      sendDataHead(ID_Altitude_bp);
      write_FrSky16(Datas_altitude_bp);
      sendDataHead(ID_Altitude_ap);
      write_FrSky16(Datas_altitude_ap);
   }

   // GPS speed
   void send_GPS_speed(void)
   {
      if (f.GPS_FIX && GPS_numSat >= 4)
      {            
         uint16_t Datas_GPS_speed_bp;
         uint16_t Datas_GPS_speed_ap;
         
         Datas_GPS_speed_bp = GPS_speed * 0.036;
         Datas_GPS_speed_ap = 0;
      
         sendDataHead(ID_GPS_speed_bp);
         write_FrSky16(Datas_GPS_speed_bp);
         sendDataHead(ID_GPS_speed_ap);
         write_FrSky16(Datas_GPS_speed_ap);
      }
   }

   // GPS position
   void send_GPS_position(void)
   {
   
         uint16_t Datas_Longitude_bp;
         uint16_t Datas_Longitude_ap;
         uint16_t Datas_E_W;
         uint16_t Datas_Latitude_bp;
         uint16_t Datas_Latitude_ap;
         uint16_t Datas_N_S;
         Datas_Longitude_bp = abs(GPS_coord[LON]) / 100000;
         Datas_Longitude_ap = abs((GPS_coord[LON])/10)  % 10000;
         Datas_E_W = GPS_coord[LON] < 0 ? 'W' : 'E';
         Datas_Latitude_bp = abs(GPS_coord[LAT]) / 100000;
         Datas_Latitude_ap = abs((GPS_coord[LAT])/10) % 10000;
         Datas_N_S = GPS_coord[LAT] < 0 ? 'S' : 'N';

         sendDataHead(ID_Longitude_bp);
         write_FrSky16(Datas_Longitude_bp);
         sendDataHead(ID_Longitude_ap);
         write_FrSky16(Datas_Longitude_ap);
         sendDataHead(ID_E_W);
         write_FrSky16(Datas_E_W);

         sendDataHead(ID_Latitude_bp);
         write_FrSky16(Datas_Latitude_bp);
         sendDataHead(ID_Latitude_ap);
         write_FrSky16(Datas_Latitude_ap);
         sendDataHead(ID_N_S);
         write_FrSky16(Datas_N_S);
      
   }

   // Course
   void send_Course(void)
   {
      uint16_t Datas_Course_bp;
      uint16_t Datas_Course_ap;

      Datas_Course_bp = heading;
      Datas_Course_ap = 0;

      sendDataHead(ID_Course_bp);
      write_FrSky16(Datas_Course_bp);
      sendDataHead(ID_Course_ap);
      write_FrSky16(Datas_Course_ap);
   }

   // Time
   void send_Time(void)
   {
      uint32_t seconds_since_start = millis() / 1000;
            
      uint16_t Datas_Date_month;
      uint16_t Datas_Year;
      uint16_t Datas_Minutes_hours;
      uint16_t Datas_seconds;
            
      Datas_Date_month = 0;
      Datas_Year = 12;
      Datas_Minutes_hours = (seconds_since_start / 60) % 60;
      Datas_seconds = seconds_since_start % 60;      
      
      sendDataHead(ID_Hour_Minute);
      write_FrSky16(Datas_Minutes_hours);
      sendDataHead(ID_Second);
      write_FrSky16(Datas_seconds);
   }

   // ACC
   void send_Accel(void)
   {
      int16_t Datas_Acc_X;
      int16_t Datas_Acc_Y;
      int16_t Datas_Acc_Z;

      Datas_Acc_X = ((float)accSmooth[0] / acc_1G) * 1000;
      Datas_Acc_Y = ((float)accSmooth[1] / acc_1G) * 1000;
      Datas_Acc_Z = ((float)accSmooth[2] / acc_1G) * 1000;

      sendDataHead(ID_Acc_X);
      write_FrSky16(Datas_Acc_X);
      sendDataHead(ID_Acc_Y);
      write_FrSky16(Datas_Acc_Y);
      sendDataHead(ID_Acc_Z);
      write_FrSky16(Datas_Acc_Z);      
   }

   // Voltage (Ampere Sensor) 
   void send_Voltage_ampere(void)
   {
   
      #if defined (FAS_100)   // todo   !!!!!!!!!!!!!!!!!
      {
         uint16_t Datas_Voltage_Amp_bp;
         uint16_t Datas_Voltage_Amp_ap;
         uint16_t Datas_Current;   

         Datas_Voltage_Amp_bp = 0;
         Datas_Voltage_Amp_ap = 0;   
         Datas_Current = 0;

         sendDataHead(ID_Voltage_Amp_bp);
         write_FrSky16(Datas_Voltage_Amp_bp);
         sendDataHead(ID_Voltage_Amp_ap);
         write_FrSky16(Datas_Voltage_Amp_ap);   
         sendDataHead(ID_Current);
         write_FrSky16(Datas_Current);
      }
      #else   // use vBat
      {
         uint16_t Datas_Voltage_vBat_bp;
         uint16_t Datas_Voltage_vBat_ap;   
         uint16_t voltage;
         voltage = (vbat * 110) / 21;          
         Datas_Voltage_vBat_bp = voltage / 100;
         Datas_Voltage_vBat_ap = ((voltage % 100) + 5) / 10;         

         sendDataHead(ID_Voltage_Amp_bp);
         write_FrSky16(Datas_Voltage_vBat_bp);
         sendDataHead(ID_Voltage_Amp_ap);
         write_FrSky16(Datas_Voltage_vBat_ap);   
      }
      #endif
   }

 #endif


mahowik
Posts: 332
Joined: Sun Apr 10, 2011 6:26 pm

Re: Direct Frsky telemtry data from MW FC

Post by mahowik »

tobi86 wrote:I'm not sure, if I understood the byte stuffing method correctly, if not, can anyone explain me how it works???


Yes, it's correct. It gives possibility:
1) to pass 0x5E as data (not as header) with replacing it to 0x5D 0x3E
2) to pass 0x5D as data (with replacing it to 0x5D 0x3D) because 0x5D discarded/ignored on RX side...

Where on RX side second byte is decoded via XORing with 0x60:
1) 0x3E XOR 0x60 = 0x5E
2) 0x3D XOR 0x60 = 0x5D

thx-
Alex

User avatar
dramida
Posts: 473
Joined: Mon Feb 28, 2011 12:58 pm
Location: Bucharest
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by dramida »

Alexinparis wrote:My dream would be a uplink telemetry based on frsky without impacting the 8 first RC channels.

Dreams are closer than we think they are:
OpenLRS tx- rx semi-duplex transmitter- receiver sistem based on RFM22B transciever is an arduino open source project witch allows to customize the data frame for bi-directional communication over RC link. The latest implementation on 433/470 Mhz (thanks to Thunded) has more than 4 Km ground range tested by many users .
Implementing RFM22B on a mega board (already did it Melih from flytron) would boost the potential of multiwii autonomous flight with waypoint navi.
ps.
price of RFM22B transciever is about 4 USD

links to OLRS http://flytron.com/16-openlrs

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

Please can someone clear me the inverter type what buy thanks

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

OK will be this code in Multiwii ? looking to 2.1 and no code is there. Thanks

wilco1967
Posts: 156
Joined: Thu Aug 18, 2011 6:04 pm
Location: Winterswijk, Netherlands

Re: Direct Frsky telemtry data from MW FC

Post by wilco1967 »

janekx wrote:Please can someone clear me the inverter type what buy thanks


You can make a simple inverter with a ordinary NPN transistor and 2 resistors..... see my post on the previous page....
If you don't want to order a 0.05 $ transistor, and pay 5 $ for postage, you could probably find a working transistor if you open up some old electronic device, and do a bit of googling on the type numbers to find one that is a NPN transistor.....
see this link for some explanation (bottom of the page)
http://www.kpsec.freeuk.com/trancirc.htm

The code is not (yet ?) contained in 2.1.... but you can simply add it yourselve, as explained earlier in this thread.

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

Thanks I ordered a few days ago Serial Port Mini RS232 to TTL Converter Adaptor Module Board MAX3232 115200bps http://www.ebay.com/itm/251103811631?ss ... 1439.l2649

Is the code still compatible with 2.1?

Yes is I looked at first page there is 2_0 and 3th page shows 2_1, why is not this realtivly simple addon in main trunk?

Sebbi
Posts: 478
Joined: Sun Jul 08, 2012 1:08 am
Location: Germany
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by Sebbi »

It's not 2.1 compatible ... or at least not compatible with the current _shared branch. I haven't tested it yet, but my changes so the code compiles again were:

FrSkyTelemtry.ino (write_FrSky8 just uses SerialWrite() now):

Code: Select all

// ****************************************************************
// FrSky telemetry
// Version: 0.2.1
// Date 20/09/2012
// Changes: V0.2.1: - make it work with 2.1 (shared dev)
// Date: 14/08/2012
// Changes: V0.2: - Byte stuffing added
//                - vBat will be send, if "#define FAS_100" is comment out
//                V0.1: - First release
// ****************************************************************

#if defined(TELEMETRY_FRSKY)
  // user defines
  //#define FAS_100  //if commment out, MultiWii vBat voltage will be send instead of FrSky FAS 100 voltage


  // Serial config datas
  #define TELEMETRY_FRSKY_SERIAL 1
  #define TELEMETRY_FRSKY_BAUD 9600 

  // Timing
  #define Time_telemetry_send 125000
  static uint8_t cycleCounter = 0;
  static uint32_t FrSkyTime  = 0;

  // Frame protocol
  #define Protocol_Header   0x5E
  #define Protocol_Tail      0x5E
 
 
  // Data Ids  (bp = before point; af = after point)
  // Official data IDs
  #define ID_GPS_altidute_bp    0x01
  #define ID_GPS_altidute_ap    0x09
  #define ID_Temprature1        0x02
  #define ID_RPM                0x03
  #define ID_Fuel_level         0x04
  #define ID_Temprature2        0x05
  #define ID_Volt               0x06
  #define ID_Altitude_bp        0x10
  #define ID_Altitude_ap        0x21
  #define ID_GPS_speed_bp       0x11
  #define ID_GPS_speed_ap       0x19
  #define ID_Longitude_bp       0x12
  #define ID_Longitude_ap       0x1A
  #define ID_E_W                0x22
  #define ID_Latitude_bp        0x13
  #define ID_Latitude_ap        0x1B
  #define ID_N_S                0x23
  #define ID_Course_bp          0x14
  #define ID_Course_ap          0x24
  #define ID_Date_Month         0x15
  #define ID_Year               0x16
  #define ID_Hour_Minute        0x17
  #define ID_Second             0x18
  #define ID_Acc_X              0x24
  #define ID_Acc_Y              0x25
  #define ID_Acc_Z              0x26
  #define ID_Voltage_Amp_bp     0x3A
  #define ID_Voltage_Amp_ap     0x3B
  #define ID_Current            0x28
  // User defined data IDs
  #define ID_Gyro_X             0x40
  #define ID_Gyro_Y             0x41
  #define ID_Gyro_Z             0x42

   // Main function FrSky telemetry
    void telemetry_frsky()
   {         
      if (currentTime > FrSkyTime ) //
      {         
         FrSkyTime = currentTime + Time_telemetry_send;
         cycleCounter++;
         // Datas sent every 125 ms
            send_Accel();
            sendDataTail();   

         if ((cycleCounter % 4) == 0)
         {     
            // Datas sent every 500ms
            send_Altitude();
            send_RPM();
            send_Course();
            send_GPS_speed();
            //send_Cell_volt();       todo
            sendDataTail();   

         }
         if ((cycleCounter % 8) == 0)
         {     
            // Datas sent every 1s           
            //send_Time();
            send_GPS_position();
            send_GPS_altitude();
            send_Temperature2();  // Distance_to_home
            //send_Fuel_level();
            send_Voltage_ampere();
            send_Temperature1();  // num of Sats
            sendDataTail();           
         }

         if (cycleCounter == 40)
         {
            // Datas sent every 5s
            cycleCounter = 0;       
         }
      }
   }

   void write_FrSky8(uint8_t Data)
   {
      SerialWrite(TELEMETRY_FRSKY_SERIAL, Data);
   }

   void write_FrSky16(uint16_t Data)
   {
      uint8_t Data_send;
      Data_send = Data;     
      check_FrSky_stuffing(Data_send);
      Data_send = Data >> 8 & 0xff;
      check_FrSky_stuffing(Data_send);
   }
   
   void check_FrSky_stuffing(uint8_t Data) //byte stuffing
   {
      if (Data == 0x5E)   
      {
         write_FrSky8(0x5D);
         write_FrSky8(0x3E);
      }
      else if (Data == 0x5D)   
      {
         write_FrSky8(0x5D);
         write_FrSky8(0x3D);
      }
      else
      {
         write_FrSky8(Data);         
      }
   }

   static void sendDataHead(uint8_t Data_id)
   {
      write_FrSky8(Protocol_Header);
      write_FrSky8(Data_id);
   }

   static void sendDataTail(void)
   {
      write_FrSky8(Protocol_Tail);     
   }


   //*********************************************************************************
   //-----------------   Telemetrie Datas   ------------------------------------------   
   //*********************************************************************************

   // GPS altitude
   void send_GPS_altitude(void)
   {         
      if (f.GPS_FIX && GPS_numSat >= 4)
      {
         int16_t Datas_GPS_altidute_bp;
         uint16_t Datas_GPS_altidute_ap;

         Datas_GPS_altidute_bp = GPS_altitude;
         Datas_GPS_altidute_ap = 0;

         sendDataHead(ID_GPS_altidute_bp);
         write_FrSky16(Datas_GPS_altidute_bp);
         sendDataHead(ID_GPS_altidute_ap);
         write_FrSky16(Datas_GPS_altidute_ap);
      }
   }
   
   // Temperature
   void send_Temperature1(void)
   {
      int16_t Datas_Temprature1;

      Datas_Temprature1 = GPS_numSat;  // Number of Satalits alias Temp1

      sendDataHead(ID_Temprature1);
      write_FrSky16(Datas_Temprature1);
   }

   // RPM
   void send_RPM(void)
   {
      uint16_t Datas_RPM = 0;     
      for (uint8_t i=0;i<NUMBER_MOTOR;i++)
      {
         Datas_RPM += motor[i];
      }
      Datas_RPM = (Datas_RPM / NUMBER_MOTOR) / 30;   // RPM

      sendDataHead(ID_RPM);
      write_FrSky16(Datas_RPM);
   }

   // Fuel level
   void send_Fuel_level(void)
   {
      uint16_t Datas_Fuel_level;

      Datas_Fuel_level = 0;

      sendDataHead(ID_Fuel_level);
      write_FrSky16(Datas_Fuel_level);
   }

   // Temperature 2
   void send_Temperature2(void)
   {
      if (f.GPS_FIX_HOME)
      {
         int16_t Datas_Temprature2;

         Datas_Temprature2 = GPS_distanceToHome; // Distance to home alias Temp2

         sendDataHead(ID_Temprature2);
         write_FrSky16(Datas_Temprature2); 
      }     
   }

   // Cell voltage  todo !!!!!!!!!!!!!!!!!!
   void send_Cell_volt(void) // Datas FrSky FLVS-01 voltage sensor
   {
      uint16_t Datas_Volt;
      uint8_t number_of_cells = 0;   // LiPo 3S = 3; LiPo 4S = 4 ...
      static uint8_t cell = 0;
      if (cell >= number_of_cells); cell = 0;
     
      Datas_Volt = 0; // 0.01v / 0 ~ 4.2v

      sendDataHead(ID_Volt);
      write_FrSky16(Datas_Volt);
   }

   // Altitude
   void send_Altitude(void)
   {
      uint16_t Datas_altitude_bp;
      uint16_t Datas_altitude_ap;
      static uint16_t Start_altitude;

      if (!f.ARMED)
      {
         Start_altitude = EstAlt / 100;
      }

      Datas_altitude_bp = (EstAlt / 100) - Start_altitude;
      Datas_altitude_ap = (EstAlt % 100);

      sendDataHead(ID_Altitude_bp);
      write_FrSky16(Datas_altitude_bp);
      sendDataHead(ID_Altitude_ap);
      write_FrSky16(Datas_altitude_ap);
   }

   // GPS speed
   void send_GPS_speed(void)
   {
      if (f.GPS_FIX && GPS_numSat >= 4)
      {           
         uint16_t Datas_GPS_speed_bp;
         uint16_t Datas_GPS_speed_ap;
         
         Datas_GPS_speed_bp = GPS_speed * 0.036;
         Datas_GPS_speed_ap = 0;
     
         sendDataHead(ID_GPS_speed_bp);
         write_FrSky16(Datas_GPS_speed_bp);
         sendDataHead(ID_GPS_speed_ap);
         write_FrSky16(Datas_GPS_speed_ap);
      }
   }

   // GPS position
   void send_GPS_position(void)
   {
   
         uint16_t Datas_Longitude_bp;
         uint16_t Datas_Longitude_ap;
         uint16_t Datas_E_W;
         uint16_t Datas_Latitude_bp;
         uint16_t Datas_Latitude_ap;
         uint16_t Datas_N_S;
         Datas_Longitude_bp = abs(GPS_coord[LON]) / 100000;
         Datas_Longitude_ap = abs((GPS_coord[LON])/10)  % 10000;
         Datas_E_W = GPS_coord[LON] < 0 ? 'W' : 'E';
         Datas_Latitude_bp = abs(GPS_coord[LAT]) / 100000;
         Datas_Latitude_ap = abs((GPS_coord[LAT])/10) % 10000;
         Datas_N_S = GPS_coord[LAT] < 0 ? 'S' : 'N';

         sendDataHead(ID_Longitude_bp);
         write_FrSky16(Datas_Longitude_bp);
         sendDataHead(ID_Longitude_ap);
         write_FrSky16(Datas_Longitude_ap);
         sendDataHead(ID_E_W);
         write_FrSky16(Datas_E_W);

         sendDataHead(ID_Latitude_bp);
         write_FrSky16(Datas_Latitude_bp);
         sendDataHead(ID_Latitude_ap);
         write_FrSky16(Datas_Latitude_ap);
         sendDataHead(ID_N_S);
         write_FrSky16(Datas_N_S);
     
   }

   // Course
   void send_Course(void)
   {
      uint16_t Datas_Course_bp;
      uint16_t Datas_Course_ap;

      Datas_Course_bp = heading;
      Datas_Course_ap = 0;

      sendDataHead(ID_Course_bp);
      write_FrSky16(Datas_Course_bp);
      sendDataHead(ID_Course_ap);
      write_FrSky16(Datas_Course_ap);
   }

   // Time
   void send_Time(void)
   {
      uint32_t seconds_since_start = millis() / 1000;
           
      uint16_t Datas_Date_month;
      uint16_t Datas_Year;
      uint16_t Datas_Minutes_hours;
      uint16_t Datas_seconds;
           
      Datas_Date_month = 0;
      Datas_Year = 12;
      Datas_Minutes_hours = (seconds_since_start / 60) % 60;
      Datas_seconds = seconds_since_start % 60;     
     
      sendDataHead(ID_Hour_Minute);
      write_FrSky16(Datas_Minutes_hours);
      sendDataHead(ID_Second);
      write_FrSky16(Datas_seconds);
   }

   // ACC
   void send_Accel(void)
   {
      int16_t Datas_Acc_X;
      int16_t Datas_Acc_Y;
      int16_t Datas_Acc_Z;

      Datas_Acc_X = ((float)accSmooth[0] / acc_1G) * 1000;
      Datas_Acc_Y = ((float)accSmooth[1] / acc_1G) * 1000;
      Datas_Acc_Z = ((float)accSmooth[2] / acc_1G) * 1000;

      sendDataHead(ID_Acc_X);
      write_FrSky16(Datas_Acc_X);
      sendDataHead(ID_Acc_Y);
      write_FrSky16(Datas_Acc_Y);
      sendDataHead(ID_Acc_Z);
      write_FrSky16(Datas_Acc_Z);     
   }

   // Voltage (Ampere Sensor) 
   void send_Voltage_ampere(void)
   {
   
      #if defined (FAS_100)   // todo   !!!!!!!!!!!!!!!!!
      {
         uint16_t Datas_Voltage_Amp_bp;
         uint16_t Datas_Voltage_Amp_ap;
         uint16_t Datas_Current;   

         Datas_Voltage_Amp_bp = 0;
         Datas_Voltage_Amp_ap = 0;   
         Datas_Current = 0;

         sendDataHead(ID_Voltage_Amp_bp);
         write_FrSky16(Datas_Voltage_Amp_bp);
         sendDataHead(ID_Voltage_Amp_ap);
         write_FrSky16(Datas_Voltage_Amp_ap);   
         sendDataHead(ID_Current);
         write_FrSky16(Datas_Current);
      }
      #else   // use vBat
      {
         uint16_t Datas_Voltage_vBat_bp;
         uint16_t Datas_Voltage_vBat_ap;   
         uint16_t voltage;
         voltage = (vbat * 110) / 21;         
         Datas_Voltage_vBat_bp = voltage / 100;
         Datas_Voltage_vBat_ap = ((voltage % 100) + 5) / 10;         

         sendDataHead(ID_Voltage_Amp_bp);
         write_FrSky16(Datas_Voltage_vBat_bp);
         sendDataHead(ID_Voltage_Amp_ap);
         write_FrSky16(Datas_Voltage_vBat_ap);   
      }
      #endif
   }

#endif


Init isn't needed anymore, but you need to place this somewhere in the annexCode() function:

Code: Select all

  #if defined(TELEMETRY_FRSKY) // new
   telemetry_frsky();
  #endif


Last, but not least in config.h ... add/change:

Code: Select all

#define TELEMETRY_FRSKY

    #define SERIAL0_COM_SPEED 115200
    #define SERIAL1_COM_SPEED 9600 // it's on serial 1 for me ... so set this to 9600 baud
    #define SERIAL2_COM_SPEED 115200
    #define SERIAL3_COM_SPEED 115200


That's it ... most of the functions in FrSkyTelemetry.ino don't send useful information yet. Feel free to change that ... I'd like to see a more complete version of this included in MultiWii ;-)

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

Thanks I am affraid will be able make some changes I program more then 10y ago in C++ and only basics.

martinito
Posts: 7
Joined: Fri Jun 15, 2012 6:18 pm

Re: Direct Frsky telemtry data from MW FC

Post by martinito »

Hi all,

Although it is probably slightly slower, Software serial might be an interresting option:
[*] Since Arduino 1.0 software serial supports inverted signaling (info http://arduino.cc/en/Reference/SoftwareSerial)
[*] Since we are only writing but not reading, we can probably save some extra time.

Has anybody tried this?

Some other thoughts for non-mega boards: we could add a co-processor reading interface data from the serial port and translating it to the Frsky module.

What are your opinions?

Cheers

User avatar
IceWind
Posts: 115
Joined: Fri Mar 25, 2011 2:11 am
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by IceWind »

I have it all working fine with a promini.
What I've done is to change the code to only send the FrSky data when the FC is armed. That way I avoid using a software port and I keep
the serial port for Mwc configuration when disarmed.

Only drawback is that Mwc serial had to be slowed down to 9600 but I'll change that as well.

martinito
Posts: 7
Joined: Fri Jun 15, 2012 6:18 pm

Re: Direct Frsky telemtry data from MW FC

Post by martinito »

Hi IceWind, this sounds like a good solution :-)
When you get the chance, could you please post your code?

Cheers,
Martin

User avatar
IceWind
Posts: 115
Joined: Fri Mar 25, 2011 2:11 am
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by IceWind »

Sure, if you're hosting this somewhere I won't mind committing the changes for approval.

Main .ino file in the end of the annexCode()

Code: Select all

  
  #if defined(TELEMETRY_FRSKY)
   if (f.ARMED) { 
     telemetry_frsky();
   }
  #endif


(It only starts sending when armed, It also allows to know when the FC is armed as the FrSky telemetry data starts to populate right away.)

In the FrSkyTelemetry.ino I added the following to make the setting of the port more automatic. (would be best to move to the config file
for the ones that have a MEGA board and want to select the precise serial port)

Code: Select all

// Serial config datas
  #if defined(MEGA)
    #define TELEMETRY_FRSKY_SERIAL 1
  #else
    #define TELEMETRY_FRSKY_SERIAL 0
  #endif
  #define TELEMETRY_FRSKY_BAUD 9600


Like I said I'll now update the main code so that it swaps from 115200 <> 9600 so the Mwc UI apps aren't affected.
(I want to keep using my own android app. :) )

Sebbi
Posts: 478
Joined: Sun Jul 08, 2012 1:08 am
Location: Germany
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by Sebbi »

martinito wrote:Hi all,

Although it is probably slightly slower, Software serial might be an interresting option:
[*] Since Arduino 1.0 software serial supports inverted signaling (info http://arduino.cc/en/Reference/SoftwareSerial)
[*] Since we are only writing but not reading, we can probably save some extra time.

Has anybody tried this?

Some other thoughts for non-mega boards: we could add a co-processor reading interface data from the serial port and translating it to the Frsky module.

What are your opinions?

Cheers


I have tried SoftwareSerial ... it adds about 2500 bytes to the binary, so if you have enough bytes left that would work. You'll also wont need any kind of hardware between the used bin and the FrSky RX as inverted logic is supported.

However, the write-function is blocking. This means that the cycle time will increase ... if you have no problem with that, I guess it's doable.

In my case - I have a Leonardo - I access the GUI via the USB-port, will use a I2C-GPS and have the FrSky on serial1 ...

P.S.: You could possibly save some bytes if you reimplement SoftwareSerial (basically write your own function that outputs a byte at 9600 baud inverted on a pin). You could also use a timer interrupt and do it in a none blocking way (it will still use the same amount of cpu cycles, but evenly spread out instead of huge junks every time data needs to be sent).

P.P.S.: You can use a 9600 baud GPS and FrSky telemetry on the same serial port, btw ;-)

martinito
Posts: 7
Joined: Fri Jun 15, 2012 6:18 pm

Re: Direct Frsky telemtry data from MW FC

Post by martinito »

Hello Sebi & IceWind,

Thanks for your inputs.

I'll first strip the SoftwareSerial library to reduce
1. remove all un-necessary code (the entire RX part)
2. Hard-code the 9600 baud and 'inverse_logic' to avoid un-necessary tests and variables
This should work without too many problems.

I'll then (try to) re-engineer the SoftwareSerial::write function to use timers instead of the tunedDelay() function.
This way we should be able to replace the serial write.
For the sake of compatibility I'm thinking about keeping empty functions (e.g. to set the baud rate) to keep the code easy integrate.

What do you think?

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

Hi,
I tryed the telemetry code and converter but looks that not recieve data.
From Crius AIOP use TX3 to TTL side of converter TX (arrow in) and power it with +5V on side RS232 I use only GND and TX (Arrow out) to reciever GND and Rx

IMG_4918.jpg


In 1143 build I have

Code: Select all

/******                Serial com speed    *********************************/
    /* This is the speed of the serial interfaces */
    #define SERIAL0_COM_SPEED 115200
    #define SERIAL1_COM_SPEED 115200
    #define SERIAL2_COM_SPEED 115200
    #define SERIAL3_COM_SPEED 9600 //telemetry
   
    #define TELEMETRY_FRSKY
   


in Multiwii void annexCode() before end } of this function

Code: Select all

 
    #if defined(TELEMETRY_FRSKY) // new
   telemetry_frsky();
  #endif



and Frskytelemetry

Code: Select all

// ****************************************************************
// FrSky telemetry
// Version: 0.2.1
// Date 20/09/2012
// Changes: V0.2.1: - make it work with 2.1 (shared dev)
// Date: 14/08/2012
// Changes: V0.2: - Byte stuffing added
//                - vBat will be send, if "#define FAS_100" is comment out
//                V0.1: - First release
// ****************************************************************

#if defined(TELEMETRY_FRSKY)
  // user defines
  //#define FAS_100  //if commment out, MultiWii vBat voltage will be send instead of FrSky FAS 100 voltage


  // Serial config datas
  #define TELEMETRY_FRSKY_SERIAL 3
  #define TELEMETRY_FRSKY_BAUD 9600 

  // Timing
  #define Time_telemetry_send 125000
  static uint8_t cycleCounter = 0;
  static uint32_t FrSkyTime  = 0;

  // Frame protocol
  #define Protocol_Header   0x5E
  #define Protocol_Tail      0x5E
 
 
  // Data Ids  (bp = before point; af = after point)
  // Official data IDs
  #define ID_GPS_altidute_bp    0x01
  #define ID_GPS_altidute_ap    0x09
  #define ID_Temprature1        0x02
  #define ID_RPM                0x03
  #define ID_Fuel_level         0x04
  #define ID_Temprature2        0x05
  #define ID_Volt               0x06
  #define ID_Altitude_bp        0x10
  #define ID_Altitude_ap        0x21
  #define ID_GPS_speed_bp       0x11
  #define ID_GPS_speed_ap       0x19
  #define ID_Longitude_bp       0x12
  #define ID_Longitude_ap       0x1A
  #define ID_E_W                0x22
  #define ID_Latitude_bp        0x13
  #define ID_Latitude_ap        0x1B
  #define ID_N_S                0x23
  #define ID_Course_bp          0x14
  #define ID_Course_ap          0x24
  #define ID_Date_Month         0x15
  #define ID_Year               0x16
  #define ID_Hour_Minute        0x17
  #define ID_Second             0x18
  #define ID_Acc_X              0x24
  #define ID_Acc_Y              0x25
  #define ID_Acc_Z              0x26
  #define ID_Voltage_Amp_bp     0x3A
  #define ID_Voltage_Amp_ap     0x3B
  #define ID_Current            0x28
  // User defined data IDs
  #define ID_Gyro_X             0x40
  #define ID_Gyro_Y             0x41
  #define ID_Gyro_Z             0x42

   // Main function FrSky telemetry
    void telemetry_frsky()
   {         
      if (currentTime > FrSkyTime ) //
      {         
         FrSkyTime = currentTime + Time_telemetry_send;
         cycleCounter++;
         // Datas sent every 125 ms
            send_Accel();
            sendDataTail();   

         if ((cycleCounter % 4) == 0)
         {     
            // Datas sent every 500ms
            send_Altitude();
            send_RPM();
            send_Course();
            send_GPS_speed();
            //send_Cell_volt();       todo
            sendDataTail();   

         }
         if ((cycleCounter % 8) == 0)
         {     
            // Datas sent every 1s           
            //send_Time();
            send_GPS_position();
            send_GPS_altitude();
            send_Temperature2();  // Distance_to_home
            //send_Fuel_level();
            send_Voltage_ampere();
            send_Temperature1();  // num of Sats
            sendDataTail();           
         }

         if (cycleCounter == 40)
         {
            // Datas sent every 5s
            cycleCounter = 0;       
         }
      }
   }

   void write_FrSky8(uint8_t Data)
   {
      SerialWrite(TELEMETRY_FRSKY_SERIAL, Data);
   }

   void write_FrSky16(uint16_t Data)
   {
      uint8_t Data_send;
      Data_send = Data;     
      check_FrSky_stuffing(Data_send);
      Data_send = Data >> 8 & 0xff;
      check_FrSky_stuffing(Data_send);
   }
   
   void check_FrSky_stuffing(uint8_t Data) //byte stuffing
   {
      if (Data == 0x5E)   
      {
         write_FrSky8(0x5D);
         write_FrSky8(0x3E);
      }
      else if (Data == 0x5D)   
      {
         write_FrSky8(0x5D);
         write_FrSky8(0x3D);
      }
      else
      {
         write_FrSky8(Data);         
      }
   }

   static void sendDataHead(uint8_t Data_id)
   {
      write_FrSky8(Protocol_Header);
      write_FrSky8(Data_id);
   }

   static void sendDataTail(void)
   {
      write_FrSky8(Protocol_Tail);     
   }


   //*********************************************************************************
   //-----------------   Telemetrie Datas   ------------------------------------------   
   //*********************************************************************************

   // GPS altitude
   void send_GPS_altitude(void)
   {         
      if (f.GPS_FIX && GPS_numSat >= 4)
      {
         int16_t Datas_GPS_altidute_bp;
         uint16_t Datas_GPS_altidute_ap;

         Datas_GPS_altidute_bp = GPS_altitude;
         Datas_GPS_altidute_ap = 0;

         sendDataHead(ID_GPS_altidute_bp);
         write_FrSky16(Datas_GPS_altidute_bp);
         sendDataHead(ID_GPS_altidute_ap);
         write_FrSky16(Datas_GPS_altidute_ap);
      }
   }
   
   // Temperature
   void send_Temperature1(void)
   {
      int16_t Datas_Temprature1;

      Datas_Temprature1 = GPS_numSat;  // Number of Satalits alias Temp1

      sendDataHead(ID_Temprature1);
      write_FrSky16(Datas_Temprature1);
   }

   // RPM
   void send_RPM(void)
   {
      uint16_t Datas_RPM = 0;     
      for (uint8_t i=0;i<NUMBER_MOTOR;i++)
      {
         Datas_RPM += motor[i];
      }
      Datas_RPM = (Datas_RPM / NUMBER_MOTOR) / 30;   // RPM

      sendDataHead(ID_RPM);
      write_FrSky16(Datas_RPM);
   }

   // Fuel level
   void send_Fuel_level(void)
   {
      uint16_t Datas_Fuel_level;

      Datas_Fuel_level = 0;

      sendDataHead(ID_Fuel_level);
      write_FrSky16(Datas_Fuel_level);
   }

   // Temperature 2
   void send_Temperature2(void)
   {
      if (f.GPS_FIX_HOME)
      {
         int16_t Datas_Temprature2;

         Datas_Temprature2 = GPS_distanceToHome; // Distance to home alias Temp2

         sendDataHead(ID_Temprature2);
         write_FrSky16(Datas_Temprature2); 
      }     
   }

   // Cell voltage  todo !!!!!!!!!!!!!!!!!!
   void send_Cell_volt(void) // Datas FrSky FLVS-01 voltage sensor
   {
      uint16_t Datas_Volt;
      uint8_t number_of_cells = 0;   // LiPo 3S = 3; LiPo 4S = 4 ...
      static uint8_t cell = 0;
      if (cell >= number_of_cells); cell = 0;
     
      Datas_Volt = 0; // 0.01v / 0 ~ 4.2v

      sendDataHead(ID_Volt);
      write_FrSky16(Datas_Volt);
   }

   // Altitude
   void send_Altitude(void)
   {
      uint16_t Datas_altitude_bp;
      uint16_t Datas_altitude_ap;
      static uint16_t Start_altitude;

      if (!f.ARMED)
      {
         Start_altitude = EstAlt / 100;
      }

      Datas_altitude_bp = (EstAlt / 100) - Start_altitude;
      Datas_altitude_ap = (EstAlt % 100);

      sendDataHead(ID_Altitude_bp);
      write_FrSky16(Datas_altitude_bp);
      sendDataHead(ID_Altitude_ap);
      write_FrSky16(Datas_altitude_ap);
   }

   // GPS speed
   void send_GPS_speed(void)
   {
      if (f.GPS_FIX && GPS_numSat >= 4)
      {           
         uint16_t Datas_GPS_speed_bp;
         uint16_t Datas_GPS_speed_ap;
         
         Datas_GPS_speed_bp = GPS_speed * 0.036;
         Datas_GPS_speed_ap = 0;
     
         sendDataHead(ID_GPS_speed_bp);
         write_FrSky16(Datas_GPS_speed_bp);
         sendDataHead(ID_GPS_speed_ap);
         write_FrSky16(Datas_GPS_speed_ap);
      }
   }

   // GPS position
   void send_GPS_position(void)
   {
   
         uint16_t Datas_Longitude_bp;
         uint16_t Datas_Longitude_ap;
         uint16_t Datas_E_W;
         uint16_t Datas_Latitude_bp;
         uint16_t Datas_Latitude_ap;
         uint16_t Datas_N_S;
         Datas_Longitude_bp = abs(GPS_coord[LON]) / 100000;
         Datas_Longitude_ap = abs((GPS_coord[LON])/10)  % 10000;
         Datas_E_W = GPS_coord[LON] < 0 ? 'W' : 'E';
         Datas_Latitude_bp = abs(GPS_coord[LAT]) / 100000;
         Datas_Latitude_ap = abs((GPS_coord[LAT])/10) % 10000;
         Datas_N_S = GPS_coord[LAT] < 0 ? 'S' : 'N';

         sendDataHead(ID_Longitude_bp);
         write_FrSky16(Datas_Longitude_bp);
         sendDataHead(ID_Longitude_ap);
         write_FrSky16(Datas_Longitude_ap);
         sendDataHead(ID_E_W);
         write_FrSky16(Datas_E_W);

         sendDataHead(ID_Latitude_bp);
         write_FrSky16(Datas_Latitude_bp);
         sendDataHead(ID_Latitude_ap);
         write_FrSky16(Datas_Latitude_ap);
         sendDataHead(ID_N_S);
         write_FrSky16(Datas_N_S);
     
   }

   // Course
   void send_Course(void)
   {
      uint16_t Datas_Course_bp;
      uint16_t Datas_Course_ap;

      Datas_Course_bp = heading;
      Datas_Course_ap = 0;

      sendDataHead(ID_Course_bp);
      write_FrSky16(Datas_Course_bp);
      sendDataHead(ID_Course_ap);
      write_FrSky16(Datas_Course_ap);
   }

   // Time
   void send_Time(void)
   {
      uint32_t seconds_since_start = millis() / 1000;
           
      uint16_t Datas_Date_month;
      uint16_t Datas_Year;
      uint16_t Datas_Minutes_hours;
      uint16_t Datas_seconds;
           
      Datas_Date_month = 0;
      Datas_Year = 12;
      Datas_Minutes_hours = (seconds_since_start / 60) % 60;
      Datas_seconds = seconds_since_start % 60;     
     
      sendDataHead(ID_Hour_Minute);
      write_FrSky16(Datas_Minutes_hours);
      sendDataHead(ID_Second);
      write_FrSky16(Datas_seconds);
   }

   // ACC
   void send_Accel(void)
   {
      int16_t Datas_Acc_X;
      int16_t Datas_Acc_Y;
      int16_t Datas_Acc_Z;

      Datas_Acc_X = ((float)accSmooth[0] / acc_1G) * 1000;
      Datas_Acc_Y = ((float)accSmooth[1] / acc_1G) * 1000;
      Datas_Acc_Z = ((float)accSmooth[2] / acc_1G) * 1000;

      sendDataHead(ID_Acc_X);
      write_FrSky16(Datas_Acc_X);
      sendDataHead(ID_Acc_Y);
      write_FrSky16(Datas_Acc_Y);
      sendDataHead(ID_Acc_Z);
      write_FrSky16(Datas_Acc_Z);     
   }

   // Voltage (Ampere Sensor) 
   void send_Voltage_ampere(void)
   {
   
      #if defined (FAS_100)   // todo   !!!!!!!!!!!!!!!!!
      {
         uint16_t Datas_Voltage_Amp_bp;
         uint16_t Datas_Voltage_Amp_ap;
         uint16_t Datas_Current;   

         Datas_Voltage_Amp_bp = 0;
         Datas_Voltage_Amp_ap = 0;   
         Datas_Current = 0;

         sendDataHead(ID_Voltage_Amp_bp);
         write_FrSky16(Datas_Voltage_Amp_bp);
         sendDataHead(ID_Voltage_Amp_ap);
         write_FrSky16(Datas_Voltage_Amp_ap);   
         sendDataHead(ID_Current);
         write_FrSky16(Datas_Current);
      }
      #else   // use vBat
      {
         uint16_t Datas_Voltage_vBat_bp;
         uint16_t Datas_Voltage_vBat_ap;   
         uint16_t voltage;
         voltage = (vbat * 110) / 21;         
         Datas_Voltage_vBat_bp = voltage / 100;
         Datas_Voltage_vBat_ap = ((voltage % 100) + 5) / 10;         

         sendDataHead(ID_Voltage_Amp_bp);
         write_FrSky16(Datas_Voltage_vBat_bp);
         sendDataHead(ID_Voltage_Amp_ap);
         write_FrSky16(Datas_Voltage_vBat_ap);   
      }
      #endif
   }

#endif



I thing all is have right, but not get any data, for sure is Serial3 TX3 in Crius AIOP right?

Please some idea?

Thanks

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

Looks that ACC X/Y/Z values +-0.1 and around it transfer but not any alt baro and so, have not connecter GPS, I hoped that alt will catch from baro ....

Sebbi
Posts: 478
Joined: Sun Jul 08, 2012 1:08 am
Location: Germany
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by Sebbi »

janekx wrote:Looks that ACC X/Y/Z values +-0.1 and around it transfer but not any alt baro and so, have not connecter GPS, I hoped that alt will catch from baro ....


So it transfers something ... what hardware do you use on the receiving end? FrSky directly, the T9X or an Android/PC application?

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

Frsky DHT DIY module in T9x and open9x one from lattest source codes.

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

Alt start showing in armed only logicaly because count meters from armed position.

Sebbi
Posts: 478
Joined: Sun Jul 08, 2012 1:08 am
Location: Germany
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by Sebbi »

janekx wrote:Alt start showing in armed only logicaly because count meters from armed position.


So it does work, but the code obviously needs improvement to support all the functions of the protocol (and ammend it with yaw/pitch/roll angles).

Mis
Posts: 203
Joined: Fri Apr 01, 2011 12:23 am

Re: Direct Frsky telemtry data from MW FC

Post by Mis »

Interrupt driven software UART:
http://www.atmel.com/images/doc0941.pdf
http://www.atmel.com/Images/avr304.zip
This can be easly adapt and shrinked because (big) receive part is not needed. And you simple can send inverted data.
BUT IMHO the mega328p is at end of available resources, and this feature should be added only for mega1280 and mega2560 CPU's with lot of hardware uarts and codespace :-)

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

If will look on this mod in sum

What is working and todo

#define ID_GPS_altidute_bp 0x01 - yes
#define ID_GPS_altidute_ap 0x09 - yes
#define ID_Temprature1 0x02- no of satelites
#define ID_RPM 0x03 - yes
#define ID_Fuel_level 0x04 - need todo
#define ID_Temprature2 0x05 - GPS distance to home
#define ID_Volt 0x06 - todo FrSky FLVS-01 voltage sensor - cells voltage
#define ID_Altitude_bp 0x10 - yes
#define ID_Altitude_ap 0x21 - yes
#define ID_GPS_speed_bp 0x11 - yes
#define ID_GPS_speed_ap 0x19 - yes
#define ID_Longitude_bp 0x12 - yes
#define ID_Longitude_ap 0x1A - yes
#define ID_E_W 0x22 - yes
#define ID_Latitude_bp 0x13 - yes
#define ID_Latitude_ap 0x1B - yes
#define ID_N_S 0x23 - yes
#define ID_Course_bp 0x14 - yes
#define ID_Course_ap 0x24 - 0 need todo ???
#define ID_Date_Month 0x15 - neded ???
#define ID_Year 0x16 - needed ???
#define ID_Hour_Minute 0x17 - yes since start
#define ID_Second 0x18 - yes since start
#define ID_Acc_X 0x24 - yes Gs
#define ID_Acc_Y 0x25 - yes Gs
#define ID_Acc_Z 0x26 - yes Gs
#define ID_Voltage_Amp_bp 0x3A - yes - FAS_100 todo
#define ID_Voltage_Amp_ap 0x3B - yes -FAS_100 todo
#define ID_Current 0x28 - FAS_100 todo

I thing that this mod can be added to trunk because what is not working is
Fuel level
Volt of cells
Current

and less important
year
month and date


suggestions
alt and Galt in format 1.2m not only meters would be nice.

Sebbi
Posts: 478
Joined: Sun Jul 08, 2012 1:08 am
Location: Germany
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by Sebbi »

Shouldn't Temperature 1 & 2 be temperature values? Number of satellites is nice to know, but when is this needed and is it compatible with standard FrSky hardware?

Month/Year/Hour/Minute/Second normaly transmits the GPS time. Using it for armed time should be a compile option.

Voltage and Current can come from Vbat and Powermeter functions of MultiWii or am I missing something. My FrSky transmitter has an aditional analog input to measure one external voltage. What frame ID does this use? 0x06?

I am all for extending the protocol ;) I am trying to build a ground based OSD that gets drawn with the FrSky telemetry data ... so having pitch and roll in addition to course would be nice (they can be estimated from the acceleration, but hey). Also some of the states, like "armed", "gyro mode on", "angle mode on", etc ...

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

I thing we should use the datas from board then from some additional hardware no metter protocol Or we can use hub as before....
If someone will like use frsky current senzor, fuel and cells how to connect to board? Not enought ports even some are pass thrue and needs more integration, takes more memory ...

You mention OSD that will be perfect what hw it will use?

Sebbi
Posts: 478
Joined: Sun Jul 08, 2012 1:08 am
Location: Germany
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by Sebbi »

Current and voltage sensing only need two I/O ports on MultiWii side and is already integrated. No need to use FrSky sensors for that. I think MultiWii should emulate a complete sensor hub, maybe with the option to use software serial so no additional hardware (inverter circuit) is needed.

OSD: i am using an arduino and the MX7456 chip to display an OSD ... should work similar to Rushduino OSD, except parsing the MultiWii protocol, it will parse FrSky telemetry and works on the ground. I hope this enables me to still have control over the airplane/copter even if the videolink is lost (I don't know if video or rx signal will be the first to break up, yet *g*)

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

Interesting that fas100 can be chained to flvs01 and then to hub so will need only one I/O i2c port. And tx for data out to RX or OSD;)

Sebbi
Posts: 478
Joined: Sun Jul 08, 2012 1:08 am
Location: Germany
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by Sebbi »

janekx wrote:Interesting that fas100 can be chained to flvs01 and then to hub so will need only one I/O i2c port. And tx for data out to RX or OSD;)


Yeah, but I want to have my OSD on the groundstation not on the plane/copter ... I'll connect it to the FrSky module and receive the telemetry this way. That's the plan ... will see how that works in the next weeks.

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

Interesting concept lets talk about your osd in own thread. Have you?

Back to direct frsky data..

What the problem to add it to main thrunk ? There will be bigger chance that someone will complete that a few parts not finished....

User avatar
ezio
Posts: 827
Joined: Sun Apr 01, 2012 11:03 pm
Location: Paris
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by ezio »

janekx wrote:If will look on this mod in sum

What is working and todo

#define ID_GPS_altidute_bp 0x01 - yes
#define ID_GPS_altidute_ap 0x09 - yes
#define ID_Temprature1 0x02- no of satelites
#define ID_RPM 0x03 - yes
#define ID_Fuel_level 0x04 - need todo
#define ID_Temprature2 0x05 - GPS distance to home
#define ID_Volt 0x06 - todo FrSky FLVS-01 voltage sensor - cells voltage
#define ID_Altitude_bp 0x10 - yes
#define ID_Altitude_ap 0x21 - yes
#define ID_GPS_speed_bp 0x11 - yes
#define ID_GPS_speed_ap 0x19 - yes
#define ID_Longitude_bp 0x12 - yes
#define ID_Longitude_ap 0x1A - yes
#define ID_E_W 0x22 - yes
#define ID_Latitude_bp 0x13 - yes
#define ID_Latitude_ap 0x1B - yes
#define ID_N_S 0x23 - yes
#define ID_Course_bp 0x14 - yes
#define ID_Course_ap 0x24 - 0 need todo ???
#define ID_Date_Month 0x15 - neded ???
#define ID_Year 0x16 - needed ???
#define ID_Hour_Minute 0x17 - yes since start
#define ID_Second 0x18 - yes since start
#define ID_Acc_X 0x24 - yes Gs
#define ID_Acc_Y 0x25 - yes Gs
#define ID_Acc_Z 0x26 - yes Gs
#define ID_Voltage_Amp_bp 0x3A - yes - FAS_100 todo
#define ID_Voltage_Amp_ap 0x3B - yes -FAS_100 todo
#define ID_Current 0x28 - FAS_100 todo

I thing that this mod can be added to trunk because what is not working is
Fuel level
Volt of cells
Current

and less important
year
month and date


suggestions
alt and Galt in format 1.2m not only meters would be nice.


I think there is a bug
it should be #define ID_Course_ap 0x1C
instead of #define ID_Course_ap 0x24

0x24 is used in #define ID_Acc_X 0x24

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

Yes you right protocol says 0x14+8 is 0x1C so I repair it


Code: Select all

// ****************************************************************
// FrSky telemetry
// Version: 0.2.2
// Date 7/10/2012
// Changes: V0.2.2: - corrected ID_Course_ap is 0x1C not 0x24 protocol says 0x14+8
// Date 20/09/2012
// Changes: V0.2.1: - make it work with 2.1 (shared dev)
// Date: 14/08/2012
// Changes: V0.2: - Byte stuffing added
//                - vBat will be send, if "#define FAS_100" is comment out
//                V0.1: - First release
// ****************************************************************

#if defined(TELEMETRY_FRSKY)
  // user defines
  //#define FAS_100  //if commment out, MultiWii vBat voltage will be send instead of FrSky FAS 100 voltage


  // Serial config datas
  #define TELEMETRY_FRSKY_SERIAL 3
  #define TELEMETRY_FRSKY_BAUD 9600 

  // Timing
  #define Time_telemetry_send 125000
  static uint8_t cycleCounter = 0;
  static uint32_t FrSkyTime  = 0;

  // Frame protocol
  #define Protocol_Header   0x5E
  #define Protocol_Tail      0x5E
 
 
  // Data Ids  (bp = before point; af = after point)
  // Official data IDs
  #define ID_GPS_altidute_bp    0x01
  #define ID_GPS_altidute_ap    0x09
  #define ID_Temprature1        0x02
  #define ID_RPM                0x03
  #define ID_Fuel_level         0x04
  #define ID_Temprature2        0x05
  #define ID_Volt               0x06
  #define ID_Altitude_bp        0x10
  #define ID_Altitude_ap        0x21
  #define ID_GPS_speed_bp       0x11
  #define ID_GPS_speed_ap       0x19
  #define ID_Longitude_bp       0x12
  #define ID_Longitude_ap       0x1A
  #define ID_E_W                0x22
  #define ID_Latitude_bp        0x13
  #define ID_Latitude_ap        0x1B
  #define ID_N_S                0x23
  #define ID_Course_bp          0x14
  #define ID_Course_ap          0x1C
  #define ID_Date_Month         0x15
  #define ID_Year               0x16
  #define ID_Hour_Minute        0x17
  #define ID_Second             0x18
  #define ID_Acc_X              0x24
  #define ID_Acc_Y              0x25
  #define ID_Acc_Z              0x26
  #define ID_Voltage_Amp_bp     0x3A
  #define ID_Voltage_Amp_ap     0x3B
  #define ID_Current            0x28
  // User defined data IDs
  #define ID_Gyro_X             0x40
  #define ID_Gyro_Y             0x41
  #define ID_Gyro_Z             0x42

   // Main function FrSky telemetry
    void telemetry_frsky()
   {         
      if (currentTime > FrSkyTime ) //
      {         
         FrSkyTime = currentTime + Time_telemetry_send;
         cycleCounter++;
         // Datas sent every 125 ms
            send_Accel();
            sendDataTail();   

         if ((cycleCounter % 4) == 0)
         {     
            // Datas sent every 500ms
            send_Altitude();
            send_RPM();
            send_Course();
            send_GPS_speed();
            //send_Cell_volt();       todo
            sendDataTail();   

         }
         if ((cycleCounter % 8) == 0)
         {     
            // Datas sent every 1s           
            //send_Time();
            send_GPS_position();
            send_GPS_altitude();
            send_Temperature2();  // Distance_to_home
            //send_Fuel_level();
            send_Voltage_ampere();
            send_Temperature1();  // num of Sats
            sendDataTail();           
         }

         if (cycleCounter == 40)
         {
            // Datas sent every 5s
            cycleCounter = 0;       
         }
      }
   }

   void write_FrSky8(uint8_t Data)
   {
      SerialWrite(TELEMETRY_FRSKY_SERIAL, Data);
   }

   void write_FrSky16(uint16_t Data)
   {
      uint8_t Data_send;
      Data_send = Data;     
      check_FrSky_stuffing(Data_send);
      Data_send = Data >> 8 & 0xff;
      check_FrSky_stuffing(Data_send);
   }
   
   void check_FrSky_stuffing(uint8_t Data) //byte stuffing
   {
      if (Data == 0x5E)   
      {
         write_FrSky8(0x5D);
         write_FrSky8(0x3E);
      }
      else if (Data == 0x5D)   
      {
         write_FrSky8(0x5D);
         write_FrSky8(0x3D);
      }
      else
      {
         write_FrSky8(Data);         
      }
   }

   static void sendDataHead(uint8_t Data_id)
   {
      write_FrSky8(Protocol_Header);
      write_FrSky8(Data_id);
   }

   static void sendDataTail(void)
   {
      write_FrSky8(Protocol_Tail);     
   }


   //*********************************************************************************
   //-----------------   Telemetrie Datas   ------------------------------------------   
   //*********************************************************************************

   // GPS altitude
   void send_GPS_altitude(void)
   {         
      if (f.GPS_FIX && GPS_numSat >= 4)
      {
         int16_t Datas_GPS_altidute_bp;
         uint16_t Datas_GPS_altidute_ap;

         Datas_GPS_altidute_bp = GPS_altitude;
         Datas_GPS_altidute_ap = 0;

         sendDataHead(ID_GPS_altidute_bp);
         write_FrSky16(Datas_GPS_altidute_bp);
         sendDataHead(ID_GPS_altidute_ap);
         write_FrSky16(Datas_GPS_altidute_ap);
      }
   }
   
   // Temperature
   void send_Temperature1(void)
   {
      int16_t Datas_Temprature1;

      Datas_Temprature1 = GPS_numSat;  // Number of Satalits alias Temp1

      sendDataHead(ID_Temprature1);
      write_FrSky16(Datas_Temprature1);
   }

   // RPM
   void send_RPM(void)
   {
      uint16_t Datas_RPM = 0;     
      for (uint8_t i=0;i<NUMBER_MOTOR;i++)
      {
         Datas_RPM += motor[i];
      }
      Datas_RPM = (Datas_RPM / NUMBER_MOTOR) / 30;   // RPM

      sendDataHead(ID_RPM);
      write_FrSky16(Datas_RPM);
   }

   // Fuel level
   void send_Fuel_level(void)
   {
      uint16_t Datas_Fuel_level;

      Datas_Fuel_level = 0;

      sendDataHead(ID_Fuel_level);
      write_FrSky16(Datas_Fuel_level);
   }

   // Temperature 2
   void send_Temperature2(void)
   {
      if (f.GPS_FIX_HOME)
      {
         int16_t Datas_Temprature2;

         Datas_Temprature2 = GPS_distanceToHome; // Distance to home alias Temp2

         sendDataHead(ID_Temprature2);
         write_FrSky16(Datas_Temprature2); 
      }     
   }

   // Cell voltage  todo !!!!!!!!!!!!!!!!!!
   void send_Cell_volt(void) // Datas FrSky FLVS-01 voltage sensor
   {
      uint16_t Datas_Volt;
      uint8_t number_of_cells = 0;   // LiPo 3S = 3; LiPo 4S = 4 ...
      static uint8_t cell = 0;
      if (cell >= number_of_cells); cell = 0;
     
      Datas_Volt = 0; // 0.01v / 0 ~ 4.2v

      sendDataHead(ID_Volt);
      write_FrSky16(Datas_Volt);
   }

   // Altitude
   void send_Altitude(void)
   {
      uint16_t Datas_altitude_bp;
      uint16_t Datas_altitude_ap;
      static uint16_t Start_altitude;

      if (!f.ARMED)
      {
         Start_altitude = EstAlt / 100;
      }

      Datas_altitude_bp = (EstAlt / 100) - Start_altitude;
      Datas_altitude_ap = (EstAlt % 100);

      sendDataHead(ID_Altitude_bp);
      write_FrSky16(Datas_altitude_bp);
      sendDataHead(ID_Altitude_ap);
      write_FrSky16(Datas_altitude_ap);
   }

   // GPS speed
   void send_GPS_speed(void)
   {
      if (f.GPS_FIX && GPS_numSat >= 4)
      {           
         uint16_t Datas_GPS_speed_bp;
         uint16_t Datas_GPS_speed_ap;
         
         Datas_GPS_speed_bp = GPS_speed * 0.036;
         Datas_GPS_speed_ap = 0;
     
         sendDataHead(ID_GPS_speed_bp);
         write_FrSky16(Datas_GPS_speed_bp);
         sendDataHead(ID_GPS_speed_ap);
         write_FrSky16(Datas_GPS_speed_ap);
      }
   }

   // GPS position
   void send_GPS_position(void)
   {
   
         uint16_t Datas_Longitude_bp;
         uint16_t Datas_Longitude_ap;
         uint16_t Datas_E_W;
         uint16_t Datas_Latitude_bp;
         uint16_t Datas_Latitude_ap;
         uint16_t Datas_N_S;
         Datas_Longitude_bp = abs(GPS_coord[LON]) / 100000;
         Datas_Longitude_ap = abs((GPS_coord[LON])/10)  % 10000;
         Datas_E_W = GPS_coord[LON] < 0 ? 'W' : 'E';
         Datas_Latitude_bp = abs(GPS_coord[LAT]) / 100000;
         Datas_Latitude_ap = abs((GPS_coord[LAT])/10) % 10000;
         Datas_N_S = GPS_coord[LAT] < 0 ? 'S' : 'N';

         sendDataHead(ID_Longitude_bp);
         write_FrSky16(Datas_Longitude_bp);
         sendDataHead(ID_Longitude_ap);
         write_FrSky16(Datas_Longitude_ap);
         sendDataHead(ID_E_W);
         write_FrSky16(Datas_E_W);

         sendDataHead(ID_Latitude_bp);
         write_FrSky16(Datas_Latitude_bp);
         sendDataHead(ID_Latitude_ap);
         write_FrSky16(Datas_Latitude_ap);
         sendDataHead(ID_N_S);
         write_FrSky16(Datas_N_S);
     
   }

   // Course
   void send_Course(void)
   {
      uint16_t Datas_Course_bp;
      uint16_t Datas_Course_ap;

      Datas_Course_bp = heading;
      Datas_Course_ap = 0;

      sendDataHead(ID_Course_bp);
      write_FrSky16(Datas_Course_bp);
      sendDataHead(ID_Course_ap);
      write_FrSky16(Datas_Course_ap);
   }

   // Time
   void send_Time(void)
   {
      uint32_t seconds_since_start = millis() / 1000;
           
      uint16_t Datas_Date_month;
      uint16_t Datas_Year;
      uint16_t Datas_Minutes_hours;
      uint16_t Datas_seconds;
           
      Datas_Date_month = 0;
      Datas_Year = 12;
      Datas_Minutes_hours = (seconds_since_start / 60) % 60;
      Datas_seconds = seconds_since_start % 60;     
     
      sendDataHead(ID_Hour_Minute);
      write_FrSky16(Datas_Minutes_hours);
      sendDataHead(ID_Second);
      write_FrSky16(Datas_seconds);
   }

   // ACC
   void send_Accel(void)
   {
      int16_t Datas_Acc_X;
      int16_t Datas_Acc_Y;
      int16_t Datas_Acc_Z;

      Datas_Acc_X = ((float)accSmooth[0] / acc_1G) * 1000;
      Datas_Acc_Y = ((float)accSmooth[1] / acc_1G) * 1000;
      Datas_Acc_Z = ((float)accSmooth[2] / acc_1G) * 1000;

      sendDataHead(ID_Acc_X);
      write_FrSky16(Datas_Acc_X);
      sendDataHead(ID_Acc_Y);
      write_FrSky16(Datas_Acc_Y);
      sendDataHead(ID_Acc_Z);
      write_FrSky16(Datas_Acc_Z);     
   }

   // Voltage (Ampere Sensor) 
   void send_Voltage_ampere(void)
   {
   
      #if defined (FAS_100)   // todo   !!!!!!!!!!!!!!!!!
      {
         uint16_t Datas_Voltage_Amp_bp;
         uint16_t Datas_Voltage_Amp_ap;
         uint16_t Datas_Current;   

         Datas_Voltage_Amp_bp = 0;
         Datas_Voltage_Amp_ap = 0;   
         Datas_Current = 0;

         sendDataHead(ID_Voltage_Amp_bp);
         write_FrSky16(Datas_Voltage_Amp_bp);
         sendDataHead(ID_Voltage_Amp_ap);
         write_FrSky16(Datas_Voltage_Amp_ap);   
         sendDataHead(ID_Current);
         write_FrSky16(Datas_Current);
      }
      #else   // use vBat
      {
         uint16_t Datas_Voltage_vBat_bp;
         uint16_t Datas_Voltage_vBat_ap;   
         uint16_t voltage;
         voltage = (vbat * 110) / 21;         
         Datas_Voltage_vBat_bp = voltage / 100;
         Datas_Voltage_vBat_ap = ((voltage % 100) + 5) / 10;         

         sendDataHead(ID_Voltage_Amp_bp);
         write_FrSky16(Datas_Voltage_vBat_bp);
         sendDataHead(ID_Voltage_Amp_ap);
         write_FrSky16(Datas_Voltage_vBat_ap);   
      }
      #endif
   }

#endif

User avatar
ezio
Posts: 827
Joined: Sun Apr 01, 2012 11:03 pm
Location: Paris
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by ezio »

Hi
it is save if I use it with ATMega324 and I have changed serial speed to 9600 ?
it doesn't make longer main loop intervals ?

User avatar
ezio
Posts: 827
Joined: Sun Apr 01, 2012 11:03 pm
Location: Paris
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by ezio »

I have modified frsky telemetry a little bit to be compatible with my android app.
file is here https://github.com/eziosoft/MultiWii_EZ ... lemtry.ino

janekx
Posts: 63
Joined: Wed Sep 12, 2012 10:08 pm
Location: Brno, Czech Republic

Re: Direct Frsky telemtry data from MW FC

Post by janekx »

This change brake the Acc X/Y/Z telemetry data sended to Frsky modules.

kataventos
Posts: 702
Joined: Sun Aug 28, 2011 8:14 pm
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by kataventos »

wilco1967 wrote:Image





Thanks for this great idea/code ;)

I have made this inverter for other project and seems to me that this work either, but I wanted to ask for a second opinion, sorry for the hi tec hand draw ;) :

Inverter
Inverter


Thanks

vpb
Posts: 231
Joined: Mon Jul 23, 2012 4:09 pm

Re: Direct Frsky telemtry data from MW FC

Post by vpb »

Here is my telemetry test with r1177, latest frskytelemetry.ino from janekx, level converter from wilco1967 it works very well, thank you all!!!
https://www.youtube.com/watch?v=MeIb-4KfoqI

Commander1024
Posts: 1
Joined: Thu Nov 01, 2012 5:06 pm

Re: Direct Frsky telemtry data from MW FC

Post by Commander1024 »

Hi, I modified the scematic above to do both: level converting and inverting

UPDATED: fixed misplaced resistors
Attachments
MultiWii-FrSky-er9x-inverter-levelconverter_improved.png
Last edited by Commander1024 on Sun Jan 13, 2013 4:50 pm, edited 1 time in total.

kataventos
Posts: 702
Joined: Sun Aug 28, 2011 8:14 pm
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by kataventos »

Commander1024 wrote:Hi, I modified the scematic above to do both: level converting and inverting


:) thanks and welcome, you are right!

User avatar
djrm
Posts: 40
Joined: Wed Feb 15, 2012 11:32 pm
Location: North Yorkshire, UK

Re: Direct Frsky telemtry data from MW FC

Post by djrm »

Here is a simple way to use both a Bluetooth transmitter and Er9x transmitter LCD together using an RS232 Bluetooth adapter, the adapter has pins for the ttl level and the inverted RS232 level serial signals, so combining both a level translator for the RC and the Bluetooth transmitter, they both seem to work together without problems.

The HC-05-D RS232 bluetooth adapter is listed to buy online, mine came from China for $19.90 including some cables and carriage. The default settings did not need changing, it is supplied working at 9600 bps.

The Bluetooth module connects to both the USBasp programming port and the Frsky transmitter modules using these pin assignments:
1 +5v from usbasp pin 2
2 no connection
3 Rx ttl to usbasp pin 1
4 Tx ttl to usbasp pin 9
5 no connection
6 RX RS232 to Frsky Txd
7 TX RS232 to Frsky Rxd
8 Gnd to usbasp pin 10

The connections to the usbasp programming port are the ttl serial data connections needed by the Er9x - Frsky modified RC transmitter to show the telemetry data on the RC screen. with this setup I could view the telemetry on the Er9x screen as well as with my mobile Bluetooth application for logging.

Image

Its early days for this at present, I'm waiting for a chance to fly my new Naze32 quad with this gear.
hth David

kataventos
Posts: 702
Joined: Sun Aug 28, 2011 8:14 pm
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by kataventos »

OK, downlink done... it´s just tweaking and work together with the ER9x team for more "options"!

What about Alex idea of using Frsky on an uplink without disturb the 8 ch we have?
This is something usefull for way point nav, and our modules have good range for all of that! It´s this possible? any ideas?

User avatar
IceWind
Posts: 115
Joined: Fri Mar 25, 2011 2:11 am
Contact:

Re: Direct Frsky telemtry data from MW FC

Post by IceWind »

For simple operations yes, for waypoints could be tricky as it would easier to have a map to select/edit points rather than the radio.

Btw I made a different connection involving less cables.

Image
Straight into a RS232<>TTL converter.

Still need to reduce the cables size a bit.

Post Reply