Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Scripting: Adds I2C transfer() bindings and an example #27287

Merged
merged 2 commits into from
Jul 29, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 9 additions & 2 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ i2c = {}
---@param address integer -- device address 0 to 128
---@param clock? uint32_t_ud|integer|number -- optional bus clock, default 400000
---@param smbus? boolean -- optional sumbus flag, default false
---@return AP_HAL__I2CDevice_ud|nil
---@return AP_HAL__I2CDevice_ud
function i2c:get_device(bus, address, clock, smbus) end

-- EFI state structure
Expand Down Expand Up @@ -1211,6 +1211,13 @@ local AP_HAL__I2CDevice_ud = {}
---@param address integer
function AP_HAL__I2CDevice_ud:set_address(address) end

-- Performs an I2C transfer, sending data_str bytes (see string.pack) and
-- returning a string of any requested read bytes (see string.unpack)
---@param data_str string
---@param read_length integer
---@return string|nil
function AP_HAL__I2CDevice_ud:transfer(data_str, read_length) end

-- If no read length is provided a single register will be read and returned.
-- If read length is provided a table of register values are returned.
---@param register_num integer
Expand Down Expand Up @@ -2608,7 +2615,7 @@ function gcs:last_seen() end
-- call a MAVLink MAV_CMD_xxx command via command_int interface
---@param command integer -- MAV_CMD_xxx
---@param params table -- parameters of p1, p2, p3, p4, x, y and z and frame. Any not specified taken as zero
---@return boolean
---@return integer -- MAV_RESULT
function gcs:run_command_int(command, params) end

-- The relay library provides access to controlling relay outputs.
Expand Down
108 changes: 108 additions & 0 deletions libraries/AP_Scripting/examples/BQ40Z_bms_shutdown.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
-- TI BQ40Z BMS shutdown script

local mavlink_msgs = require("MAVLink/mavlink_msgs")

local COMMAND_ACK_ID = mavlink_msgs.get_msgid("COMMAND_ACK")
local COMMAND_LONG_ID = mavlink_msgs.get_msgid("COMMAND_LONG")
local msg_map = {}
msg_map[COMMAND_ACK_ID] = "COMMAND_ACK"
msg_map[COMMAND_LONG_ID] = "COMMAND_LONG"

local PARAM_TABLE_KEY = 51
local PARAM_TABLE_PREFIX = "BATT_BQ40Z_"
-- add a parameter and bind it to a variable
local function bind_add_param(name, idx, default_value)
assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name))
return Parameter(PARAM_TABLE_PREFIX .. name)
end
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 2), 'could not add param table')
--[[
// @Param: BATT_BQ40Z_BUS
// @DisplayName: Bus number for the BQ40Z
// @Description: Bus number for the BQ40Z
// @Range: 0 3
// @User: Standard
--]]
local BATT_BQ40Z_BUS = bind_add_param('BUS', 1, 0)


local MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246
local MAV_RESULT_ACCEPTED = 0
local MAV_RESULT_FAILED = 4

-- Initialize MAVLink rx with number of messages, and buffer depth
mavlink:init(1, 10)
-- Register message id to receive
mavlink:register_rx_msgid(COMMAND_LONG_ID)
-- Block MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN so we can handle the ACK
mavlink:block_command(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN)

-- Init BMS i2c device
local i2c_addr = BATT_BQ40Z_BUS:get()
assert(i2c_addr ~= nil, "BATT_BQ40Z_BUS not retrievable")
local bms = i2c:get_device(math.floor(i2c_addr), 0x0B)

-- Exit emergency shutdown (for BQ40Z60, twice for redundancy)
bms:transfer("\x00\xA7\x23", 0)
bms:transfer("\x00\xA7\x23", 0)

-- Function that is returned to the AP scheduler when we want to shutdown
local function shutdown_loop()
local ret = bms:transfer("\x00\x10\x00", 0)
if ret == nil then
gcs:send_text(0, "BQ40Z shutdown transfer failed")
end

return shutdown_loop, 500
end

-- Main loop
local function update()
local msg, chan = mavlink:receive_chan()
local parsed_msg = nil

