Hello Fellow Yuneec Pilot!
Join our free Yuneec community and remove this annoying banner!
Sign up

Typhoon H 480 PX4 v1.10 (Stability issues ;-)

So here it goes what I found saved on my computer about Yuneec protocols.
(well... the growing PWM ramp actually doesn't exist - I'm getting older :p)
Probably you found them already, but just in case...

Gimbal signaling :



SR24 zigbee protocol, files attached (only for Q500 and without telemetry ...):


I played a little with the Typhoon H motherboard with stock firmware and I managed to lift it in the air (sort of...) with custom arms and custom motors+props, but due to the inability to tune it I gave it up for the moment.
Initially I wanted to port it to INAV, but my coding skills are close to zero, so even if I able to do the port definitions, I can't compile it (beeing an electrical engineer). Anyhow, INAV doesn't compare to AP/PX4, at least for cinematographic platforms...
Once I wanted to do it to the Phantom3 (having a F427, it would be a good pretender to AP or PX4) :), but the H is much easier to port to AP/PX4.

As a side-note, I found a creepy similarity between the CGO3 and CGO3+ gimbal controllers' hardware and the 32bit version of AlexMos boards :p. But the research ends here, because they are closed source ones and each of them is somewhat activated and tracked by their S/N.

Keep us tuned and best regards,
Zsolt

Edit:
The big hexa is using the stock ESC board? I checked it's power capability and concluded that they are waaay oversized, but no way till 3508-sized motors on 15" :)
I tested it initially with 2216-810kV on Phantom2 props (9,5"x4,5") but wanted to upgrade to 10"x5" or 11"x5" props, still on the safe side IMHO...
 

Attachments

  • YuneecRX2ppmFinal.zip
    7.6 KB · Views: 26
  • Yuneec-Protocol.zip
    12.5 KB · Views: 29
Last edited:
Hi and thank you very much for the info! ;-)

I am going to write something about that custom-made gimbal as soon as this PX4 port is done and made available for you! ;) (The gimbal has a Sony 10X analog low-res/high-speed camera core, Storm32 gimbal controller, mechanics and yuneec -> ppm/visca converter designed and 3d-printed by me). It could be a bit too heavy for the Typhoons. The big hexa has a Pixhawk 2.1 and separate ESCs; no Yuneec hardware there except the Mk58 video transmitter and SR24 receiver ;-) The Typhoon's ESCs are indeed not suitable for that kind of motors.

I am going to release this port as soon as I get the items that I consider mandatory (gimbal tilt, bind mode, documentation) together and have done few test flights (and some days of hardware-in-the-loop simulation). Then you'll be able to tune your platform to your hearts content (get an STLink or ST Nucleo board meanwhile... ;-) Inav is nice, but the PX4 is way more advanced than it in its current form.

The F427 is no problem, actually that is the MCU that is used in Pixhawks. The sensors and wiring however are something that may give you some surprises. DJI loves for example grind markings off the ICs, and in later models they are using a lot of ASICs with no public documentation, that makes hardware/software hacking pretty much impossible.

The gimbals indeed do share some similarities with Alexmos ones.. ;-) Speaking of the gimbals; I probed the signals with a scope. Yuneec made a little surprise for us there. In startup, the signal goes high (3.27V) for a while, then changes to 71 us on / 16 us off pulse for few seconds. The normal signal is different from the earlier ones, too. There are two pulses in it. The first pulse has a constant length. The second pulse drives the tilt axis; its width changes according to the tilt slider. One would think that the first pulse is for the yaw axis, but no, it reacts to nothing. The PX4 can not generate such signal; I have to write my own driver for it. There are luckily some examples available that I could use... ;-)
 

Attachments

  • cgo3plus_run.PNG
    cgo3plus_run.PNG
    75.1 KB · Views: 37
  • cgo3plus_startup.PNG
    cgo3plus_startup.PNG
    73.5 KB · Views: 35
Last edited:
...And here is my attempt to generate that PPM/PWM signal. Carefully handcrafted, proudly bitbanged and scoped fresh off the Typhoon gimbal connector. ;-)

Next I have to create that startup pulse and somehow get tilt channel data from the mixer to my PPM generator. Maybe tomorrow, it's time to ZZZ now.

Br, TR
 

Attachments

  • px4_ppmgen.PNG
    px4_ppmgen.PNG
    169.8 KB · Views: 37
Initially I wanted to port it to INAV, but my coding skills are close to zero, so even if I able to do the port definitions, I can't compile it (beeing an electrical engineer). Anyhow, INAV doesn't compare to AP/PX4, at least for cinematographic platforms...

If you want to try the INAV porting, here are some of my notes that might help you. I am going to finish them later, but here's a fast screencap to get you started... It would be awesome to have the TH run both PX4 and *flight firmwares. Why? Just because we can! ;-)

Omnibus F4 SD could be a good candidate for a base. I started with that one on the PX4. No SPI, only two I2C's. UART ESCs are going to be a minor pain with INAV, borrow it from the PX4 (tap_esc). Works as-is. What could be fun with *flights: in-flight reverse... ;-) The TH is clocked using 16 MHz external crystal, unlike the most F4 FC's (8 MHz), a good thing to notice. PLL settings / dividers / multipliers for clocks can be generated using CubeMX, or wait my code... ;-)
 

Attachments

  • th_pinout.PNG
    th_pinout.PNG
    167.9 KB · Views: 86
Last edited:
Thanks for the infos! Hard to choose for a winter project...especially when you have no spare time for tinkering :( I think I will wait till the "official" release :)
One more thing worth noting if you are a fresh ST16 user (as I am, too)... in case you not tumbled upon this yet...
The ST16's components and assembly quality is not as top-notch as one can think if looking from outside of the transmitter... but you probably noticed that already.
One issue is very striking: the gimbal PCBs 3-pin connectors can do very nasty things and the majority of the users are not aware of this. This is caused probably by the constantly flexing gimbal cables at the PCB.
This issue was somewhat covered here, with a solution, too.
I can bet that 80% of flyaways can be attributed to this, coupled with user's inexperience to handle such situation.
The solution is simple: just solder the gimbal pot cables directly to the PCB, adding some flexible glue on top.
My Ebay-transmitter (bought as "deffective"...) had the same habbit: all four gimbal channels were all over the places even at the lightest stick movement . After the surgery and recalibration, everything is fine now...
This ST16 looks like new... almost zero mileage...
Anyhow, it's a good habbit to check all channels before takeoff in the "hardware monitor".
 
Last edited:
  • Like
Reactions: DoomMeister
Thanks for the info! ;-) I was not aware of that growing PWM ramp. I've gotta scope that and probably take a look also at the TX with a logic analyzer. ;-) The CGO3+ is connected to PA2 and PA3 on F405.

There is a ready-made implementation for the SR24 in PX4 (w/o bind function), also for telemetry, but the telemetry part seems not to be working with the ST16. Probably only with the ST24, I've got to try with it. I am flying my larger drone (photo attached ;-) with the ST24 and my own SR24 -> PPM/Sony Visca protocol adapter with my custom-made 10X zoom gimbal. ;-) But the ST16 telemetry is something that we need to implement as the ST24s are quite rare.

I have to check the PX4 telemetry implementation against that excel sheet and modify if required. ;-)
What is the larger drone?
 
Looks to me like a Sky Hero Spyder 6, 1000mm. A tad bigger than my 480mm Little Spyder clone, haha.
That is it :) A Spyder 6 with a custom-made carbon cover and some little tweaks.. ;-) I'm going to tell about it a bit later. ;-)

