AP_Periph: rename rx-protocol-stats ins local to avoid conflict with ins singleton
This commit is contained in:
parent
635c764c6f
commit
3bd8f1a3df
@ -1225,19 +1225,19 @@ void AP_Periph_FW::update_rx_protocol_stats(int16_t res)
|
|||||||
void AP_Periph_FW::processRx(void)
|
void AP_Periph_FW::processRx(void)
|
||||||
{
|
{
|
||||||
AP_HAL::CANFrame rxmsg;
|
AP_HAL::CANFrame rxmsg;
|
||||||
for (auto &ins : instances) {
|
for (auto &instance : instances) {
|
||||||
if (ins.iface == NULL) {
|
if (instance.iface == NULL) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
#if HAL_NUM_CAN_IFACES >= 2
|
#if HAL_NUM_CAN_IFACES >= 2
|
||||||
if (can_protocol_cached[ins.index] != AP_CAN::Protocol::DroneCAN) {
|
if (can_protocol_cached[instance.index] != AP_CAN::Protocol::DroneCAN) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
while (true) {
|
while (true) {
|
||||||
bool read_select = true;
|
bool read_select = true;
|
||||||
bool write_select = false;
|
bool write_select = false;
|
||||||
ins.iface->select(read_select, write_select, nullptr, 0);
|
instance.iface->select(read_select, write_select, nullptr, 0);
|
||||||
if (!read_select) { // No data pending
|
if (!read_select) { // No data pending
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -1246,7 +1246,7 @@ void AP_Periph_FW::processRx(void)
|
|||||||
//palToggleLine(HAL_GPIO_PIN_LED);
|
//palToggleLine(HAL_GPIO_PIN_LED);
|
||||||
uint64_t timestamp;
|
uint64_t timestamp;
|
||||||
AP_HAL::CANIface::CanIOFlags flags;
|
AP_HAL::CANIface::CanIOFlags flags;
|
||||||
if (ins.iface->receive(rxmsg, timestamp, flags) <= 0) {
|
if (instance.iface->receive(rxmsg, timestamp, flags) <= 0) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#if HAL_PERIPH_CAN_MIRROR
|
#if HAL_PERIPH_CAN_MIRROR
|
||||||
@ -1267,7 +1267,7 @@ void AP_Periph_FW::processRx(void)
|
|||||||
#endif
|
#endif
|
||||||
rx_frame.id = rxmsg.id;
|
rx_frame.id = rxmsg.id;
|
||||||
#if CANARD_MULTI_IFACE
|
#if CANARD_MULTI_IFACE
|
||||||
rx_frame.iface_id = ins.index;
|
rx_frame.iface_id = instance.index;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const int16_t res = canardHandleRxFrame(&dronecan.canard, &rx_frame, timestamp);
|
const int16_t res = canardHandleRxFrame(&dronecan.canard, &rx_frame, timestamp);
|
||||||
@ -1362,14 +1362,14 @@ void AP_Periph_FW::node_status_send(void)
|
|||||||
buffer,
|
buffer,
|
||||||
len);
|
len);
|
||||||
}
|
}
|
||||||
for (auto &ins : instances) {
|
for (auto &instance : instances) {
|
||||||
uint8_t buffer[DRONECAN_PROTOCOL_CANSTATS_MAX_SIZE];
|
uint8_t buffer[DRONECAN_PROTOCOL_CANSTATS_MAX_SIZE];
|
||||||
dronecan_protocol_CanStats can_stats;
|
dronecan_protocol_CanStats can_stats;
|
||||||
const AP_HAL::CANIface::bus_stats_t *bus_stats = ins.iface->get_statistics();
|
const AP_HAL::CANIface::bus_stats_t *bus_stats = instance.iface->get_statistics();
|
||||||
if (bus_stats == nullptr) {
|
if (bus_stats == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
can_stats.interface = ins.index;
|
can_stats.interface = instance.index;
|
||||||
can_stats.tx_requests = bus_stats->tx_requests;
|
can_stats.tx_requests = bus_stats->tx_requests;
|
||||||
can_stats.tx_rejected = bus_stats->tx_rejected;
|
can_stats.tx_rejected = bus_stats->tx_rejected;
|
||||||
can_stats.tx_overflow = bus_stats->tx_overflow;
|
can_stats.tx_overflow = bus_stats->tx_overflow;
|
||||||
|
Loading…
Reference in New Issue
Block a user