How to get CAN write frame working in sim_vehicle.py (SITL ardupilot)

I was wondering if it is possible to get CAN:write_frame() to work in SITL ardupilot (aka sim_vehicle.py). I am currently in Ubuntu 22.04 and my CAN driver is working fine where I am currently using USB CANable.

I connected my USB CANable and set it up with socketcan where I ran the following commands (just in case anyone is interested in developing CAN drivers in the future):

sudo slcand -o -c -s8 /dev/ttyACM0 can0 && sudo ifconfig can0 up

Note: Please be sure to check which tty device your USB CANable is connected to!

I have followed the instructions for SITL and this is my current parameter file where I have set up all necessary parameters to work for both scripting and CAN interface.

can_write_example.parm (31.0 KB)

So, upon running the SITL, just to show that the CAN interface is working perfectly, here is a quick snapshot.

In this screenshot, you can see the CAN Driver Found message which means that the LUA script is working and manage to find the CAN driver.

Here is the output of cangaroo where I am able to see all of the DroneCAN messages being published by SITL.

However, when running the LUA script update() loop, eventhough the logs says that the CAN data has been sent, I am not seeing it whatsoever in the CAN bus. Is this a limitation of the SITL CAN interface or am I missing something?

The whole LUA script can be found below. Any help would be much appreciated!

-- This script is an example of writing to CAN bus
---@diagnostic disable: need-check-nil

-- Load CAN driver, using the scripting protocol and with a buffer size of 5
local driver
local initialised = false

local function init()
	driver = CAN:get_device(5)
	if not driver then
		-- If the above fails, then this tries to get Scripting2 interface
		driver = CAN:get_device2(5)
	end

	-- If no scripting interface found, then this should be stuck in a loop and warns the user about the scripting interface
	if not driver then
		logger(2, string.format("No scripting CAN interface found!"))
		logger(
			2,
			string.format("Please ensure that you have set CAN_D2_PROTOCOL2 with Scripting interface.")
		)
		return init, 100
  else
    gcs:send_text(6, "CAN Driver found")
    initialised = true
    return update, 100
	end
end


function update()

  if not initialised then
    init()
    return init, 100
  end

	msg = CANFrame()

	local target_id = 100 
	msg:id(uint32_t(target_id))

	msg:data(0, 1) -- set light_id = 0
	msg:data(1, 2) -- set light_id = 0
	msg:data(2, 3) -- set light_id = 0
	msg:data(3, 4) -- set light_id = 0

	-- sending 4 bytes of data
	msg:dlc(4)

	-- write the frame with a 10000us timeout
	driver:write_frame(msg, 10000)

	gcs:send_text(6, "Sending data to CAN")

  return update, 100

end

return update()

Also, note that this lua script works on the actual hardware, but I am choosing to develop it in SITL for now since it is much easier to quickly write the script without having to gather all the necessary resources to get the CAN bus working. When running this script in the actual hardware, I am indeed seeing the 0x100 ID coming from the LUA script.