I am starting to dislike the CGO3+... ;-) I have written a nice little driver for the PX4 that reproduces the exact PWM signal the Typhoon sends in startup. And that weird PPM/PWM drive signal. And the CGO3+ tilt still does not work. So, I decided to take a bit closer look at it. The Typhoon sends out a very specially crafted initialization pulse and pretty weird PPM/PWM signal, complete with a heartbeat (hb3.png) or something that occurs in every 25th cycle. Probably to retain compatibility with CGO3 or something. It does this only when the CGO3+ is not present. When the CGO3+ is connected, the communication mode switches to full serial (yun_serial.png) where the PWM pin acts as a RX (or TX) pin. It is completely different than the Y's older gimbals and cameras. I am now thinking to finish what I've done so far, release them and then focus on the CGO3+. Challenge accepted... ;-)
 

Attachments

  • hb3.PNG
    hb3.PNG
    60.1 KB · Views: 36
  • yun_serial.PNG
    yun_serial.PNG
    97.8 KB · Views: 42
Last edited:
  • Like
Reactions: Luma
Thanks for the infos! Hard to choose for a winter project...especially when you have no spare time for tinkering :( I think I will wait till the "official" release :)
One more thing worth noting if you are a fresh ST16 user (as I am, too)... in case you not tumbled upon this yet...
The ST16's components and assembly quality is not as top-notch as one can think if looking from outside of the transmitter... but you probably noticed that already.
One issue is very striking: the gimbal PCBs 3-pin connectors can do very nasty things and the majority of the users are not aware of this. This is caused probably by the constantly flexing gimbal cables at the PCB.
This issue was somewhat covered here, with a solution, too.
I can bet that 80% of flyaways can be attributed to this, coupled with user's inexperience to handle such situation.
The solution is simple: just solder the gimbal pot cables directly to the PCB, adding some flexible glue on top.
My Ebay-transmitter (bought as "deffective"...) had the same habbit: all four gimbal channels were all over the places even at the lightest stick movement . After the surgery and recalibration, everything is fine now...
This ST16 looks like new... almost zero mileage...
Anyhow, it's a good habbit to check all channels before takeoff in the "hardware monitor".

Hi, thank you very much for this good info regarding the ST16. I did not know about that one. I was aware that the potentiometers are not among the best ones there are (I've had to replace one gimbal of my ST16 and put some contact cleaner to the remaining ones potentiometers and to both of my ST24's gimbals). I even tried to source better pots for the gimbals, only to find out that one of the two pots in a gimbal is impossible to replace. But wires getting loose too, causing nasty things to happen... the build quality in these is indeed impressive, and not in a positive way. ;-)
 
Last edited:
The gimbal is working. :)

The initialization pulse is 650 uS PWM @ 50 Hz, immediately when the camera is powered on for 5 seconds.


PWM signal characteristics:
- frequency: 50-200Hz
- amplitude: 3-5V (3,3V)
- Initialization signal: 630 - 660 μs
- Signal to block tilt: 900 - 1040 μs (see at 04:15)
- Signal to control tilt: 1100 - 1850 μs


Why I did not find that info above earlier.. I spent quite many evenings with this one. :-D
But what I found out:

- There are indeed two communication modes for the gimbal. The 650 uS PWM enables PWM controlled tilt.
- No previous initialization signals work with the CGO3+
- If the gimbal is connected to the Typhoon, a full serial communication is established between the drone and the camera
- I was not able to figure out the protocol. There were some patterns in the signal, but..
- The bit rate was unknown for me. I could not get rid of serial framing errors (I assumed it being serial). I tried every standard baud rate from 9600 - 921 000 and also the two Yuneec specials; 250 000 kbps (ESC's) and 500 000 (later cameras).
- The Typhoon's back up control link, firmware upgrades, gimbal pan, following etc. are probably transmitted over this
- The PWM interface may be there for compatibility only
 
Last edited:
Things are starting to look nice. The Typhoon flies (at least in my living room, its cold, wet and dark here.. ;-), the gimbal works (I had to generate the initialization waveform with the bootloader as the CGO3+ wants its signal immediately with no delay when powered up) and it was also interesting to see, that for example the panorama photo mode is also functional. It seems that some of the gimbal movements are actually controlled over WiFi by the ST16 or the camera itself.

There are some issues that need to be resolved, this PX4 issue being the most critical: FIX: Crash after ST24/16 power down PX4#13265 by ultrasystem · Pull Request #13266 · PX4/Firmware
I was able to reproduce that and I am probably going to do something for it by myself...

I also need to implement a bind functionality for the SR24 receiver. The PX4 V1.10 is in its RC4 state, and before I'll finish all I've done so far, I will probably wait for the final V1.10 release.
 
Last edited:
This conversation on discuss.ardupilot.org may help with the bind issue.

 
This conversation on discuss.ardupilot.org may help with the bind issue.


Thanks, that should do the trick. ;-) I think I am going to try this other way around, too. I have few SR24's somewhere with Teensys/ESPs connected to them. I built few PPM/PWM -enabled SR24's a while ago when I wanted to use the ST24 as a controller for my other drones, the Spyder 6 being one of them.

For future development, I would like to pair two SR24's as a transparent serial link, one connected directly to a PC or smartphone, to transmit raw MAVLINK messages instead of Yuneec protocol, to the drone. ;-) Of course, it would be easy to connect some ready-made serial TX/RX to the Typhoon now, but I want to keep it stock in hardware.

I managed to resolve the crashy failsafe issue on the ST16/24 above. Maybe the next task for me is writing that bind application for the NuttX RTOS / PX4. ;-)
 
Last edited:
Binding works, I wrote a small app for it. Running "typhoon_bind" on TH's NSH shell, sends the bind command to SR24 (/dev/ttyS3, 115 200 bps) and puts it to the bind mode. Next up: ADC/battery voltage etc. ;-)

Edit: done. ;-)
 
Last edited:
Thanks, Tuna! ;-)

We're getting closer.. ;-) I had a bench / indoors testing evening and I found out that the Typhoons are supplied with two different magnetometers, depending on era/batch. The earlier ones come with HMC5883 and later ones with IST8310. Had to add support for the IST8310, luckily Intel Aero is made of Typhoon's parts, so this was an easy one. Both verified working.

HMC5883 rotation in PX4: Yaw 270 degrees. IST8310 rotation: Yaw 180 degrees. You'll need these when calibrating the magnetometer. If after calibration north is not where it was supposed to be, try another one of these. ;-)

I also updated my files to build on PX4 1.10.0 Relase Candidate 1 and uploaded my fork to GitHub. It is somewhere there, it's not hidden...
Where; that's something you'll find out as soon as I have done some outdoor test flights with my Typhoon first. ;-)

Our new firmware fork might also need a nice name and a logo to stick on to the lid of our hot-rodded Typhoons. "PX4 Typhoon" sounds so boring, so I came up with an idea... See attachment. (Yes, it is really rainy, dark and cold here! ;-)

Edit:

I am going to write a documentation for this fork, before telling you where the source codes actually are, but in case you'll find them and you know PX4 and STM32 well enough... All information should already be here in this thread. The current code in the branch Typhoon_H_480, the latest commit being bootloader-related, has been tested only indoors at the time of writing this. Telemetry, lights, etc.. are not there yet. I'd flash the bootloader first, the git repo for that is in the zip. Get an ST-link, build and install st-flash, build the bootloader with .sh script and flash it with the STLink. SWD pads are described earlier here. Or some other SWD capable flasher/debugger of your choice. The bootloader is capable of flashing the PX4 over USB. Build the PX4, flash it over the USB using flash_typhoon_bootloader.sh., /dev/ttyACM0 is hardcoded there as the port. It is a (rather ugly ;-) fork of Omnibus F4SD's bootloader. The bootloader has a time delay of 3 seconds for the flashing command. After that, it starts sending the CGO3+ init pulse, then boots the Typhoon. Hold power button down for 8 secs for normal startup. Calibrate sensors with QGroundcontrol, set battery, radio as you wish. CGO3+ pitch is driven by the vmount driver's pitch, map that to AUX1 and AUX1 to the gimbal slider. Remember to configure failsafes. Test everything, especially the failsafe w/o propellers. Start with attitude/Rattitude mode, then proceed to GNSS assisted ones. (I am going to release .param file as a starting point for you, when I have test-flown the TH outdoors and I am happy how it behaves.) Have fun. ;-)
 

Attachments

  • th_thunderbird_logo.png
    th_thunderbird_logo.png
    35.2 KB · Views: 41
Last edited:
Hi,

A quick update: weather permitted me to do some outdoor testing with the Typhoon and the Thunderbird FW... Wow. ;-)
The PX4 1.10.0 RC1 is really wonderful with the Typhoon. It feels a lot smoother and enjoyable to fly than any drone I've flown before (including some 20-50 kUSD special rigs and a stock Typhoon!). This time my testing focused on GNSS-assisted flight and failsafe functionality instead of aerobatics (although I could not resist not to do few loops with the Typhoon. ;-).

Here is a short shaky video:


Only issue I found, is that I can't use RTH as a radio failsafe. When RTH is assigned as a radio failsafe, the Typhoon retracts the landing gear like it plans to go for a automatic mission (which RTH is), but it does not go anywhere. Land mode as a failsafe action, works reliably, I'll use that for now. Don't shut your radio down while you are flying over water. ;-) Possibly a bug in PX4 V1.10.0 RC1.

Other than that.. amazing! ;-) Even the landing gear is actuated automatically. When the drone starts climbing for RTH, it automatically retracts the landing gear, and when it starts autoland, landing gear is automatically deployed.
 
Last edited:
  • Like
Reactions: Gunit
When I was testing the drone, there was one thing I was missing: telemetry and especially battery voltage. I just had to do something for it. So here is a little piece of code I wrote today to inject some telemetry data to the ST16 over SR24 link, for testing with Arduino, if someone is interested... ;-) Next I have to adapt this to PX4, resolve few missing fields, make run it on Typhoon and get some data from uORB messages to enable telemetry on the Thunderbird / Typhoon. ;-)

EDIT:

Resolved missing fields and included data descriptions. They differ slightly from "stock" ST24 implementation of the PX4. It took me few evenings experimenting to find out how the Typhoon's telemetry works. ;-)

C:
/****************************************************************************
*
*   Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
*    notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
*    notice, this list of conditions and the following disclaimer in
*    the documentation and/or other materials provided with the
*    distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
*    used to endorse or promote products derived from this software
*    without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

typedef struct {
    uint8_t length;       ///< length includes type, data, and crc = sizeof(type)+sizeof(data[payload_len])+sizeof(crc8)
    uint8_t type;       ///< from enum ST24_PACKET_TYPE
    uint16_t t;     ///< packet counter or clock
    int32_t lat;      ///< latitude (degrees)  +/- 90 deg
    int32_t lon;      ///< longitude (degrees)  +/- 180 deg
    int32_t alt;      ///< 0.01m resolution, altitude (meters)
    int16_t vx, vy, vz;     ///< velocity 0.01m res, +/-320.00 North-East- Down

    uint8_t nsat;     ///< Sum of GPS status and number of satellites.
    //GPS status is bit 8 of the byte. Number of satellites is defined using the first 5 bits.
    //0b10011111 = GPS Ready, 31 satellites.
      //0b00011111 = GPS Acguiring, 31 satellites.

    uint8_t voltage;    ///< 25.4V  voltage = 5 + 255*0.1 = 30.5V, min=5V
    uint8_t current;    ///< 0.5A resolution
    int16_t roll, pitch, yaw; ///< 0.01 degree resolution
    uint8_t motorStatus;    ///< 1 bit per motor for status 1=good, 0= fail

    uint8_t gpsStatus;    ///< gps and obs status
    /* Example: 0x61
    * 0x[X]Y
    * 0001 yyyy = gps disabled, obs rdy
    * 0010 yyyy = gps acquiring, obs disabled
    * 0100 yyyy = gps disabled, obs disabled
    * 1000 yyyy = gps disabled, obs disabled
    *
    * 0xX[Y]
    * xxxx 0001 = none
    * xxxx 0010 = none
    * xxxx 0100 = none
    * xxxx 1000 = none
    */

    uint8_t obsStatus; ///< obs_avoidance | unknown
    /* Example: 0x55
    * 0x[X]Y
    * 0001 yyyy = obs avoidance fail
    * 0010 yyyy = obs avoidance fail
    * 0100 yyyy = obs avoidance disabled
    * 1000 yyyy = obs avoidance fail
    *
    * 0xX[Y]
    * xxxx 0001 = none
    * xxxx 0010 = none
    * xxxx 0100 = none
    * xxxx 1000 = none
    */

    uint16_t optionbytes; ///< drone model | flight mode
    /* Example: 0x0510
    *
    * 0x00XY (Bytes 0-1)
    *
    * 0x[X]Y
    * 0001 yyyy = READY
    * 0010 yyyy = IPS
    * 0100 yyyy = "N/A"
    * 1000 yyyy = THR
    *
    * 0x1[Y]
    * 0001 1000 = WATCH
    * 0001 0100 = RATE
    * 0001 0010 = MAG CALI
    * 0001 0001 = NO RC
    *
    *0xXY00 (Bytes 2-3)
    *
    * 0x[X]Y
    * 0001 yyyy = nothing
    * 0010 yyyy = nothing
    * 0100 yyyy = nothing
    * 1000 yyyy = nothing
    *
    * 0xX[Y]
    * //xxxx 0001 = BATT RED, drone model: hex
    * //xxxx 0010 = BATT FULL, drone model: quad
    * //xxxx 0100 = BATT RED, drone model: hex
    * //xxxx 1000 = BATT RED, drone model: hex
    * 0x03xx = drone model: quad, batt red
    * 0x05xx = drone model: hex, batt ok <---- Typhoon H (captured)
    * 0x06xx = drone model: hex, batt red
    * 0x07xx = drone model: hex, batt ok <---- ?
    */

    uint16_t alarmbytes; ///< unknown | alarms
    /* Example: 0x5820
    *
    * 0x00XY (Bytes 0-1)
    *
    * 0x[X]Y
    * 0001 yyyy = imu temperature warning
    * 0010 yyyy = compass warning (captured, uncalibrated compass attached)
    * 0100 yyyy = ?
    * 1000 yyyy = no fly zone warning
    *
    * 0xX[Y]
    * xxxx 0001 = battery voltage low
    * xxxx 0010 = battery voltage critically low
    * xxxx 0100 = imu temperature warning (again?)
    * xxxx 1000 = ?
    *
    * 0xXY00 (Bytes 2-3)
    *
    * 0001 yyyy = ?
    * 0010 yyyy = ?
    * 0100 yyyy = ?
    * 1000 yyyy = ?
    *
    * xxxx 0001 = ?
    * xxxx 0010 = ?
    * xxxx 0100 = ?
    * xxxx 1000 = ?
    */
} telemPayload;

typedef struct {
  uint8_t header1;      ///< 0x55 for a valid packet
  uint8_t header2;      ///< 0x55 for a valid packet
  telemPayload payload;
  uint8_t crc8;       ///< crc8 checksum, calculated by st24_common_crc8 and including fields length, type and st24_data
} telemData;

uint8_t st24_common_crc8(uint8_t *ptr, uint8_t len)
{
  uint8_t i, crc ;
  crc = 0;

  while (len--) {
    for (i = 0x80; i != 0; i >>= 1) {
      if ((crc & 0x80) != 0) {
        crc <<= 1;
        crc ^= 0x07;

      } else {
        crc <<= 1;
      }

      if ((*ptr & i) != 0) {
        crc ^= 0x07;
      }
    }

    ptr++;
  }

  return (crc);
}

// ^--- From PX4's st24.cpp and st24.h
/*****************************************************************************/



int counter;

/*Sets Yuneec SR24 receiver to bind mode*/
void yuneecBind()
{
  int i;
  while (i < 5)
  {
  byte bindRx[] = {0x55,0x55,0x8,0x4,0x0,0x0,0x42,0x49,0x4E,0x44,0xB0}; 
  Serial1.write(bindRx, sizeof(bindRx));
 
  i++;
  }
}

void setup() {
 
  Serial.begin(115200);
  Serial1.begin(115200); 
    
  delay(1000);
  counter = 0;
//yuneecBind();
}

void loop() {
 
  unsigned long currentMillis = millis();
   
  telemPayload telemetryPayload;
  telemData telemetryData;

  if (counter >= 65535) counter = 0;
  counter ++;
 
  telemetryPayload.length = 0x26;
  telemetryPayload.type = 0x02;
  telemetryPayload.t = counter;
  telemetryPayload.lat =  294671104; // The format is correct, numbers are random ;-)
  telemetryPayload.lon =  343731322; // The format is correct, numbers are random ;-)
  telemetryPayload.alt =  99900; //999.0 m
  telemetryPayload.vx =  0;
  telemetryPayload.vy =  0;
  telemetryPayload.vz =  0;

  //GPS status is bit 8 of the byte. Number of satellites is defined using first 5 bits.
  //0b10011111 = GPS Ready, 31 satellites.
  //0b00011111 = GPS Acguiring, 31 satellites.
 
  uint8_t numsats = 11; //Number of satellites
  uint8_t gpslock = 0b10000000; //READY (0b00000000 = acguiring) 
  telemetryPayload.nsat = numsats+gpslock; //Sum of GPS status and number of satellites.

  ///< 25.4V  voltage = 5 + 255*0.1 = 30.5V, min=5V
  //0x63 = 99, 5+99*0,1 = 14.9   
  telemetryPayload.voltage = (uint8_t)99; //hex
  telemetryPayload.current = 0;
  telemetryPayload.roll = 0;
  telemetryPayload.pitch = 0;
  telemetryPayload.yaw = 0;
  telemetryPayload.motorStatus = 0xFF; //OK
  telemetryPayload.gpsStatus = 0x61;
  telemetryPayload.obsStatus = 0x55; //obs avoidance
  telemetryPayload.optionbytes = 0x0510; //drone model | flight mode
  telemetryPayload.alarmbytes = 0x0000; //nothing | alarms

  telemetryData.header1 =  0x55; //Header 1
  telemetryData.header2 =  0x55; //Header 2
  telemetryData.payload = telemetryPayload;
  telemetryData.crc8 = st24_common_crc8((byte*)&telemetryPayload, sizeof(telemetryPayload));
     
  Serial.write((byte*)&telemetryData, sizeof(telemetryData));
  Serial1.write((byte*)&telemetryData, sizeof(telemetryData));

}
 
Last edited:
Telemetry works. In my previous post there is an Arduino example that I used in testing for anyone interested.

What (major) features are missing at the moment when compared to the stock Typhoon:

