Home Forums Everything about everything else Triflight 0.7 Beta 1

Viewing 15 posts - 46 through 60 (of 143 total)
  • Author
    Posts
  • #37423
    bhuism
    Participant

    Ok, I’m out of options in getting the servo feedback wire working on bff3. Custom bff3 firmware’s with (target.c):

    #define EXTERNAL1_ADC_PIN PA8 (let strip)
    or
    #define EXTERNAL1_ADC_PIN PB7 (ppm)

    and

    set tri_servo_feedback = EXT1

    did not work.

    Wat happens is, the servo speed calibration throws the servo one time full deflection then centers and stops (not a couple of throws as normal). The voltages I measure on the feedbackpin are correct, pulse 1086 = 1.021v (min deflection) and pulse 1973 = 2.460v (max defection).

    I guess there needs to be more software configuration in order for these pins to be readable by the tailtune logic?

    #37424
    jihlein
    Participant

    @bhuism, from what I found testing, the EXT1 analog inputs don’t work in this release. I made some quick code patches for the Naze32, and now I can get functional tail servo feedback on that board via EXT1, as evidenced by the un-armed tail tune completing the servo speed calibration. I need to clean up the code changes some, and I’ll send a PR to @lauka. These changes may also fix your issues with the BFF3 board not working with EXT1.

    #37426
    jihlein
    Participant

    @lauka, I created a PR that fixes EXT1 ADC input functionality. Checked out on NAZE32 hardware, but I’m unable to test other targets.

    #37430
    bhuism
    Participant

    @jihlein, I’ll try to create a PR for BFF3 when I get it working, thanks!

    #37431
    lauka
    Participant

    @jihlein: Great! I will merge it in and probably create beta 2 for it.

    @bhuism: The problem with BFF3 analog inputs is that they are tied to ADC2 in code.

    ADC2 pins are:
    – CH1: PA4 (used by VBAT)
    – CH2: PA5 (used by CURRENT)
    – CH3: PA6 (used by PWM1)
    – CH4: PA7 (used by PWM2)
    – CH12: PB2 (used by RSSI)

    You would have to move the servo and motor outputs around to free either PA6 or PA7 for EXT1.

    One of the motor or servo output can be moved to the PPM input pin for example.

    #37434
    jihlein
    Participant

    @bhuism,

    Here’s how to get the servo fdbk on PWM Output #1 pin. Note that this change takes over the use of that pin, and you will have to remap the other resources accordingly. The PWM2 pin will actually now be PWM1, etc., and there are only 7 PWM outputs now.

    In target.h, add this line to the adc setup block:
    #define EXTERNAL1_ADC_PIN PA6
    Change the last line from:
    #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
    to:
    #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(17) )

    In target.c, comment out the following line:

    // DEF_TIM(TIM16,CH1, PA6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM1

    I can say the target builds with these changes, not sure if it works, needs testing.

    #37435
    bhuism
    Participant

    Thanks guys, I think I get it now. I also see why only these pins are eligible for ADC2 work in the f3 datasheet. I can’t just use the resource command to set PWM1 (PA6) to NONE, and move PWM1 to PPM (PB7)?.

    I didn’t think it would be this much work to get feedbackwire working, since there are no free ADC2 pins left. Maybe I’ll try removing the components which screw up the normal feedbackwire working on the RSSI pin on the bff3, and find out where I can solder the PB2 pin.

    #37436
    jihlein
    Participant

    “use the resource command to set PWM1 (PA6) to NONE, and move PWM1 to PPM (PB7)”

    You could try this along with just #define EXTERNAL1_ADC_PIN PA6 and see if it works. That’s a cleaner solution.

    #37437
    LitterBug
    Participant

    All this remapping talk makes me SOOOOooooo glad I am using the RCExplorer F3FC controller on my Tricopters. Works right out of the box.

    Cheers!
    LitterBug

    #37438
    bhuism
    Participant

    Exactly my idea @jihlein, I’ll try that tonight, keep u posted.

    #37440
    TheZoq2
    Participant

    I have been having some trouble tuning the yaw on my tricopter (custom 3d printed, about the same size as the mini) which is running the latest triflight beta. I got it working decently however, when quickly changing the throttle, it doesn’t keep straight. When analyzing the blackbox data, I noticed that the yaw P compensation has a weird pattern. Here is a screenshot of what im talking about Weird P values http://imgur.com/tmFFqfa. Here is the full blackbox log https://drive.google.com/open?id=0B-ZjOK5GhXS_SlBkdkVOT0xQRVk

    As you can see, the P curve seems to follow a line but it has a ton of drops from that value which don’t seem to correspond to any gyro value. The I and D gain don’t have this effect, however there was a ton of noise on the D value until I lowered the gain from 105 to 60.

    Is this a configuration issue or some strange software/hardware issue?

    #37442
    lauka
    Participant

    On my phone now, I’ll check the log later during the weekend. I have seen the same occasionally on my copter, but in much smaller magnitude.

    If you’re going out flying again, you could try setting tri_motor_acc_yaw_correction to 0. Check if it reduces the drops in the p term.

    #37444
    TheZoq2
    Participant

    Alright, I’ll try that tomorrow

    #37448
    TheZoq2
    Participant

    That seems to have fixed both the choppy P values and the yaw when quickly changing throttle. Thanks

    #37449
    lauka
    Participant

    @TheZoq2: Okay there’s something wrong in the motor model, maybe the filter implementation has changed somehow. Would you mind doing more testing if I provided you a new HEX? Or you just want to fly? 🙂

Viewing 15 posts - 46 through 60 (of 143 total)
  • The forum ‘Everything about everything else’ is closed to new topics and replies.