mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_HAL_ChibiOS: fix script for HerePro
This commit is contained in:
parent
b5f303e5e7
commit
fa631c11a1
@ -55,7 +55,7 @@ local led_map = {
|
||||
12,
|
||||
13}
|
||||
|
||||
function table.contains(table, element)
|
||||
function table_contains(table, element)
|
||||
for _, value in pairs(table) do
|
||||
if value == element then
|
||||
return true
|
||||
@ -81,11 +81,11 @@ end
|
||||
function do_initialisation()
|
||||
local pos = math.rad(total_time/2)
|
||||
local v =0.5 + 0.5 * math.sin(pos)
|
||||
local invert = 1
|
||||
local invert
|
||||
local r, g, b = get_Rainbow(v, 5)
|
||||
local led_trail_length = 3
|
||||
local softness = 10
|
||||
local bfact = 1
|
||||
local bfact
|
||||
local updated_leds = {}
|
||||
if math.cos(pos) > 0 then
|
||||
invert = 1
|
||||
@ -124,7 +124,7 @@ function do_initialisation()
|
||||
end
|
||||
|
||||
for led = 1, num_leds do
|
||||
if not table.contains(updated_leds, led) then
|
||||
if not table_contains(updated_leds, led) then
|
||||
notify:handle_rgb_id(0, 0, 0, led_map[led])
|
||||
end
|
||||
end
|
||||
@ -144,7 +144,7 @@ function do_point_north(r, g, b, led_trail_length, softness)
|
||||
end
|
||||
|
||||
for led = 1, num_leds do
|
||||
if not table.contains(updated_leds, led) then
|
||||
if not table_contains(updated_leds, led) then
|
||||
notify:handle_rgb_id(0, 0, 0, led_map[led])
|
||||
end
|
||||
end
|
||||
@ -172,7 +172,7 @@ function finish_initialisation(r, g, b, led_trail_length, softness, speed_factor
|
||||
end
|
||||
|
||||
for led = 1, num_leds do
|
||||
if not table.contains(updated_leds, led) then
|
||||
if not table_contains(updated_leds, led) then
|
||||
notify:handle_rgb_id(0, 0, 0, led_map[led])
|
||||
end
|
||||
end
|
||||
@ -183,7 +183,7 @@ function do_arm_spin(r, g, b, softness, speed_factor, arming)
|
||||
local updated_leds = {}
|
||||
|
||||
-- calculate next call based on time
|
||||
local next_call = 1
|
||||
local next_call
|
||||
if arming then
|
||||
next_call = speed_factor - math.floor(((total_time)/speed_factor) + 0.5)
|
||||
if next_call < 1 then
|
||||
@ -208,7 +208,7 @@ function do_arm_spin(r, g, b, softness, speed_factor, arming)
|
||||
end
|
||||
|
||||
for led = 1, num_leds do
|
||||
if not table.contains(updated_leds, led) then
|
||||
if not table_contains(updated_leds, led) then
|
||||
notify:handle_rgb_id(0, 0, 0, led_map[led])
|
||||
end
|
||||
end
|
||||
@ -269,19 +269,19 @@ function update() -- this is the loop which periodically runs
|
||||
finish_initialisation(rainbow[1][1], rainbow[1][2], rainbow[1][3], 5, 20, 50, next_call)
|
||||
total_time = total_time + next_call
|
||||
elseif current_anim == 2 then
|
||||
local v
|
||||
if (vehicle_state & (1<<3)) ~= uint32_t(0) or --VEHICLE_STATE_PREARM
|
||||
(vehicle_state & (1<<4)) ~= uint32_t(0) or --VEHICLE_STATE_PREARM_GPS
|
||||
(vehicle_state & (1<<7)) ~= uint32_t(0) or --VEHICLE_STATE_FAILSAFE_RADIO
|
||||
(vehicle_state & (1<<8)) ~= uint32_t(0) or --VEHICLE_STATE_FAILSAFE_BATT
|
||||
(vehicle_state & (1<<11)) ~= uint32_t(0) then --VEHICLE_STATE_EKF_BAD
|
||||
v = 0.0
|
||||
end
|
||||
if (vehicle_state & (1<<17)) == uint32_t(0) then--VEHICLE_STATE_POS_ABS_AVAIL
|
||||
v = 0.5 + (0.5 * math.min(gps:num_sats(0)/20, 1.0))
|
||||
else
|
||||
v = 1.0
|
||||
end
|
||||
-- local v
|
||||
-- if (vehicle_state & (1<<3)) ~= uint32_t(0) or --VEHICLE_STATE_PREARM
|
||||
-- (vehicle_state & (1<<4)) ~= uint32_t(0) or --VEHICLE_STATE_PREARM_GPS
|
||||
-- (vehicle_state & (1<<7)) ~= uint32_t(0) or --VEHICLE_STATE_FAILSAFE_RADIO
|
||||
-- (vehicle_state & (1<<8)) ~= uint32_t(0) or --VEHICLE_STATE_FAILSAFE_BATT
|
||||
-- (vehicle_state & (1<<11)) ~= uint32_t(0) then --VEHICLE_STATE_EKF_BAD
|
||||
-- v = 0.0
|
||||
-- end
|
||||
-- if (vehicle_state & (1<<17)) == uint32_t(0) then--VEHICLE_STATE_POS_ABS_AVAIL
|
||||
-- v = 0.5 + (0.5 * math.min(gps:num_sats(0)/20, 1.0))
|
||||
-- else
|
||||
-- v = 1.0
|
||||
-- end
|
||||
local r, g, b = get_Rainbow(v, 4)
|
||||
count = do_point_north(r, g, b, 5, 20)
|
||||
-- --[[ ARM Display
|
||||
|
Loading…
Reference in New Issue
Block a user