if (msg ~= nil) then
parsed_msg = mavlink_msgs.decode(msg, msg_map)
end

if parsed_msg ~= nil and (parsed_msg.msgid == COMMAND_LONG_ID) and (parsed_msg.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN) then
-- Prepare ack
local ack = {}
ack.command = parsed_msg.command
ack.result = MAV_RESULT_ACCEPTED
ack.progress = 0
ack.result_param2 = 0
ack.target_system = parsed_msg.sysid
ack.target_component = parsed_msg.compid

-- Don't shutdown if armed
if arming:is_armed() and parsed_msg.param1 == 2 then
gcs:send_text(1, "Not sutting down BQ40Z as vehicle is armed")
ack.result = MAV_RESULT_FAILED
mavlink:send_chan(chan, mavlink_msgs.encode("COMMAND_ACK", ack))
IanBurwell marked this conversation as resolved.
Show resolved Hide resolved

-- Shutdown
elseif parsed_msg.param1 == 2 then
gcs:send_text(1, "Shutting down BQ40Z!!!")
mavlink:send_chan(chan, mavlink_msgs.encode("COMMAND_ACK", ack))
return shutdown_loop, 0

-- Pass through the command if it isn't requesting shutdown
else
local command_int = {
p1 = parsed_msg.param1,
p2 = parsed_msg.param2,
p3 = parsed_msg.param3,
p4 = parsed_msg.param4,
}
local result = gcs:run_command_int(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, command_int)
ack.result = result
mavlink:send_chan(chan, mavlink_msgs.encode("COMMAND_ACK", ack))
end
end

return update, 1000
end


return update, 1000
107 changes: 107 additions & 0 deletions libraries/AP_Scripting/examples/RM3100_self_test.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,107 @@
-- Runs the Built-In Self Test on the RM3100 LR circuits
-- Note COMPASS_DISBLMSK should have the 16th bit set to 1 (RM3100)

-- Init RM3100 on bus 0
local rm3100 = i2c:get_device(0, 0x20)
assert(rm3100 ~= nil, "i2c get_device error, cannot run RM3100 self test")

-- Queues a Built-In Self Test
function queue_test()
gcs:send_text(1, "Running RM3100 self test")

-- Queue a self test by setting BIST register
local ret = rm3100:transfer("\x33\x8F", 0)
if ret == nil then
gcs:send_text(1, "Rm3100 BIST transfer failed")
return queue_test, 1000
end

-- Send a POLL request to run a BIST
ret = rm3100:transfer("\x00\x70", 0)
if ret == nil then
gcs:send_text(1, "Rm3100 POLL transfer failed")
return queue_test, 1000
end

-- As a measurement takes time, delay a bit by scheduling a different function
return read_test, 1000
end


-- Reads back values from a Built-In Self Test
function read_test()
-- Read the BIST results
local results_str = rm3100:transfer("\x33", 1)
if results_str ~= nil then
local results = results_str:byte()

if results & (1 << 4) == 0 then
gcs:send_text(1, "RM3100 X is unhealthy")
else
gcs:send_text(1, "RM3100 X is OK")
end

if results & (1 << 5) == 0 then
gcs:send_text(1, "RM3100 Y is unhealthy")
else
gcs:send_text(1, "RM3100 Y is OK")
end

if results & (1 << 6) == 0 then
gcs:send_text(1, "RM3100 Z is unhealthy")
else
gcs:send_text(1, "RM3100 Z is OK")
end
else
gcs:send_text(1, "Rm3100 BIST read transfer failed")
return queue_test, 1000
end

-- Reset the BIST register
local ret = rm3100:transfer("\x33\x0F", 0)
if ret == nil then
gcs:send_text(1, "Rm3100 BIST reset transfer failed")
return queue_test, 1000
end

-- Send a POLL request to take a data point
ret = rm3100:transfer("\x00\x70", 0)
if ret == nil then
gcs:send_text(1, "Rm3100 POLL data transfer failed")
return queue_test, 1000
end

-- As a measurement takes time, delay a bit by scheduling a different function
return read_data, 1000
end

-- Reads data from the RM3100
function read_data()
-- Check that data is ready for a read
local status_str = rm3100:transfer("\x34", 1)
if status_str ~= nil then
local status = status_str:byte()
if status & (1 << 7) == 0 then
gcs:send_text(1, "RM3100 data not ready for reading")
return queue_test, 1000
end
else
gcs:send_text(1, "Rm3100 BIST status reg transfer failed")
return queue_test, 1000
end

-- Read measured values
local measurements_str = rm3100:transfer("\x24", 9)
if measurements_str ~= nil then
local MX, MY, MZ = string.unpack(">i3>i3>i3", measurements_str)
gcs:send_text(6, string.format("RM3100 Mag: X=%8d Y=%8d Z=%8d", MX, MY, MZ))
else
gcs:send_text(1, "Rm3100 data read transfer failed")
return queue_test, 1000
end

-- Loop back to the first function to run another set of tests
return queue_test, 1000
end

return queue_test, 1000
1 change: 1 addition & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -586,6 +586,7 @@ ap_object AP_HAL::I2CDevice semaphore-pointer
ap_object AP_HAL::I2CDevice method set_retries void uint8_t 0 20
ap_object AP_HAL::I2CDevice method write_register boolean uint8_t'skip_check uint8_t'skip_check
ap_object AP_HAL::I2CDevice manual read_registers AP_HAL__I2CDevice_read_registers 2 1
ap_object AP_HAL::I2CDevice manual transfer AP_HAL__I2CDevice_transfer 2 1
ap_object AP_HAL::I2CDevice method set_address void uint8_t'skip_check

include AP_HAL/utility/Socket.h depends (AP_NETWORKING_ENABLED==1)
Expand Down
33 changes: 29 additions & 4 deletions libraries/AP_Scripting/lua_bindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -656,6 +656,33 @@ int AP_HAL__I2CDevice_read_registers(lua_State *L) {
return success;
}

int AP_HAL__I2CDevice_transfer(lua_State *L) {
binding_argcheck(L, 3);

AP_HAL::I2CDevice * ud = *check_AP_HAL__I2CDevice(L, 1);

// Parse string of bytes to send
size_t send_len;
const uint8_t* send_data = (const uint8_t*)(lua_tolstring(L, 2, &send_len));

// Parse and setup rx buffer
uint32_t rx_len = get_uint8_t(L, 3);
uint8_t rx_data[rx_len];

// Transfer
ud->get_semaphore()->take_blocking();
const bool success = ud->transfer(send_data, send_len, rx_data, rx_len);
ud->get_semaphore()->give();

if (!success) {
return 0;
}

// Return a string
lua_pushlstring(L, (const char *)rx_data, rx_len);
return 1;
}

#if AP_SCRIPTING_CAN_SENSOR_ENABLED
int lua_get_CAN_device(lua_State *L) {

Expand Down Expand Up @@ -1178,10 +1205,8 @@ int lua_GCS_command_int(lua_State *L)

auto result = _gcs->lua_command_int_packet(pkt);

// map MAV_RESULT to a boolean
bool ok = result == MAV_RESULT_ACCEPTED;

lua_pushboolean(L, ok);
// Return the resulting MAV_RESULT
lua_pushinteger(L, result);
Comment on lines -1181 to +1209
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Be sure to update the docs, if not put this in a separate PR.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Somehow that escaped me, thank you for the catch. I think it is not too out of scope of this PR and is required by it. I can split it into a different commit if you think that is justified.

Copy link
Contributor

@tpwrules tpwrules Jul 29, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, it definitely should be a separate commit.

I recognize it's necessary for the PR but it is technically backwards incompatible. It doesn't look like any examples currently check the return values though and it hasn't made it to a stable release so I'd be okay with it going in this PR.


return 1;
}
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Scripting/lua_bindings.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ int lua_mission_receive(lua_State *L);
int AP_Logger_Write(lua_State *L);
int lua_get_i2c_device(lua_State *L);
int AP_HAL__I2CDevice_read_registers(lua_State *L);
int AP_HAL__I2CDevice_transfer(lua_State *L);
int lua_get_CAN_device(lua_State *L);
int lua_get_CAN_device2(lua_State *L);
int lua_serial_find_serial(lua_State *L);
Expand Down
Loading