PreArm: Internal errors 0x4000020 l:253 panic,mem_guard

Note: I am going crazy. I know this is not a hard one but if anyone has ideas I’d greatly appreciate it

I am porting changes from an older version of ArduCopter (4.0.5) to 4.2.3.

After porting some of the functionality the firmware compiled without complaints but keeps yelling about mem_guard panic.

mem_guard internal error gets thrown if block size > num_blocks in

AP_UAVCAN_pool.cpp - void* AP_PoolAllocator::allocate(std::size_t size)
AP_UAVCAN_pool.cpp - void* AP_PoolAllocator::deallocate(std::size_t size)
num_blocks = _pool_size/pool block size // 8192 and 64 respectively.

the value 8192 is also displayed in CAN_D1_UC_POOL and instruction say to increase it for higher CAN loads. Previously these numbers worked fine in 4.0.5. Anyway I doubled it to 16384 and the error persists.

I then started commenting things out and narrowed it down to one of my custom fns. I use custom ESCs with custom messages, so within AP_UAVCAN.cpp - handle_ESC_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ESCStatusCb &cb) I have added a call to my fn:

AP_Motors::get_singleton()->update_esc_state(cb.msg->esc_index, cb.msg->voltage, cb.msg->current, cb.msg->temperature, cb.msg->rpm, cb.msg->power_rating_pct > 0, cb.msg->error_count);

update_esc_state() fn just assigns the provided values to an array of esc_status structs.

e.g.
esc_status[i].voltage = voltage;

The strangest thing is that the error occurs if I try to assign value to any floats (e.g. voltage) but not ints (e.g. rpms).

The esc_status array (size of 8, ) of structs is a public variable if that matters.

struct EscStatus_info{
    float voltage;
    float current;
    float temperature;
    int rpm;
    bool ready;
    int stus;
    uint32_t last_reading_ms = 0;
};

Please HALP!

p.s. I am running mRoCtrlZeroOEMH7 in case that’s important

l:253 is a line number, not sure if that helps.

Generally this means either memory corruption or a zero memory write. Not sure about the CAN thing.

Thanks. 253 is indeed a line number however pretty useless without a file cause there is nothing on line253 of the file where the problematic function is.

I tried editing the AP_InternalError to include __ FILE__ in the message but it just locked up the AP.

p.s. Excuse my ignorance – what is a zero memory write?

Since the code is already compiled I doubt line numbers are the same. Aren’t comments removed? Just wondering

It’s a line number where someone calls internal error, so I tend to grep for all instances of internal error and see whether one has a line number that matches