Thanks very much for testing! We’ve merged the MANUAL_STR_EXPO change to master now so it will be automatically included in 4.4.
Re the other changes, I’m happy to create a Pixhawk1 binary for you if you’d like.
Thanks very much for testing! We’ve merged the MANUAL_STR_EXPO change to master now so it will be automatically included in 4.4.
Re the other changes, I’m happy to create a Pixhawk1 binary for you if you’d like.
Here are two ArduCopter balance bot v4.3beta4 with manual steering expo tests, a good and a bad one, each consisting in an indoors mission, followed by turns in Acro and Manual (MANUAL_STR_EXPO=0.9).
Good (standard DC motors)
Bad (low KV sensored brushless motors)
Here are the logs.
Certainly I would appreciate it, to try other controls on the problematic balance bot (or may be I don’t know how to tune it better), and also considering that I am going to try stepper motors (also on a Pixhawk1).
Hi @Webillo,
Thanks for testing the manual-expo change. I think you’d find that Rover-4.3.0-beta4 performs exactly the same for the two vehicles and I think this means that the balance bot code is just as good as 4.2. Please tell me if you disagree. This question is important for me because we don’t want to release a new version that is worse than the older version.
Here is a Pixhawk1 Rover binary with the pitch limit protection. You will see that ATC_BAL_SPD_FF has been renamed to ATC_BAL_PIT_FF and I think it should be set to 0.4. For my vehicle this new feed-forward allowed me to greatly reduce the vehicle’s wobble.
You’ll also see that there are two new parameters ATC_BAL_LIM_THR (defaults to 0.6) and ATC_BAL_LIM_TC (defaults to 0.5) which control the desired pitch limiting. If ATC_BAL_LIM_THR is 0.6 this means that the desired pitch angle will be reduced back towards zero if the throttle ever climbs above 60%. The ATC_BAL_LIM_TC controls how quickly the pitch protection is invoked (lower numbers invoke it more quickly). I suspect you can leave these parameters at their default.
Re the wobble on the low KV brushless motor vehicle, I think using this new firmware may help but in any case, I think the ATC_BAL_D gain (currently 0.4) is too high. When tuning the pitch control you’re doing this in Manual mode with real-time display of the PID outputs?
Update: here is the pitch-feedforward and pitch protection in action
These are my impressions:
I flashed Rover-440-pitchlim-14Nov2022.apj on the direct drive balance bot. Certainly, the wobble on this low KV brushless motor vehicle has improved a lot, and pitch curves seem to have no oscillations:
This is the log of it (BTW, ATC_STR_RAT_FF lowered) and this is the video with piddesired and pidachieved and the hud in MP.
So observe that piddesired and pidachieved traces move in Acro and not in Manual, but trying Acro a second time, piddesired (blue trace) doesn’t move and it falls immediately.
I don’t think I can test this indoors in a reduced space. Before trying on an outside track (such as here) I would like to have a version not falling easily.
Hi @Webillo,
Thanks very much for the feedback.
The pitch protection should work in all modes. it is possible to make it more conservative by reducing ATC_BAL_LIM_THR from 0.6 to 0.5 (or even a little lower).
By the way, the change was merged to master (aka “latest”) so within 12hrs you’ll be able to just load latest from MP if you like (press Ctrl-Q on the Install Firmware screen).
So bug compensated elsewhere.
Yes, good idea.
Sorry, I hadn’t completed the update process; corrected now.
This is the end:
Yes, there is overshoot in graphic above, but not so much in the video:
Here’s the line that checks for the time difference being too large (>0.1 sec) and if it is, then it uses the system time. This is why the old us vs ms bug was not found sooner.
The tracking looks quite good in the video except for the end of course. By the way, I’ve updated the pitch tuning instructions to include an explanation about how to get faster PID output displayed using the “message interval” feature.
Nice. You can add:
This is a video with new tuning:
Observe the low noise (upper microphone for catching it better) and the fast spins in Manual.
But now I cannot do missions for what I think is a hardware problem on the left wheel which has been there for ever: it gets blocked frequently (seems to disappear with fast throttle input forwards or backwards), and I have pending to distinguish if it is the motor or its controller (perhaps heard here). I haven’t found any parameter influencing this (seems sensors sync). It only happens on the left wheel, and seems to appear specially if the vehicle is moreless quiet (so it was less frequent before with more pitch vibrations). So in the meanwhile I will start with the stepper motors version.
Question: why ATT DesYaw always appears 0 when examining logs?
Hi @Webillo,
Well, that tune looks great!
ATT.DesYaw is always zero because we don’t actually use an absolute yaw target even in Auto mode. The highest level yaw control is just turn rate (or lateral acceleration which can be converted to turn rate using the vehicle’s forward-back speed).
I’ll update the “reduce drift with pitch trim” section.
For testing a balance bot with stepper motors, I had available two Pololu TIC T500’s and two HK42BYG250-001 stepper motors (with encoders). I had tried unsuccesfully in the past, but I didn’t dedicate much time.
This is the motor documentation:
From the chip documentation (Honeywell SS526G), it needs pullups and this is the signal description:
Programming the TIC T500’s for an RC pulse (bidirectional: <1500µs backwards, 1500µs neutral and >1500µs forwards) and using a servo tester (moved around 1500µs), therefore not requiring direction information from the FC (RELAY_PIN/RELAY_PIN2), I could get this oscilloscope capture:
Pending to complete this balance bot setup (it can go incredibly slow with 1/8 stepping, and torque seems high), obviously I don’t know how to get WENC signals as with other balance bots.
Is any trick possible to admit speed/direction (Honeywell) instead of direct/quadrature encoder signals, or will this be supported in the future (new as WENC_TYPE=2 (Honeywell))?