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

AP_SerialManager: RegisteredPort, add bytes_per_second/baudrate methods, proper flow control for MAVLink via DroneCAN #28315

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

olliw42
Copy link
Contributor

@olliw42 olliw42 commented Oct 5, 2024

The RegisteredPort class in AP_SerialManager derives from the "naked" AP_HAL::UARTDriver class, and therefore provides its bw_in_bytes_per_second() method. This method however returns a default bytes/seconds of 5760 (https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_HAL/UARTDriver.h#L151-L153).

The registered port is used by e.g. the DroneCAN serial class, in order to do e.g. MAVlink via DroneCAN tunneling. The MAVLink flow control of the parameter stream and mavftp however relies on the value returned by bw_in_bytes_per_second() (https://github.com/ArduPilot/ardupilot/blob/master/libraries/GCS_MAVLink/GCS_Param.cpp#L56, https://github.com/ArduPilot/ardupilot/blob/master/libraries/GCS_MAVLink/GCS_FTP.cpp#L500). Therefore, currently it only works properly if the default of 5760 is in fact appropriate. There is no means to change this.

This PR adds the missing bw_in_bytes_per_second() method to the RegisteredPort class (and in addition also adds the get_baudrate() method, to be consistent).

This has the effect that the setting in the parameter CAN_D1_UC_Sx_BD results in respective return values for bw_in_bytes_per_second(), so that the parameter/mavftp flow control has an idea.

OT note:
The whole baudrate thing is actually pretty wild. Each AP_HAL::UARTDriver has it's own baudrate field, when there is a state.baud in the serial manager class, and in addition the DroneCAN serial class also maintains it's own baudrate field. I think what actually should be done is that the generic AP_HAL::UARTDriver class gets a baudrate field (pretty much like it also has a parity field https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_HAL/UARTDriver.h#L222). This would allow defining proper default methods for bw_in_bytes_per_second() and get_baudrate(), and the higher classes would not have to always do the same thing over and over again. Also the baudrate mapping could be moved to the generic begin() and similar methods, so that its baudrate field would always hold the correct value. I think this would simplify the code in sevral places a good bit (maybe also saving flash). Unfortunately I don't have the oversight to know if such a change would not have side effects, hence I here propse the simple "work around".

Tested on the bench using a MatekH743 flight controller with Plane firmware, and a Matek DroneCAN-ized mLRS receiver.

Copy link
Collaborator

@andyp1per andyp1per left a comment

Choose a reason for hiding this comment

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

LGTM

@olliw42
Copy link
Contributor Author

olliw42 commented Oct 5, 2024

to give you guys something to think about, here how it would look like if one would add a baudrate field to the generic UARTDriver class:

olliw42@9c000a6 AP_HAL: UARTDriver, add baudrate
olliw42@32e34c2 AP_DroneCAN: DorneCAN serial, remove baudrate as now in UARTDriver class

It achieves the same as this PR. It is "better" in as much as it

  • doesn't call AP_SerialManager::map_baudrate(baud) for each call
  • opens a path to simplify & streamline the code in the derived uart classes (they all define their own _baudrate or _uart_baudrate etc field)

So, looks better, but as said, I can't evaluate negative side effects (I don't see any, but...)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants