../../libraries/GCS_MAVLink/GCS_Common.cpp: In member function 'void GCS_MAVLINK::send_highres_imu()':
../../libraries/GCS_MAVLink/GCS_Common.cpp:2184:27: error: unused variable 'HIGHRES_IMU_UPDATED_XMAG' [-Werror=unused-variable]
2184 | static const uint16_t HIGHRES_IMU_UPDATED_XMAG = 0x40;
| ^~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated due to -Wfatal-errors.
cc1plus: all warnings being treated as errors
Co-authored-by: Bob Long <robertlong13@gmail.com>
Co-authored-by: Michelle Rossouw <michelleros128@gmail.com>
another one of our "do nasty thing to autopilot" commands, useful for testing what ground control stations do when the autopilot is in this state
this is going to be used for changing the rate of a specific instance of a message at some stage
we have to reject it for now so that when the index is used the GCS is told that their message is invalid in this older version of the autopilot
- split get_type into allocated_type and configured_type
- check allocated type rather than configured type when looking at backends
Prevents overwrite of random memory when backends are changed at runtime.
Add code to reflect USB ACM parity setting to the passthrough port alongside existing support for ACM baud rate changes. Some use cases for serial passthrough require specific parity settings.
For example, even parity is used and required by the USART protocol used in the STM32 system bootloader. This enhancement allows the use of standard flash programming tools such as STM32CubeProgrammer to flash connected STM based peripherals such as Receivers and Telemetry radios via serial passthrough. Some examples of such peripherals include the FrSky R9 receivers as well as various other STM based LoRa modules used by the mLRS project.
Delete unneeded orphan comment
replace get_last_txbuf() with a predicate
Make txbuf flow control threashold consistent between Parameter download and FTP and keep it in range where we are also slowing down normal streams
Delay sending text banner until after first FTP response to reduce latency on slow links
Don't let flow control delay setting ftp.last_send_ms so as to slow down normal streams as soon as possible to improve FTP response time