Skip to content
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

Copter: remove stale parameter conversions #28951

Open
wants to merge 2 commits into
base: master
Choose a base branch
from

Conversation

peterbarker
Copy link
Contributor

this removes stale parameter conversions.

These patches are all in the Copter-4.0.0 tag, meaning that they are all for upgrading from a version prior to that to a version prior-or-equal-to Copter-4.0.0

Past this a user running a version of ArduCopter < 4.0.0 to something >= 4.7.0 will not have smooth parameter conversions

Board                    AP_Periph  blimp  bootloader  copter  heli   iofirmware  plane  rover  sub
CubeOrange-periph-heavy  *                                                                      
CubeRedPrimary                      *      *           -1720   -3072              *      *      *
Durandal                            *      *           -1872   -3488              *      *      *
Hitec-Airspeed           *                                                                      
KakuteH7-bdshot                     *      *           -1720   -3080              *      *      *
MatekF405                           *      *           -1712   -3072              *      *      *
Pixhawk1-1M-bdshot                  *                  -1704   -3072              *      *      *
bebop                               *                  -556    -5108              *      *      *
f103-QiotekPeriph        *                                                                      
f303-Universal           *                                                                      
iomcu                                                                 *                         
revo-mini                           *      *           -1712   -3072              *      *      *
skyviper-v2450                                         -1192                                    

// PARAMETER_CONVERSION - Added: Jan-2019
{ "RC8_OPTION", 32 },
// PARAMETER_CONVERSION - Added: Aug-2018
// PARAMETER_CONVERSION - Added: Aug-2020
{ "RC_OPTIONS", 0 },
Copy link
Contributor

@rmackay9 rmackay9 Dec 27, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

optionally we could probably drop this RC_OPTIONS line too which is from Aug 2020

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

optionally we could probably drop this RC_OPTIONS line too which is from Aug 2020

Yeah, I really did consider it. But they I couldn't use the pretty straight-forward 3.6.9 -> 4.x.x argument as to why it was time for these to go away :-)

I was also a little surprised at how much of the conversion code did go away. I wonder if we're doing less of it now-adays...

Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM but @bnsgeyer should approve as well because these are mostly trad heli changes

@rmackay9 rmackay9 requested a review from bnsgeyer December 27, 2024 01:13
this removes stale parameter conversions.

These patches are all in the Copter-4.0.0 tag, meaning that they are all for upgrading from a version prior to that to a version prior-or-equal-to Copter-4.0.0

Past this a user running a version of ArduCopter < 4.0.0 to something >= 4.7.0 will not have smooth parameter conversions
despite these looking likely to be conversion information, these are actually default values embedded within the Copter::convert_pid_parameters method
@peterbarker peterbarker force-pushed the pr/remove-copter-param-conversion branch from a28bf19 to 18772d8 Compare December 27, 2024 10:49
@peterbarker
Copy link
Contributor Author

@rmackay9 I've fixed an error in this PR. Currently in master there's a block of code which is responsible for setting parameter defaults on the heli frame - and it's within a method called convert_pid_parameters (mostly not actually PID parameters either...).

I'd like to move that code out in a future PR - it's in the wrong place IMO. Probably move it up, called around the comment "now setup some frame-class specific defaults"

@peterbarker peterbarker requested a review from rmackay9 December 27, 2024 10:55
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants