mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_CANManager: use ExpandingString class
This commit is contained in:
parent
6c1891fcb3
commit
0c6b4a1045
@ -39,6 +39,8 @@
|
|||||||
#include <AP_HAL_ChibiOS/CANIface.h>
|
#include <AP_HAL_ChibiOS/CANIface.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#include <AP_Common/ExpandingString.h>
|
||||||
|
|
||||||
#define LOG_TAG "CANMGR"
|
#define LOG_TAG "CANMGR"
|
||||||
#define LOG_BUFFER_SIZE 1024
|
#define LOG_BUFFER_SIZE 1024
|
||||||
|
|
||||||
@ -373,15 +375,13 @@ void AP_CANManager::log_text(AP_CANManager::LogLevel loglevel, const char *tag,
|
|||||||
}
|
}
|
||||||
|
|
||||||
// log retrieve method used by file sys method to report can log
|
// log retrieve method used by file sys method to report can log
|
||||||
uint32_t AP_CANManager::log_retrieve(char* data, uint32_t max_size) const
|
void AP_CANManager::log_retrieve(ExpandingString &str) const
|
||||||
{
|
{
|
||||||
if (_log_buf == nullptr) {
|
if (_log_buf == nullptr) {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Log buffer not available");
|
gcs().send_text(MAV_SEVERITY_ERROR, "Log buffer not available");
|
||||||
return 0;
|
return;
|
||||||
}
|
}
|
||||||
uint32_t read_len = MIN(max_size, _log_pos);
|
str.append(_log_buf, _log_pos);
|
||||||
memcpy(data, _log_buf, read_len);
|
|
||||||
return read_len;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_CANManager& AP::can()
|
AP_CANManager& AP::can()
|
||||||
|
@ -90,7 +90,7 @@ public:
|
|||||||
// Method to log status and debug information for review while debugging
|
// Method to log status and debug information for review while debugging
|
||||||
void log_text(AP_CANManager::LogLevel loglevel, const char *tag, const char *fmt, ...);
|
void log_text(AP_CANManager::LogLevel loglevel, const char *tag, const char *fmt, ...);
|
||||||
|
|
||||||
uint32_t log_retrieve(char* data, uint32_t max_size) const;
|
void log_retrieve(ExpandingString &str) const;
|
||||||
|
|
||||||
// return driver type index i
|
// return driver type index i
|
||||||
Driver_Type get_driver_type(uint8_t i) const
|
Driver_Type get_driver_type(uint8_t i) const
|
||||||
|
@ -536,13 +536,12 @@ uint32_t SLCAN::CANIface::getErrorCount() const
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t SLCAN::CANIface::get_stats(char* data, uint32_t max_size)
|
void SLCAN::CANIface::get_stats(ExpandingString &str)
|
||||||
{
|
{
|
||||||
// When in passthrough mode methods is handled through can iface
|
// When in passthrough mode methods is handled through can iface
|
||||||
if (_can_iface) {
|
if (_can_iface) {
|
||||||
return _can_iface->get_stats(data, max_size);
|
_can_iface->get_stats(str);
|
||||||
}
|
}
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool SLCAN::CANIface::is_busoff() const
|
bool SLCAN::CANIface::is_busoff() const
|
||||||
|
@ -112,7 +112,7 @@ public:
|
|||||||
bool set_event_handle(AP_HAL::EventHandle* evt_handle) override;
|
bool set_event_handle(AP_HAL::EventHandle* evt_handle) override;
|
||||||
uint16_t getNumFilters() const override;
|
uint16_t getNumFilters() const override;
|
||||||
uint32_t getErrorCount() const override;
|
uint32_t getErrorCount() const override;
|
||||||
uint32_t get_stats(char* data, uint32_t max_size) override;
|
void get_stats(ExpandingString &) override;
|
||||||
bool is_busoff() const override;
|
bool is_busoff() const override;
|
||||||
bool configureFilters(const CanFilterConfig* filter_configs, uint16_t num_configs) override;
|
bool configureFilters(const CanFilterConfig* filter_configs, uint16_t num_configs) override;
|
||||||
void flush_tx() override;
|
void flush_tx() override;
|
||||||
|
Loading…
Reference in New Issue
Block a user