New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
CC3D_OPBL, enabling PWM reciever mode makes ESCs not working. #2177
Comments
Thats how mine had been. It only worked on 0.5k pid loops |
This is a limitation of the timers used on the CC3D. If you have to use PWM for the RX then you will have to switch to normal PWM for the motors as well, it can't handle oneshot on all the motors. |
BUT, PWM reciever with oneshot 125 works fine on 3.0.1 release version of betaflight firmware. |
We can not hand over things like this to the user to fix, and understand. Constraints like this must be handled by firmware and configurator etc. Preferably the limitations should be fixed, but if that is not possible it must be handled in some way. There are more edge cases like this that is neither fixed, handled nor documented. How would the end user be able to know anything of this? We are close to 3.1 release, but all this is still hanging loose. |
If some one gets me a high res photo of the CC3D I'll map out the pins for the resource command to enable documentation on each option. There's nothing wrong with the wiki, it's just that it's light on - and needs work. Every target manufacturer should document their target on the wiki. It's not fair to expect us to document every target either by code (pwm mapping) or by wiki. |
There's just too many use cases. Broken USB, pads lifted, pwm, ppm, serial... who knows what any user has in their setup. |
@blckmn Can't provide a picture of any use, my CC3D is covered in conformal coat and mud. This is the issue I submitted last year. |
It's for doing up a pin Pxx is this solder pad. So need the high res. I'll see if I can find a shop photo |
The users have a hard time finding the Wiki in the first place. Then finding anything in the Wiki is the next challenge. Being able to understand follow written instructions can be a problem too, for some. And who would be the target manufacturer for CC3D, Naze, Revo etc etc etc? We/me/you are the implementor of things for those targets that makes or brakes things. Would you expect OP or someone else fix or document that? |
3.1 defaults to betaflight pid controller. I find that everytime I try to use betaflight pids on 3.0.1 it goes to legacy. However the CPU usage is much lower than 3.0.1 even on 4k2k. The cycle time is not stable and passthrough doesn't seem to work |
Thanks @YimingT perfect. @andwho the problem is this. For every hardcoded scenario that existed previously - I can give you 20 other edge cases that wouldn't have worked. The fact is reset settings on a board will still give a working scenario. If you want to deviate from that there's an expectation you will do some research, ask some questions. Previously if you wanted to do anything different - you had to setup your own build!!! Least now the possibility of just down loading a setup exists. What I think is wrong here is something different. PWM timer clash protection is possibly been removed in the whole changeover, and simply needs to be looked at and if possible reinstated. The question is for the few users affected is it worth it. Yes it may have worked in 3.0.1 - no probs, that's still a viable option for those users. No one expects windows 10 to run on a 486. |
Yes, I know the advantages of the new IO system. And it is brilliant, for the most part. But is it ready for the poor users? Try to put on the newbee hat and pretend you don't know that much. How would you enter into the BF3.1 universe? Where would you start? Into CLI, typing resource commands? Would not think so.... |
@andwho the issue here though is the use of PWM AND OS125. The problem will be a timer clash (frequencies) and may be possible to resolve, HOWEVER, this particular combination is indeed legacy. My argument is it works on 3.0.1 (as it had PWM timer clash protection), and it may well be that this should be the last version released where that particular combination should be supported. I will take a look in the coming days and see if this is easy enough to put back in or not. |
@Sheynar I think this issue is only affecting setups using PWM as RC inputs, AND any ESC output faster than Standard 1000-2000 PWM. |
oneshot works fine ppm 1k1k and 2k2k. pwm only works on 1k0.5k and 2k0.5k ESCs at 400hz |
Thats correct. PPM has the timer clash protection |
3.0.1 prevents me from using betaflight pids, but 3.1 is betaflight only so that is possibly overload the timers |
Has the PWM input for rx on CC3D been changed? I use a CC3D with CC3D_OPBL.bin 3.1 release. I only changed board orientation yaw, rx to pwm and motor protocol to pwm 400HZ. Looptime 1k/0.5k is stable. But my rx inputs are messed up. TAER worked for me in BF3.01 but now seems to have a new behaviour. Channel mapping is completly different. YAW now acts as AUX1 etc. Is this expected behaviour? Did not arm it using BF3.1 But i also can hear the escs doing some other melody on startup, instead of the init beep. Cant say if they would work. I flew this machine yesterday on BF3.01 with TAER settings and did not touch a pin. But it only worked in legacy pid mode. Also with PWM rx and motors set to pwm@400. PID tuning is quite hard and standart settings behave far away from nice. (Tested with 1k/1k, 0.5k/1k looptimes) At least with this 250 frame/esc/motor combo on BF3.01. (frame has not too much vibrations and FC is softmounted) Is it possible to use PWM for RX and ESC in BF3.1? Or will it be a problem? Sorry if i did miss anything. |
Update: Still only 0.5k pid loops work, escs 123 freak out on 2k pid loop, 4k1k has intermittent control of escs. Blheli passthrough still does not work. |
I have exactly the same problem on CC3D with cleanflight firmware. So, is there any way to make ESCs and receiver both work properly? |
@longxk I think you'll get exactly the same issue on other FC firmwares sharing ***Flight code base (CleanFlight, Betaflight etc). And as i know it affects all FC's, not only CC3D. I've bought PPM controller and all works fine. If you can't get other then PWM reciever, you can add PWM -> PPM(Sbus) decoder between reciever and FC. |
For anyone still interested, I believe I found a fix for the CC3D parallel PWM in and motor outputs. The timer conflict exists, but by reworking which timers are assigned to inputs and outputs will support the parallel PWM in. It does require that one of the pins that was used previously for servo output must now be connected to an auxiliary RX PWM in, but it really isn't a big deal. If for some reason you require more than 4 motors then it also means that one pin from the receiver port is mapped to the ESC. I'm going to test tomorrow and I'll report back on it's stability. I don't really do a lot of GIT push/pulls, so if someone is interested enough to push it back into repository, I'll gladly provide the file that I changed. -Jason |
Sounds nice. Would revive some of my old fc/rx combos. I would at least like to test it, if your tests are successful. |
So I tested with some low level flights and it appears to work fine. The good part is, on v1.12 I only had 1 Auxilary available, but now I have both. I did checking the datasheet and the pin used previously for ESC (now for PWM in) is 5V tolerant so it does not hurt the chip. The other PWM IN pins have filters inline with them, so it was a concern of mine since the ESC OUTs do not have any protection inline if they were used as inputs. |
In the CC3D folder of targets (..\src\main\target\CC3D\target.c) this needs to be redefined:
` to this:
` What I'm essentially doing is moving all Timer3 based channels to the inputs, and all Timer4 based channels to the outputs. The reason it didn't work before is because they were interleaved and the timer needs one base frequency for all channels. So to work for the inputs it needs to be able to accommodate a signal that may have a period of 20ms for the parallel PWM which is way to hard to share that time base with things that work on 2ms (or much faster for Oneshot) base. Your motors won't have to change, and my RX inputs were unchanged if I didn't add and additional AUX channel. |
@dangeljs: Can you please submit a pull request for your fix for the CC3D? |
@dangeljs Cool! Thank you! I will test your approach as soon as possible. |
@mikeller Unfortunately I am not GIT savvy, so I'm not having much luck getting a clean pull request. Do I need to push to my Github account then put the pull request from there? |
@dangeljs: Now is a good time to learn GitHub then. ;-). What you need to do is create a fork of the betaflight project (online). Then clone that fork locally, create a branch, apply your changes to the branch, and push the branch to GitHub (all locally with git). Then go online again, select the branch with the changes, and create a pull request against the betaflight master branch. |
So I think I have it now. I submitted a pull request and I actually see it in the GitHub repository now. Before I was not cloning, I just created a GIT environment. Thanks @mikeller ! |
No, thank you, @dangeljs, for helping improve Betaflight! |
Updating CC3D target file to allow for Parallel PWM to Issue #2177
CC3D_OPBL RC10 Walkera Runner 250c (advance), ESC with BLHELI oneshot 125. Default settings (PPM reciever mode) works fine, when enabling PWM reciever mode (don't touch any other settings) i have one motor initialisation and working, other motors some times sounds like trying to initialise(part of ESCs melody) and dont work. Reciever on PWM works fine.
The text was updated successfully, but these errors were encountered: