|
| 1 | +--[[ |
| 2 | + update and log battery tag information from BatteryTag periph nodes |
| 3 | +--]] |
| 4 | + |
| 5 | +local GLOBALTIME_ID = 344 |
| 6 | +local GLOBALTIME_SIGNATURE = uint64_t(0xA5517744, 0x8A490F33) |
| 7 | + |
| 8 | +local BATTERYTAG_ID = 20500 |
| 9 | +local BATTERYTAG_SIGNATURE = uint64_t(0x4A5A9B42, 0x099F73E1) |
| 10 | + |
| 11 | +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} |
| 12 | + |
| 13 | +PARAM_TABLE_KEY = 49 |
| 14 | +PARAM_TABLE_PREFIX = "BTAG_" |
| 15 | + |
| 16 | +-- add a parameter and bind it to a variable |
| 17 | +function bind_add_param(name, idx, default_value) |
| 18 | + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) |
| 19 | + return Parameter(PARAM_TABLE_PREFIX .. name) |
| 20 | +end |
| 21 | + |
| 22 | +-- Setup Parameters |
| 23 | +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 6), 'BatteryTag: could not add param table') |
| 24 | + |
| 25 | +--[[ |
| 26 | + // @Param: BTAG_ENABLE |
| 27 | + // @DisplayName: enable battery info support |
| 28 | + // @Description: enable battery info support |
| 29 | + // @Values: 0:Disabled,1:Enabled |
| 30 | + // @User: Standard |
| 31 | +--]] |
| 32 | +local BTAG_ENABLE = bind_add_param('ENABLE', 1, 1) |
| 33 | + |
| 34 | +if BTAG_ENABLE:get() == 0 then |
| 35 | + return |
| 36 | +end |
| 37 | + |
| 38 | +-- a handle for receiving BatteryTag messages |
| 39 | +local batterytag_handle = DroneCAN_Handle(0, BATTERYTAG_SIGNATURE, BATTERYTAG_ID) |
| 40 | +batterytag_handle:subscribe() |
| 41 | + |
| 42 | +-- a handle for sending GlobalTime messages |
| 43 | +local globaltime_handle = DroneCAN_Handle(0, GLOBALTIME_SIGNATURE, GLOBALTIME_ID) |
| 44 | + |
| 45 | +--[[ |
| 46 | + check for BatteryTag messages |
| 47 | +--]] |
| 48 | +local function check_batterytag() |
| 49 | + local payload, nodeid = batterytag_handle:check_message() |
| 50 | + if not payload then |
| 51 | + return |
| 52 | + end |
| 53 | + local serial_num, num_cycles, arm_hours, capacity, first_use, last_arm = string.unpack("IIfIII", payload) |
| 54 | + if not serial_num then |
| 55 | + return |
| 56 | + end |
| 57 | + |
| 58 | + -- log battery information |
| 59 | + logger:write("BTAG", |
| 60 | + 'Node,Ser,NCycle,ArmHr,Cap,FirstUse,LastArm', |
| 61 | + 'BIIfIII', |
| 62 | + '#------', |
| 63 | + '-------', |
| 64 | + nodeid, |
| 65 | + serial_num, num_cycles, arm_hours, |
| 66 | + capacity, first_use, last_arm) |
| 67 | +end |
| 68 | + |
| 69 | +local last_globaltime_send = millis() |
| 70 | + |
| 71 | +--[[ |
| 72 | + see if we should send GlobalTime message |
| 73 | +--]] |
| 74 | +local function check_globaltime() |
| 75 | + local now = millis() |
| 76 | + if now - last_globaltime_send < 1000 then |
| 77 | + return |
| 78 | + end |
| 79 | + if gps:num_sensors() < 1 or gps:status(0) < 3 then |
| 80 | + return |
| 81 | + end |
| 82 | + last_globaltime_send = now |
| 83 | + |
| 84 | + -- create 56 bit UTC microsecond timestamp |
| 85 | + local utc_usec = gps:time_epoch_usec(0) |
| 86 | + if utc_usec == 0 then |
| 87 | + return |
| 88 | + end |
| 89 | + local usec_hi,usec_lo = utc_usec:split() |
| 90 | + local payload8 = string.pack("II", usec_lo:toint(), usec_hi:toint()) |
| 91 | + local payload7 = string.sub(payload8, 1, 7) |
| 92 | + globaltime_handle:broadcast(payload7) |
| 93 | +end |
| 94 | + |
| 95 | +local function update() |
| 96 | + if BTAG_ENABLE:get() ~= 0 then |
| 97 | + check_batterytag() |
| 98 | + check_globaltime() |
| 99 | + end |
| 100 | + return update, 200 |
| 101 | +end |
| 102 | + |
| 103 | +gcs:send_text(MAV_SEVERITY.INFO, "BatteryTag loaded") |
| 104 | + |
| 105 | +return update, 1000 |
0 commit comments