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_GPS: Add configurable baud rate/port for AP_GPS_GSOF #25449

Closed
wants to merge 1 commit into from

Conversation

Ryanf55
Copy link
Collaborator

@Ryanf55 Ryanf55 commented Nov 3, 2023

Overview

  • Add in ability to support 115k and 230k baud rates through AP params
  • Default behavior for baud rate is preserved at 115k
  • Removed support (bug?) for trying to output GSOF on the NMEA port
  • Modified function signature to take in port as a param
  • Added a baud rate validation helper to validate the AP param is a supported baud rate

Demo

You can see in the screenshot, the config UI shows the device is now configured on COM2 for 230k, which is the desired behavior when the user sets the parameter correctly. COM2 is the TTL level serial port that users typically connect to a flight controller.
image

Preserving behavior

Old behavior was to configure the NTRIP Caster 3 and COM1 (RS232) for GSOF output, which wasn't useful on most drones. This breaks that behavior. I think it's obvious no one was using this.

Testing

I've tested this on my bench with a PX1 connected to SITL. The configuration at both baud rates works, and this improves the default port assignment to work with the right COM port at TTL level logic. The validity checks for GSOF pass in SITL.

To decide before merge

One thing to discuss is how this parameter should interact with GPS_DRV_OPTIONS. Perhaps this approach:

@Bitmask: 0:Use UART2 for moving baseline on ublox,1:Use base station for GPS yaw on SBF,2:Use baudrate 115200. Ignored on GSOF; use GPS_GSOF_BAUDn instead,3:Use dedicated CAN port b/w GPSes for moving baseline,4:Use ellipsoid height instead of AMSL

Future work

In a future PR, I will implement the support for checking acknowledgment of commands. This is blocked due to some usage issues in the Linux serial HAL.

@Ryanf55 Ryanf55 added GPS WikiNeeded needs wiki update labels Nov 3, 2023
// @DisplayName: Baud rate for the first GSOF GPS
// @Description: What baud rate to configure the first GSOF GPS to
// @Values: 7:115k, 11:230k
// @User: Advanced
Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Perhaps this needs information that the flight controller needs a reboot if this is changed since the baud command is only sent during the constructor of the GPS instance?

Copy link
Contributor

Choose a reason for hiding this comment

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

Reboot required is probably needed,

Copy link
Contributor

@WickedShell WickedShell left a comment

Choose a reason for hiding this comment

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

It seems like we already have parameters that let us specify what baud rate to use with the SERIALx_BAUD params. This adds more confusion for ways to get there. It's already odd that the GPS library mostly neglects these, but we have the free params that let us pick it up from there.

Can we either grab DRV_OPTIONS bits for this, or start to make some backend specific param instances? Maybe a DRV_OPTIONS bit that says "use the baud rate the user set the serial port at" and then the GSOF driver can use that information in it's config?

// @DisplayName: Baud rate for the first GSOF GPS
// @Description: What baud rate to configure the first GSOF GPS to
// @Values: 7:115k, 11:230k
// @User: Advanced
Copy link
Contributor

Choose a reason for hiding this comment

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

Reboot required is probably needed,

@Ryanf55
Copy link
Collaborator Author

Ryanf55 commented Nov 3, 2023

It seems like we already have parameters that let us specify what baud rate to use with the SERIALx_BAUD params. This adds more confusion for ways to get there. It's already odd that the GPS library mostly neglects these, but we have the free params that let us pick it up from there.

Can we either grab DRV_OPTIONS bits for this, or start to make some backend specific param instances? Maybe a DRV_OPTIONS bit that says "use the baud rate the user set the serial port at" and then the GSOF driver can use that information in it's config?

Yea. I agree it's a bit confusing. Perhaps @Hwurzburg could suggest what he thinks the most intuitive approach would be from a user perspective to configuring the desired baud rate of a GPS is.

Some things to note:

  • If ArduPilot is at a different baud than the PX1, and sends a SetBaud command to the PX1, it will be ignored. The approach currently taking of cycling through all available bauds seems appropriate.
  • The purpose of this PR is to set the desired baud rate of the PX1, but still allow ArduPilot to cycle through to find the PX1. This will ensure that regardless of what the PX1 is currently configured, it will end up at the desired AP_GSOF_BAUD rate.
  • SERIALN_BAUD does not currently have an auto option, however field 0 is open.

@Ryanf55 Ryanf55 force-pushed the gsof-configurable-baud branch from d3a2693 to 51a0c8e Compare November 3, 2023 15:51
@WickedShell
Copy link
Contributor

  • The purpose of this PR is to set the desired baud rate of the PX1, but still allow ArduPilot to cycle through to find the PX1. This will ensure that regardless of what the PX1 is currently configured, it will end up at the desired AP_GSOF_BAUD rate.

That's a really important point actually. We use (and rely) upon the same ideas with the SBF driver among others.

SERIALN_BAUD does not currently have an auto option, however field 0 is open.

That would be quite reasonable, but also a bit problematic for not breaking setups on upgrading firmware.

@Ryanf55
Copy link
Collaborator Author

Ryanf55 commented Nov 3, 2023

  • The purpose of this PR is to set the desired baud rate of the PX1, but still allow ArduPilot to cycle through to find the PX1. This will ensure that regardless of what the PX1 is currently configured, it will end up at the desired AP_GSOF_BAUD rate.

That's a really important point actually. We use (and rely) upon the same ideas with the SBF driver among others.

SERIALN_BAUD does not currently have an auto option, however field 0 is open.

That would be quite reasonable, but also a bit problematic for not breaking setups on upgrading firmware.

What is the expected behavior currently if a user sets this to zero? IE, what would we break?

@Hwurzburg
Copy link
Collaborator

GPS_DRV_OPTION would be a good place to enable this, make sure it overrides bit 2

@Ryanf55
Copy link
Collaborator Author

Ryanf55 commented Nov 4, 2023

GPS_DRV_OPTION would be a good place to enable this, make sure it overrides bit 2

Can you elaborate?

The GSOF device currently supports 8 baud rates. I only exposed the two highest. I expect them to add support for 460k baud in the next revision. Microstrain supports 920k, so this bit doesn't make sense. Use 115k or something else?

@Ryanf55
Copy link
Collaborator Author

Ryanf55 commented Nov 4, 2023

After a discussion with Tridge and Henry, the desired approach is

Add another options bit to GPS_DRV_OPTIONS to bypass GPS baud detection and use serial manager"

Requirements:

  • GPS_TYPEN is not set to AUTO
  • SERIALN_BAUD is configured to the same baud that your GPS is configured.
    Relation to other params
  • The use 115k bit earlier GPS_DRV_OPTIONS will be ignored (that was sort of a hack). Tridge doesn't want to break compatibility with it though, hence a new options bit here.

TODO:

  • How should this option bit interact with DriverOptions::UBX_MBUseUart2, which takes priority?

@Ryanf55
Copy link
Collaborator Author

Ryanf55 commented Nov 4, 2023

In further research, there are some complexities in baud rates in the UBX driver caused by moving baseline. There are two snippets. The proposed use of SERIALN_BAUD would conflict with the custom baud rate options here. I am not confident adding support for disabling GPS auto baud without a better plan for how this will all fit. The easiest would be to say the new option bit takes priority over all other options.

#if GPS_MOVING_BASELINE && AP_GPS_UBLOX_ENABLED
if ((_type[instance] == GPS_TYPE_UBLOX_RTK_BASE ||
_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) &&
!option_set(DriverOptions::UBX_MBUseUart2)) {
// we use 460800 when doing moving baseline as we need
// more bandwidth. We don't do this if using UART2, as
// in that case the RTCMv3 data doesn't go over the
// link to the flight controller
static const char blob[] = UBLOX_SET_BINARY_460800;
send_blob_start(instance, blob, sizeof(blob));
return;
}
#endif

#if AP_GPS_UBLOX_ENABLED
if ((_type[instance] == GPS_TYPE_AUTO ||
_type[instance] == GPS_TYPE_UBLOX) &&
((!_auto_config && _baudrates[dstate->current_baud] >= 38400) ||
(_baudrates[dstate->current_baud] >= 115200 && option_set(DriverOptions::UBX_Use115200)) ||
_baudrates[dstate->current_baud] == 230400) &&
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
return new AP_GPS_UBLOX(*this, state[instance], _port[instance], GPS_ROLE_NORMAL);
}
const uint32_t ublox_mb_required_baud = option_set(DriverOptions::UBX_MBUseUart2)?230400:460800;
if ((_type[instance] == GPS_TYPE_UBLOX_RTK_BASE ||
_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) &&
_baudrates[dstate->current_baud] == ublox_mb_required_baud &&
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
GPS_Role role;
if (_type[instance] == GPS_TYPE_UBLOX_RTK_BASE) {
role = GPS_ROLE_MB_BASE;
} else {
role = GPS_ROLE_MB_ROVER;
}
return new AP_GPS_UBLOX(*this, state[instance], _port[instance], role);
}
#endif // AP_GPS_UBLOX_ENABLED

@Ryanf55
Copy link
Collaborator Author

Ryanf55 commented Nov 6, 2023

The two use cases

  1. I have set up my my GPS and want to not autobaud. Just use the serial baud and be done. This bypasses all detection and instantiates instantly. The autobaud flag should be set to false here. Don't need to call _detect, just instantiate.
  2. I want to use the serial baud for the target baud, but use auto detection because I haven't yet set up my GPS. This is another use case. This is a larger piece of work. This could be a driver option bit or a new enum in GPS_AUTO_CONFIG.

* Add in ability to support 115k and 230k baud rates through AP params
* Default behavior is preserved at 115k
* Removed support (bug?) for trying to output GSOF on the NMEA port
* Modified function signature to take in port as a param
* Added a baud rate validation helper to validate the AP param is a
  supported baud rate

Signed-off-by: Ryan Friedman <[email protected]>
@Ryanf55 Ryanf55 force-pushed the gsof-configurable-baud branch from 51a0c8e to de718ef Compare November 10, 2023 16:16
@Ryanf55
Copy link
Collaborator Author

Ryanf55 commented Nov 12, 2024

Moving to Ethernet EAHRS instead which doesn't have these difficult baud problems.

@Ryanf55 Ryanf55 closed this Nov 12, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
GPS WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants