mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AP_UAVCAN: log bus statistics
This commit is contained in:
parent
21b4a19c6f
commit
50d00f4e45
@ -494,6 +494,7 @@ void AP_UAVCAN::loop(void)
|
||||
#if AP_OPENDRONEID_ENABLED
|
||||
AP::opendroneid().dronecan_send(this);
|
||||
#endif
|
||||
logging();
|
||||
}
|
||||
}
|
||||
|
||||
@ -543,7 +544,11 @@ void AP_UAVCAN::SRV_send_actuator(void)
|
||||
}
|
||||
|
||||
if (i > 0) {
|
||||
act_out_array[_driver_index]->broadcast(msg);
|
||||
if (act_out_array[_driver_index]->broadcast(msg) > 0) {
|
||||
_srv_send_count++;
|
||||
} else {
|
||||
_fail_send_count++;
|
||||
}
|
||||
|
||||
if (i == 15) {
|
||||
repeat_send = true;
|
||||
@ -594,7 +599,11 @@ void AP_UAVCAN::SRV_send_esc(void)
|
||||
k++;
|
||||
}
|
||||
|
||||
esc_raw[_driver_index]->broadcast(esc_msg);
|
||||
if (esc_raw[_driver_index]->broadcast(esc_msg) > 0) {
|
||||
_esc_send_count++;
|
||||
} else {
|
||||
_fail_send_count++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -1217,4 +1226,52 @@ bool AP_UAVCAN::prearm_check(char* fail_msg, uint8_t fail_msg_len) const
|
||||
return _dna_server->prearm_check(fail_msg, fail_msg_len);
|
||||
}
|
||||
|
||||
/*
|
||||
periodic logging
|
||||
*/
|
||||
void AP_UAVCAN::logging(void)
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
const uint32_t now_ms = AP_HAL::millis();
|
||||
if (now_ms - last_log_ms < 1000) {
|
||||
return;
|
||||
}
|
||||
last_log_ms = now_ms;
|
||||
if (HAL_NUM_CAN_IFACES <= _driver_index) {
|
||||
// no interface?
|
||||
return;
|
||||
}
|
||||
const auto *iface = hal.can[_driver_index];
|
||||
if (iface == nullptr) {
|
||||
return;
|
||||
}
|
||||
const auto *stats = iface->get_statistics();
|
||||
if (stats == nullptr) {
|
||||
// statistics not implemented on this interface
|
||||
return;
|
||||
}
|
||||
const auto &s = *stats;
|
||||
AP::logger().WriteStreaming("CANS",
|
||||
"TimeUS,I,T,Trq,Trej,Tov,Tto,Tab,R,Rov,Rer,Bo,Etx,Stx,Ftx",
|
||||
"s#-------------",
|
||||
"F--------------",
|
||||
"QBIIIIIIIIIIIII",
|
||||
AP_HAL::micros64(),
|
||||
_driver_index,
|
||||
s.tx_success,
|
||||
s.tx_requests,
|
||||
s.tx_rejected,
|
||||
s.tx_overflow,
|
||||
s.tx_timedout,
|
||||
s.tx_abort,
|
||||
s.rx_received,
|
||||
s.rx_overflow,
|
||||
s.rx_errors,
|
||||
s.num_busoff_err,
|
||||
_esc_send_count,
|
||||
_srv_send_count,
|
||||
_fail_send_count);
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
}
|
||||
|
||||
#endif // HAL_NUM_CAN_IFACES
|
||||
|
@ -247,6 +247,9 @@ private:
|
||||
// send parameter save request
|
||||
void send_parameter_save_request();
|
||||
|
||||
// periodic logging
|
||||
void logging();
|
||||
|
||||
// set parameter on a node
|
||||
ParamGetSetIntCb *param_int_cb;
|
||||
ParamGetSetFloatCb *param_float_cb;
|
||||
@ -287,10 +290,17 @@ private:
|
||||
bool servo_pending;
|
||||
} _SRV_conf[UAVCAN_SRV_NUMBER];
|
||||
|
||||
uint32_t _esc_send_count;
|
||||
uint32_t _srv_send_count;
|
||||
uint32_t _fail_send_count;
|
||||
|
||||
uint8_t _SRV_armed;
|
||||
uint32_t _SRV_last_send_us;
|
||||
HAL_Semaphore SRV_sem;
|
||||
|
||||
// last log time
|
||||
uint32_t last_log_ms;
|
||||
|
||||
///// LED /////
|
||||
struct led_device {
|
||||
uint8_t led_index;
|
||||
|
Loading…
Reference in New Issue
Block a user