- Realsense (I don't have one and that one could be a bit too time consuming to implement regarding its use cases.. ;-)
- Obstacle avoidance and sonar (Might implement it some day, haven't found any use for it either)
- Yuneec-specific Smart flight modes
- Wizard (I'm going to take a look at this some day as I kinda like it. This might open some smart mode -like features.)
- Backup link, camera pan (automatic panorama mode however works) and fw updates over camera's WiFi (I am not going to make these.. a way too much work.)
- Some error messages via telemetry (see the code above what is missing.. ;-)
- The IMU heater is always on and the MPU6050 enjoys the 40-50 C temperature it provides (the winter is coming!). This is however something that I'm going to fix some day.

But what the Thunderbird gives in return:

- Aerobatics! ;-)
- Amazing performance
- Smooth handling
- Stock PX4 with all of its features (except logging, there is no SD card slot in the Typhoon's MCU board, soldering pads are there, but components are missing... ;-)
- Payload options (the E90/C23 MIGHT be possible to some extent!)
- It is yours now! ;-) The PX4 is open source, and from the documentation I am going to write (like how the Thunderbird port was done), you'll find out how it works.
- Expansion possibilities (There are few UART's around the drone for payload controllers, you could install a Raspberry Pi onboard the drone to control it, the SR24 radio can be replaced with some other datalink or cellular modem etc. for Mavlink control...)

What next:

- More flight testing
- Documentation

Br,

TR
 
Last edited:
Why I did not find that info above earlier.. I spent quite many evenings with this one. :-D
But what I found out:

- There are indeed two communication modes for the gimbal. The 650 uS PWM enables PWM controlled tilt.
- No previous initialization signals work with the CGO3+
- If the gimbal is connected to the Typhoon, a full serial communication is established between the drone and the camera
- I was not able to figure out the protocol. There were some patterns in the signal, but..
- The bit rate was unknown for me. I could not get rid of serial framing errors (I assumed it being serial). I tried every standard baud rate from 9600 - 921 000 and also the two Yuneec specials; 250 000 kbps (ESC's) and 500 000 (later cameras).
- The Typhoon's back up control link, firmware upgrades, gimbal pan, following etc. are probably transmitted over this
- The PWM interface may be there for compatibility only

I have been working on the CGO3+ serial communication for about a week now. Here are my observations:
- It is 115200 8n1 LSB first.
- The first byte is 0xFE
- 2nd byte is the total length of the packet minus 10 (size of the payload? implying the header is 10bytes?)
- 3rd byte is the sequence number/packet count.
- There are a lot of different packet sizes, but I focused mostly on the 0x1A packet because that seemed to vary when I changed the switches and knobs on the ST16.
- In the 0x1A size packet, bytes 24 and 25 are the gimbal pan command (ST-16 K1)
- In the 0x1A size packet ,bytes 26 and 27 are the gimbal tilt command
- In the 0x1A size packet, I think that bytes 28 and 29 are the tilt mode switch (ST-16 S1) but I need to verify that
- In the 0x1A size packet, bytes 30 and 31 are the pan mode switch (ST-16 S2)
-I'm pretty sure that the last 2 bytes are a CRC and have spent most of the week trying to decode it without much luck.
-Right after start up the TH sends 3 almost identical short packets to the camera. They have 3 byte payloads (13bytes total), and the only values that vary are the sequence byte and the 2 CRC bytes. I have been trying to use those to decode the CRC, but I'm almost sure there is additional info that is being included in the CRC calculation
- Last night I found that the packet format is pretty similar to the Mavlink V1 protocol (Serialization · MAVLink Developer Guide). The first 3 bytes are the same. It is different in that the header size is only 5 bytes. The Mavlink V2 protocol has a 10 byte header, but then other parts of the packets don't match. Maybe it is a combination of v1 and v2? maybe it is customized in some other way?
- IF it is Mavlink like, then there is a CRC_Extra byte that gets added into the CRC calculation somehow. The CRC_Extra byte the CRC of the string name of the message id. So if it uses the standard mavlink message names and ids, I should be able to figure all of this out. I think I'm going to start with finding some arduino code to decode mavlink messages and then feed some packets into it and see what happens.
 

New Posts

Members online

No members online now.

Forum statistics

Threads
20,973
Messages
241,797
Members
27,359
Latest member
tmsmindspace