ArduPPM : - PPM encoder version 3.0.1 beta 1 available -

1,969 views
Skip to first unread message

Olivier ADLER

unread,
Nov 14, 2013, 6:08:03 PM11/14/13
to drones-...@googlegroups.com


Hi, i did push ArduPPM version 3.0. 1 beta 1 to my GitHUB.

https://github.com/Olivier-ADLER/ardupilot/tree/ArduPPM_v3/Tools/ArduPPM

A binary is available in the binaries folder.


I did modify the arduino usb driver, removing LED control, so that APM 2.x USB TX and RX LEDs can be used to check ArduPPM inputs when connected to Mission Planner. It's here : https://github.com/Olivier-ADLER/ardupilot/tree/ArduPPM_v3/Tools/ArduPPM/ATMega32U2



It is a merge of the actual version 2 ArduPPM code, plus the PPM redundancy mode i did start to work on about one year ago.


After a full week of coding and tests, i'm happy with it (using Jeti transmitter / receiver hardware for my test setup) and should works with almost all hardware brands using PPM thanks to auto polarity and auto channel count detection.

I did test PPM signals ranging from 4 to 16 channels, positive or negative polarity, 10 to 30 ms frame period. All of them did successfully pass tests, from 750 us to 2250 us (or 150 % range on Jeti transmitters).

It's now time to test this beta so that we'll be able to release a RC version for public testing before final release.


John Arne Birkeland, creator of the ArduPPM servo and passthrough code and main contributor to ArduPPM, is actually working on a new servo mode version, with even better performances (less jitter), that could be integrated inside version 3 if it does show good performances and reliability (and if John's spare time is available too :=). I'm quite confident when i watch for John's low level programming expertise.


For those interested in the PPM redundancy mode i did joined the manual as a .txt file.


There are three important points in this release :


1) Three failsafe methods are now available at compile time, so that it will be possible to choose the best compatible one when the next ArduPilot and ArduPPM v3 release will be ready.


FAILSAFE_MUTE       // Failsafe method muting ppm output ( mainly for use with other systems )

FAILSAFE_THROTTLE // Legacy throttle failsafe method using a low value (900 us) on the throttle channel

FAILSAFE_EXTRA_LOW // Preferred new method using extra low PWM
values on missing channels ( 700 us is the value i would suggest if possible for the APM ).


The FAILSAFE_EXTRA_LOW method will be the preferred one, because it will be channel order agnostic, and will allow for the APM to make a difference between a PPM encoder hardware fault, or a receiver fault.


2) PPM redundancy mode is now working and will permit to connect one or two PPM receivers at the same time. Here is the manual summary :


Introductory :
------------------

PPM redundancy mode is a dual input PPM passthrough mode, with automatic switchover if one input is lost.

How to connect ?
------------------------

PPM input 1 (primary receiver) : PWM connector channel 1
PPM input 2 (secondary receiver ) : PWM connector channel 5
The two radio receivers can have different frame formats (polarity, channel count, sync width, frame period) and do no not need to be synchronized.


How to enable PPM redundancy mode ?
-------------------------------------------------------

To enable PPM redundancy mode, short the servo input channel 7 & 8 signal pins together using a jumper strap. The jump must be present before powering the APM board. This jumper is checked during bootup, the ArduPPM mode will not change if this jumper is removed or lost during operation.

To confirm redundancy mode, the green LED will light on the APM 2.x board (near the USB port).


What will it do ?
---------------------

This mode can replace advantageously the actual PPM passthrough mode, even if used with a single input, to sanitize the PPM signal, avoiding APM interrupt overload if something goes very wrong at the receiver side (mad PPM signal). This is something that is unlikely to occur, but it is still good to be protected.
The biggest improvement is the possibility to use two receivers at the same time, for example a GHz link and a MHz link for redundancy.

How does it work ?
--------------------------

PPM redundancy mode will closely watch the input signals, checking for sync and channel validity. It will switchover PPM inputs if one of them becomes invalid.

PPM input 1 is the preferred input, it will switch to PPM input 2 during a forced switchover, or if channel 1 is invalid and channel 2 is valid. If both signals are valid, input 1 is selected.



Witch PPM formats are compatible ?
--------------------------------------------


PPM redundancy mode accept standard PPM signals, commonly known as Futaba trainer interface signals :

Negative PPM frame :

¯¯¯|__|¯¯¯¯¯¯¯¯|__|¯¯¯¯¯¯¯¯¯¯¯¯¯¯¯¯¯¯¯¯¯¯¯¯|__|¯¯¯¯¯¯¯¯|__|¯¯¯¯¯¯¯¯|__|¯¯¯¯¯¯
----->|<---ch8--->|<----frame sync symbol---->|----ch1----|----ch2----|----ch3--
               
 
Positive PPM frame :

___|¯¯|________|¯¯|________________________|¯¯|________|¯¯|________|¯¯|______
----->|<---ch8--->|<----frame sync symbol---->|----ch1----|----ch2----|----ch3--
       

The PPM polarity and channel count is automatically detected during first PPM input acquisitions.
Then the decoder keeps this setting until power off.



It does accept :

- negative (more common) or positive PPM polarity with initial detection.

- from 5 to 16 channels with initial channel count auto detection (settable at compile time).

- channels lengths from 725 to 2275 us (settable at compile time).

- channel sync pulse lengths (prepulse) from 200us to 525 us (settable at compile time).

- frame sync lengths from 2700 us to 32 ms (settable at compile time).


The PPM input validity monitoring is agnostic to frame period and frame period variability, as soon as channel sync and frame sync timings are ok. This is a desired feature because some transmitters do not deliver a stable frame period and anyway frame period stability is not necessary to correctly transfer a PPM signal. This is even more true with GHz links, where error correction in the air  protocol can delay some frames.


There are a couple more options settable at compile time :

- force switchover channel

- allow polarity detection after a watchdog event

- allow channel new detection after a watchdog event

- allow dynamic channel count detection

- failsafe strategy options




---------------------------------------------------------------------------------------
Note for testers and developers :

Channel 1 and 5 inputs as well as the jump strap between channel 7 and 8 have been chosen to avoid conflicting with the SPI port, so that easier debugging and programming can be done without using a one wire debug connection.

Using this setup, it is possible to program and debug using a 6 pin ISP probe connector, in ISP mode or One wire mode. So you’ll not need a non standard one wire cable. Your probe will work in both modes without any problem. This is nice if if you prefer to stay away from one wire debugging.
Because PPM Passthrough mode is using a jump between channel 2 and 3, mode detection will not work if a 6 pin probe is connected to the SPI port. To solve the problem you could disconnect the probe before powering on, or force the encoder mode modifying servo_input_mode variable initialization.

In some circumstances, the AVR MEGA chips can stay locked in one wire debug mode without possibility to get it disabled. So if you don’t absolutely need this mode, it could be better to stay away from it. We can suppose that ATMEL did solve this issue in recent production batches but I personally bricked an APM board last year because of that.

I did the actual debug in one wire mode using AVR Studio 5 to be able to probe variables and set breakpoints. It’s the only debug mode that do allow this with the 32U2 chip. ISP will only permitt programming and fuses settings.

As a supplementary debug help (at least in the release candidate version), i did modify the Arduino USB driver so that RX and TX leds are disabled during USB communication. They are dedicated to the PPM redundancy mode monitoring. The APM board can be connected to Mission Planner to read  radio PWM values for verifications. The TX / RX LEDs will be dedicated to PPM redundancy mode error reporting avoiding the USB dancing LED pattern.

Failsafe note : the 700 us failsafe signal value was chosen to allow using radio transmitters at their maximum 150 % channel range (750 us – 2250 us) without affecting failsafe signaling that will occur below at 700 us. Such a very large range could be used for example to enhance channel resolution.

Happy testing and flying.


Olivier ADLER – 2013 -

manual_redundancy_mode.txt

Randy Mackay

unread,
Nov 15, 2013, 1:09:01 AM11/15/13
to drones-...@googlegroups.com
Olivier,

     Congrats on the new version.  Some general questions/comments:
         1. I think the majority of people are moving to ppmsum or sbus type connections.  Is the negative polarity equivalent to SBUS?
         2. I somewhat wonder if having support for an additional receiver is worth the additional complexity.

     In a somewhat unrelated event, I've found that in the current official version of the ppm encoder, if I use a ppmsum receiver that stops sending the stream on a failsafe event, the ppmencoder briefly outputs 900 on all channels before outputting the expected values of 1500 for all channels except ch5 which is 1555.  I've created a video of this behaviour here:   http://youtu.be/fXHEbZJD8JI

-Randy



--
You received this message because you are subscribed to the Google Groups "drones-discuss" group.
To unsubscribe from this group and stop receiving emails from it, send an email to drones-discus...@googlegroups.com.
For more options, visit https://groups.google.com/groups/opt_out.


Olivier ADLER

unread,
Nov 15, 2013, 4:55:43 AM11/15/13
to drones-...@googlegroups.com, Randy Mackay

Hi Randy,


1. I think the majority of people are moving to ppmsum or sbus type connections.  Is the negative polarity equivalent to SBUS?

No, SBUS is a different digital protocol. PPM is a time multiplexed PWM protocol where channel widths are encoded in an analog form.

See some informations about SBUS here :

http://forum.arduino.cc/index.php/topic,99708.0.html


Jeti EX Bus is another digital protocol,more open. The specification is freely available for developers. The bad point is that each radio RC manufacturer has now a different protocol.

It's difficult to support them because it's a moving target with new protocols or protocol versions every six months.

 For basic uses, a simpler and open protocol is UDI (universal digital interface), a simple unidirectional protocol, similar to PPM but in a digital form. Jeti, JR and Vstabi are supporting it.


Negative PPM is the more common PPM modulation in the RC world. Positive it the same thing with a minor difference : polarity is simply reversed. I think that most decoders are agnostic to polarity.

2. I somewhat wonder if having support for an additional receiver is worth the additional complexity.

Yes you are right, a minority of users will use or will need two receivers. But :

1) The PPM redundancy mode is designed to work with a single receiver. In this setup, it will sanitize the PPM input signal so that the APM cannot be interrupt overloaded if the PPM input becomes mad.

2) As opposite to the previous PPM passthrough mode, the redundancy mode is a true decoder, so that it is possible for example to get the digital Data in the channel width structured array, and send it through the SPI port for example to the main AVR or another chip.

3) The dual receiver setup has some really exciting uses, not only for redundancy, but for dual pilot setups as well (teacher / student, dual pilots to extend flying area and piloting precision capabilities). The point here is that this new mode has a feature i did name force switchover, where the PPM1 input is able to force the switching to PPM2 input through a channel (by default the last channel of PPM1 input must be rised to a PWM value > 2000.


Here is what i'm saying in the manual about this :

Some standard or  more creative uses of the redundancy mode :

- Single PPM input sanitizer : to check for a clean signal before to send it to the APM

- Classical redundancy with two receivers : if a radio link is lost, the remaining one takes precedence. This feature will take benefit of using a GHz link as the primary one and a MHz link as the secondary one, effectively enhancing radio redundancy using very different frequency bands.


Because the redundancy mode has a manual switchover control, those creative uses are very possible :

- Teacher / student mode : using the force channel, it’s possible to give control to the student from a teacher transmitter switch.

- Dual pilots setups : to fly in large areas or when there are large obstacles it can be useful to share the RC control with a second pilot.

In those cases, each receiver needs to be paired with a separate transmitter.

Because the RC sharing occur at the model location in the air it is a decisive advantage over linking RC transmitters on the ground using a cable or a GHz link. When ground linking offers about hundred  meters of reliable distance separation (or even less if there are obstacles), air sharing could allow for a few hundred meters or even more.




the ppmencoder briefly outputs 900 on all channels before outputting the expected values of 1500

I've seen that during testing. We'll take care that it is not the case anymore in the release version. It could be because the PPM polarity is reversed when we trig the PPM generator. The redundancy mode could reverse the PPM generator polarity according to the input polarity in the next version to avoid momentary decoding errors at the APM side.

We'll test this more deeply and eventually we'll modify the APM decoder if needed, because at the same time it would be nice if the APM decoder could detect the polarity. This would be a nice feature to log receiver switchovers in the APM flash. If you watch at the PPM redundancy // Todo in the code, you'll see that this is something i'd like to add.


Olivier

Chris Anderson

unread,
Nov 15, 2013, 5:50:32 AM11/15/13
to drones-discuss, Randy Mackay

Very impressive, Olivier. I assume this should be eventually shipped with our hardware. What sort of verification / testing will be needed before we make that change?

Chris

Olivier ADLER

unread,
Nov 15, 2013, 6:40:13 AM11/15/13
to drones-...@googlegroups.com, Randy Mackay

Hi Chris.

We need a short developper testing phase first. I did contact John Arne Birkeland and he should be able to work on testing to confirm compatibility and reliability. At the same time i think that he will integrate its new servo PWM code, with even better performances.

Other developers / testers can jump on testing as well if they are interested.

Next we'll need a public testing phase, where a small group of advanced users will test it so that we can be sure that we do not have a hardware compatibility problem with common RC hardware.

I think that this will need from one to two months. At the same time, we need to make a couple modifications in the APM code, to support the new failsafe method using Extra low PWM values on missing channels. This is desired mainly to get failsafe signaling agnostic to channel order, so that autopilot boards and RC hardware can use any channel for any function keeping the failsafe function intact.


Then it will be possible to program production boards with ArduPPM version 3. There will be no hardware modification necessary.



Olivier

Olivier ADLER

unread,
Nov 17, 2013, 6:11:22 AM11/17/13
to drones-...@googlegroups.com, Randy Mackay


3.0.1 beta 3 is now available. I did add a Documentation folder, with the manual for PPM Redundancy mode and all code flow charts.

We need a few more testers so that the PPM decoder can be tested against different RC hardware.

I did add the .hex file so that it is not necessary for a tester to compile the source.

The source is here :

https://github.com/Olivier-ADLER/ardupilot/tree/ArduPPM_v3/Tools/ArduPPM/Libraries


Olivier


ArduPPM_polarity_and channel_count_detector_v3.pdf
ArduPPM_ppm_decoder_v3.pdf
ArduPPM_switchover_v3.pdf
ArduPPM_task_optimizer_v3.pdf
manual_redundancy_mode.txt
ArduPPM v3.0.1 beta 3.hex
Hash.txt

Randy Mackay

unread,
Dec 6, 2013, 11:44:09 PM12/6/13
to drones-...@googlegroups.com

     By the way, we found what appears to be a bug in the current ppmencoder software today when using a ppmsum receiver and when power to the receiver is lost.

     The discussion is here:  http://www.diydrones.com/forum/topics/rtl-mode-cuts-motors-off-and-falls-to-the-ground

     the video is here:  http://www.youtube.com/watch?v=qDMRW04Ui2o

     The problem can be recreated by doing this:
          1. attach a ppmsum receiver to the APM2
          2. disconnect only the power wire to the receiver
          3. the throttle will drop temporarily to 1100 before dropping to 900

     If the user has the FS_THR_VALUE set to say 960 (like I do) this has the nasty effect of reducing the throttle to zero for a moment before the failsafe kicks in.  The bad news being that if you're in stabilize mode it causes the copter to disarm in the air instead of initiating the RTL!

     If this is fixed in the new version then I'm suddenly very interested in it being released.

-Randy



Randy Mackay

unread,
Dec 6, 2013, 11:59:54 PM12/6/13
to drones-...@googlegroups.com

     Sorry to reply so quickly, but I just quickly tested the new ppmencoder software and it does appear to fix this issue.  The throttle drops to 900 immediately when power to the receiver is cut.

     One bad thing about this version is that it (like earlier versions) still sets ch5 to 1555 and all other channels to 1500.  These inputs will be ignored in AC3.1 but I think it would be better if the ppmencoder does not change any channels when the signal is lost.  I'd even prefer if it simply stopped sending updates to the main code because we can capture that as well in the flight controller code.

-Randy

Olivier ADLER

unread,
Dec 7, 2013, 6:11:39 AM12/7/13
to drones-...@googlegroups.com, Randy Mackay

Hi Randy.

Version 3.01 do have three options for failsafe, so that it can be adapted easily to our needs. For example, the desired failsafe behavior could be certainly different for the standalone board because it can be used with other autopilots.

The compiled 3.0.1 version do use the conservative "FAILSAFE_THROTTLE" option.

FAILSAFE_MUTE is an alternative we could use now.


FAILSAFE_EXTRA_LOW is the ideal solution for the near futur, it gives mainly three advantages :

- is channel order agnostic. This is an enhancement compared to the FAILSAFE_THROTTLE method where channel 3 cannot be exchanged with another channel.
- gives a clear report of the failsafe situation, so that the APM can decide what to do with the remaining channels.
- the APM know if the problem does come from the PPM encoder or from the receiver (a missing signal means that the PPM encoder is dead).

FAILSAFE_EXTRA_LOW is using an extra low PWM value, i would recommand 700 us, to avoid confusion with RC radio signals that can be in the 750 - 2250 us range. This is the value i did put in the 3.01 code but there is a define if needed to change it.

Let me know if you want to try other options i can compile it.


Those options are :

// -------------------------------------------------------------
// FAILSAFE MODE
// -------------------------------------------------------------

// FAILSAFE_EXTRA_LOW is the preferred new failsafe method
// Check compatibility with your APM board firmware
// Channel failsafe value for each lost or invalid channel
// will be the extra low value specified with PPM_CHANNEL_LOSS setting
// available in the "PPM output special values" section

#define FAILSAFE_MUTE 0 // Failsafe method muting ppm output ( mainly for use with other systems )
#define FAILSAFE_THROTTLE 1 // Legacy throttle failsafe method using a low value (900 us) on the throttle channel
#define FAILSAFE_EXTRA_LOW 2 // Preferred method using extra low PWM values (700 us) on missing channels or on all channels for PPM modes.

#define _FAILSAFE_METHOD_ FAILSAFE_THROTTLE // Select the failsafe method here

Robert Lefebvre

unread,
Dec 7, 2013, 7:25:22 AM12/7/13
to drones-discuss
Yow, scary stuff!  Glad at least we have a fix already.  Always good when users help us track down these issues.  Would be great if we had a "gold star" feature on the forums. :)

