mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_RCTelemetry: re-order initialiser lines so -Werror=reorder will work
This commit is contained in:
parent
87fa7a208d
commit
1ce391c6e8
@ -1288,8 +1288,13 @@ void AP_CRSF_Telem::calc_parameter() {
|
|||||||
class BufferChunker {
|
class BufferChunker {
|
||||||
public:
|
public:
|
||||||
BufferChunker(uint8_t* buf, uint16_t chunk_size, uint16_t start_chunk) :
|
BufferChunker(uint8_t* buf, uint16_t chunk_size, uint16_t start_chunk) :
|
||||||
_buf(buf), _idx(0), _start_chunk(start_chunk), _chunk_size(chunk_size), _chunk(0), _bytes(0) {
|
_buf(buf),
|
||||||
}
|
_idx(0),
|
||||||
|
_bytes(0),
|
||||||
|
_chunk(0),
|
||||||
|
_start_chunk(start_chunk),
|
||||||
|
_chunk_size(chunk_size)
|
||||||
|
{ }
|
||||||
|
|
||||||
// accumulate a string, writing to the underlying buffer as required
|
// accumulate a string, writing to the underlying buffer as required
|
||||||
void put_string(const char* str, uint16_t str_len) {
|
void put_string(const char* str, uint16_t str_len) {
|
||||||
|
Loading…
Reference in New Issue
Block a user