mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_CANManager: remove unused variable from SLCANIface code
This commit is contained in:
parent
54f03b9b64
commit
e29ddebe3c
@ -330,8 +330,7 @@ int16_t SLCAN::CANIface::reportFrame(const AP_HAL::CANFrame& frame, uint64_t tim
|
|||||||
*p++ = '\r';
|
*p++ = '\r';
|
||||||
const auto frame_size = unsigned(p - &buffer[0]);
|
const auto frame_size = unsigned(p - &buffer[0]);
|
||||||
|
|
||||||
if (_port->txspace() < _pending_frame_size) {
|
if (_port->txspace() < frame_size) {
|
||||||
_pending_frame_size = frame_size;
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
//Write to Serial
|
//Write to Serial
|
||||||
|
@ -61,7 +61,6 @@ class CANIface: public AP_HAL::CANIface
|
|||||||
bool initialized_;
|
bool initialized_;
|
||||||
|
|
||||||
char buf_[SLCAN_BUFFER_SIZE + 1]; // buffer to record raw frame nibbles before parsing
|
char buf_[SLCAN_BUFFER_SIZE + 1]; // buffer to record raw frame nibbles before parsing
|
||||||
uint32_t _pending_frame_size = 0; // holds the size of frame to be tx
|
|
||||||
int16_t pos_ = 0; // position in the buffer recording nibble frames before parsing
|
int16_t pos_ = 0; // position in the buffer recording nibble frames before parsing
|
||||||
AP_HAL::UARTDriver* _port; // UART interface port reference to be used for SLCAN iface
|
AP_HAL::UARTDriver* _port; // UART interface port reference to be used for SLCAN iface
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user