Craig Elder

unread,
Dec 7, 2013, 1:23:46 PM12/7/13
to drones-discuss
Do you suppose there is anybody left who uses the CH5 set to 1555 option as their failsafe trigger of choice?

It seems to me like something we should be depreciating.

Olivier ADLER

unread,
Dec 7, 2013, 3:41:53 PM12/7/13
to drones-...@googlegroups.com

True.

On the other end, keeping the last known values is not a good practice because it is quite possible to see some fanciful data before a full blackout.

For example, i remember a radio transmitter that was pulling channels to a low value when switching it off.


The most reliable solution is to mute the output, or send an extra low value on all channels (for PPM modes) or missing channels (for PWM servo mode) so that the main APM code can decide what to do.


We should decide now which method to choose, FAILSAFE_MUTE or FAILSAFE_EXTRA_LOW.


FAILSAFE_MUTE will only ask for a small modification in the APM code : make the "missing frame radio failsafe" timeout a bit shorter. I think that the actual timeout is 1 second before switching to radio failsafe when the PPM frame is missing. A 250 ms timeout should be ok. FAILSAFE_MUTE will be compatible with the actual APM code.


FAILSAFE_EXTRA_LOW is certainly the best option, but will ask for a more invasive APM code modification and a sync between PPM encoder and APM versions.


This mean that if we decide to use FAILSAFE_EXTRA_LOW, users buying new APM boards will need to use the latest APM code.

Eventually, we could use an APM jumper (we have two free 2mm jumpers for the PPM encoder) to choose the failsafe method. The boards could be delivered with the FAILSAFE_MUTE method, and switched later to FAILSAFE_EXTRA_LOW method adding a jumper.

I did ask to put those PPM encoder jumpers during the APM beta phase in anticipation for such a need.

Olivier

john...@gmail.com

unread,
Dec 8, 2013, 11:10:54 AM12/8/13
to drones-...@googlegroups.com, Randy Mackay
Hi Randy.

The only time the current PPM encoder will output 1100 on throttle is just after power up. After this it's either last know or fail-safe (900). Meaning that the 32u2 was reset when the cable was disconnected.

So what happens is that when power is restored the PPM encoder starts outputting default values (1100), and then after 250ms the watch-dog triggers since there is no input signals and outputs f/s (900). This also tells me that the power cut is clean. If the power cut was a low voltage dip, then the PPM encoder would have restarted with the brown-out flag set and immediately started outputting f/s (900) instead of default 1100.

The short term solution (until Oliviers new v3 is proven) is to disable any default of f/s output from the PPMencoder when in ppmsum mode. This will work now, with the missing input changes done to ppm decoder in APM.

- JAB

john...@gmail.com

unread,
Dec 16, 2013, 2:53:56 PM12/16/13
to drones-...@googlegroups.com, Randy Mackay
Since the V3 has some major changes and still hasn't been tested enough for a public release.  I've just made a pull request for a ArduPPM v2.3.17  in the mean while, addressing the problems with pulling receiver power. The modifications are minor and have been testes at my end, and should be safe for a public release. I've attached a 32u2 binary for testing.


- JAB

On Saturday, December 7, 2013 5:44:09 AM UTC+1, Randy Mackay wrote:
ArduPPM_v2.3.17_ATMega32U2.hex

Randy Mackay

unread,
Dec 16, 2013, 8:56:34 PM12/16/13
to drones-...@googlegroups.com
JAB,

     Thanks for that and the explanation.  I guess we will discuss on the dev call today the direction...

