mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: allow sending stats via mavftp on AP_Periph
This commit is contained in:
parent
6b64cfd6c1
commit
a8ab20abd9
|
@ -1031,7 +1031,7 @@ bool CANIface::select(bool &read, bool &write,
|
|||
return false;
|
||||
}
|
||||
|
||||
#if !defined(HAL_BUILD_AP_PERIPH) && !defined(HAL_BOOTLOADER_BUILD)
|
||||
#if !defined(HAL_BOOTLOADER_BUILD)
|
||||
void CANIface::get_stats(ExpandingString &str)
|
||||
{
|
||||
CriticalSectionLocker lock;
|
||||
|
|
|
@ -221,7 +221,7 @@ public:
|
|||
bool set_event_handle(AP_HAL::EventHandle* handle) override;
|
||||
#endif
|
||||
|
||||
#if !defined(HAL_BUILD_AP_PERIPH) && !defined(HAL_BOOTLOADER_BUILD)
|
||||
#if !defined(HAL_BOOTLOADER_BUILD)
|
||||
// fetch stats text and return the size of the same,
|
||||
// results available via @SYS/can0_stats.txt or @SYS/can1_stats.txt
|
||||
void get_stats(ExpandingString &str) override;
|
||||
|
|
Loading…
Reference in New Issue