-Randy

Phillip Smith

unread,
Feb 7, 2014, 7:04:15 PM2/7/14
to drones-...@googlegroups.com
Olivier,

I stumbled upon this post after fighting issues with the ArduPPM.  Previously I was running 2.3.16.  I was running into issues where when RX signal stopped due to "failsafe" I'd get lots of bizarre behavior from the APM.  I am using a lemon-rx PPM enabled RX.  The issues persist into Beta 5 of the code.  When the TX signal is lost, the lemon-rx drives the PPM output low.  This causes one of 3 things to happen in the ArduPPM.

1. ArduPPM notices the lack of signal and engages failsafe values
2. ArduPPM notices the lack of signal, but for some reason allows the throttle channel to go full (2100).
3. ArduPPM does something screwy and all channels go full (2100)

#1 is the most common result, followed by 2, then 3.  I can repeat all of these results by repeatedly turning my TX on and off.  Does the ArduPPM not correctly handle having the PPM signal driven low?

Phillip

john...@gmail.com

unread,
Feb 8, 2014, 7:46:33 AM2/8/14
to drones-...@googlegroups.com
I am a bti stumped since there is no code in the ArduPPM what can/will set PWM vales to 2100 except from external control inputs, so there is something else going on.
Have you confirmed that the RX outputs is actually dead when this happens?

- JAB

Phillip Smith

unread,
Feb 8, 2014, 7:55:18 AM2/8/14
to drones-...@googlegroups.com
Yes I verified that RX output goes low, but know I did it using an arduino Oscope (all I have).  Output goes to low.  I believe the Arducopter itself is doing this as I have commented out all of the watchdog code in ArduPPM and the problem persists.  It almost seems like an overflow somewhere as it only occurs after the throttle has been set to high at least one time.  It also only occurs after about 3-4 seconds of purely low output from the RX.

Also, I'm pretty sure it is not the RX doing it because you can replicate the same behavior by simply connecting the signal wire on the APM to ground on channel 1 when using the PPM jumper on 2/3.


john...@gmail.com

unread,
Feb 8, 2014, 1:35:26 PM2/8/14
to drones-...@googlegroups.com
Sorry, I misread you post and asummed you where still on the 2.3.x ArduPPM firmware. I do not know the behavior of the new 3.x well enough to comment on that.

- JAB

Phillip Smith

unread,
Feb 8, 2014, 1:39:45 PM2/8/14
to drones-...@googlegroups.com
JAB,

I've tried 2.3.16, 2.3.17, and 3.0 beta 5.  Problem exists in all firmwares.  I'm pretty convinced that the problem lies inside the ArduCopter source itself or the RX I have is outputting something I cannot see on my poor man's oscope.

Phillip

Gregor Meyer

unread,
Feb 13, 2014, 1:52:06 AM2/13/14
to drones-...@googlegroups.com
Hi,

Is there a chance to get the signal off functionality in case of Graupner/JR PPM SUMOut Failsafe working with the new firmware?

Graupner/JR sends no further signal in case of Failsafe with PPM SUMOut, but the Encoder with 2.3.16 or Pixhawk makes a Hold out of this.

In beetween there is a workaround with a new receiver firmware, but it would be fine if this get fixed with the new release.

sufendi lie

unread,
Jul 27, 2015, 12:48:29 AM7/27/15
to drones-discuss, cont...@nerim.net
hi Olivier, 
I am trying to develop apm sbus to cppm converter based on atmega32u2. just like this video link does:

I am not an expert in avr world but,
I also have study sbus protocol and timer configuration at atmega32u2.
I also can succesfully upload .hex file using FLIP to target chip. 

now, the question are. 
what software I must use to edit and compile your code to .hex?

Thanks,

sufendi

john...@gmail.com

unread,
Jul 27, 2015, 1:25:00 PM7/27/15
to drones-discuss, cont...@nerim.net, sufendi....@gmail.com
On windows use Atmel AVR Studio with full integrated IDE, or just use the toolchain directly and some other editor like notepad+ if you don't want the clunky IDE.
http://www.atmel.com/microsite/atmel_studio6/
http://www.atmel.com/tools/ATMELAVRTOOLCHAINFORWINDOWS.aspx

On Linux compile using GCC + AVR Libc:
https://gcc.gnu.org/onlinedocs/gcc/AVR-Options.html
http://www.nongnu.org/avr-libc/

JAB
Reply all
Reply to author
Forward
0 new messages