Closed mdecourse closed 6 years ago
if (sim_call_type==sim_childscriptcall_initialization) then
steer_handle= simGetObjectHandle('steer_joint')
motor_handle= simGetObjectHandle('motor_joint')
fl_brake_handle= simGetObjectHandle('fl_brake_joint')
fr_brake_handle= simGetObjectHandle('fr_brake_joint')
bl_brake_handle= simGetObjectHandle('bl_brake_joint')
br_brake_handle= simGetObjectHandle('br_brake_joint')
--wheel radius: 0.09
--wheel base: 0.6
--wheel track: 0.35
--maximum steering rate: 70 deg/sec
--the maximum steer angle 30 degree
max_steer_angle=0.5235987
--the maximum torque of the motor
motor_torque=60
dVel=1
dSteer=0.1
--input steer
steer_angle=0
--input velocity
motor_velocity=dVel*10
--input brake
brake_force=0
end
if (sim_call_type==sim_childscriptcall_cleanup) then
end
if (sim_call_type==sim_childscriptcall_actuation) then
--current steer pos
steer_pos=simGetJointPosition(steer_handle);
--current angular velocity of back left wheel
bl_wheel_velocity=simGetObjectFloatParameter(bl_brake_handle,sim_jointfloatparam_velocity)
--current angular velocity of back right wheel
br_wheel_velocity=simGetObjectFloatParameter(br_brake_handle,sim_jointfloatparam_velocity)
--average angular velocity of the back wheels
rear_wheel_velocity=(bl_wheel_velocity+br_wheel_velocity)/2
--linear velocity
linear_velocity=rear_wheel_velocity*0.09
-- Read the keyboard messages (make sure the focus is on the main window, scene view):
message,auxiliaryData=simGetSimulatorMessage()
while message~=-1 do
if (message==sim_message_keypress) then
if (auxiliaryData[1]==2007) then
-- up key
if (motor_velocity<dVel*9.99) then
motor_velocity=motor_velocity+dVel
end
end
if (auxiliaryData[1]==2008) then
-- down key
if (motor_velocity>-dVel*1.99) then
motor_velocity=motor_velocity-dVel
else
-- brake_force=100
end
end
if (auxiliaryData[1]==string.byte('a')) then
-- a char key
--if (auxiliaryData[1]==string.byte('a')) then
-- left key
if (steer_angle<dSteer*4.99) then
steer_angle=steer_angle+dSteer
end
end
if (auxiliaryData[1]==2010) then
-- right key
if (steer_angle>-dSteer*4.99) then
steer_angle=steer_angle-dSteer
end
end
end
message,auxiliaryData=simGetSimulatorMessage()
end
if (math.abs(motor_velocity)<dVel*0.1) then
brake_force=100
else
brake_force=0
end
--set maximum steer angle
if (steer_angle> max_steer_angle) then
steer_angle=max_steer_angle
end
if (steer_angle< -max_steer_angle) then
steer_angle= -max_steer_angle
end
simSetJointTargetPosition(steer_handle, steer_angle)
--brake and motor can not be applied at the same time
if(brake_force>0) then
simSetJointForce(motor_handle, 0)
else
simSetJointForce(motor_handle, motor_torque)
simSetJointTargetVelocity(motor_handle, motor_velocity)
end
simSetJointForce(fr_brake_handle, brake_force)
simSetJointForce(fl_brake_handle, brake_force)
simSetJointForce(bl_brake_handle, brake_force)
simSetJointForce(br_brake_handle, brake_force)
end
E-puck lua scripts:
-- This is the Epuck principal control script. It is threaded
-- FUNCTION MOVE
-- Moving the robot
-- distance : distance (meters)
-- velLeft : angular speed left wheel
-- velRight : angular speed rigth wheel
move = function(distance, velLeft, velRight)
simSetJointTargetVelocity(leftMotor, velLeft)
simSetJointTargetVelocity(rightMotor, velRight)
local i = 0
local distanceParcourue = 0
local p = simGetObjectPosition(ePuckBase, -1)
local p1 = simGetObjectPosition(ePuckBase, -1)
-- time-out : variable i
while (i < 1000 and distanceParcourue < distance) do
p1 = simGetObjectPosition(ePuckBase, -1)
distanceParcourue = distanceMes(p[1], p[2], p1[1], p1[2])
--simAddStatusbarMessage('parcourue :' .. distanceParcourue .. ' - Attendue :' .. distance)
i = i + 1
simSwitchThread()
end
simSetJointTargetVelocity(leftMotor,0)
simSetJointTargetVelocity(rightMotor,0)
end
-- FUNCTION TURNLEFT
-- Make a left turn (90°)
-- vel : angular speed of wheels
turnLeft=function(vel)
local rotAmount=-math.pi/2
local sign=rotAmount/math.abs(rotAmount)
simSetJointTargetVelocity(leftMotor,vel*sign*0.5)
simSetJointTargetVelocity(rightMotor,-vel*sign*0.5)
local previousAngle=simGetObjectOrientation(ePuckBase,-1)[3]
local rot=0
local i = 0
while (i < 1000) do --and (math.abs(rot) < math.pi/2)
local angle=simGetObjectOrientation(ePuckBase,-1)[3]
local da=angle-previousAngle
if da>=0 then
da=math.mod(da+math.pi,2*math.pi)-math.pi
else
da=math.mod(da-math.pi,2*math.pi)+math.pi
end
rot=rot+da
previousAngle=angle
if math.abs(rot)>math.pi/2 then
break
end
simSwitchThread()
end
simSetJointTargetVelocity(leftMotor,0)
simSetJointTargetVelocity(rightMotor,0)
end
-- FUNCTION TURNRIGHT
-- Make a right turn (90°)
-- vel : angular speed of wheels
turnRight=function(vel)
local rotAmount=math.pi/2
local sign=rotAmount/math.abs(rotAmount)
simSetJointTargetVelocity(leftMotor,vel*sign*0.5)
simSetJointTargetVelocity(rightMotor,-vel*sign*0.5)
local previousAngle=simGetObjectOrientation(ePuckBase,-1)[3]
local rot=0
local i = 0
while (i < 1000) do --and (math.abs(rot) < math.pi/2)
local angle=simGetObjectOrientation(ePuckBase,-1)[3]
local da=angle-previousAngle
if da>=0 then
da=math.mod(da+math.pi,2*math.pi)-math.pi
else
da=math.mod(da-math.pi,2*math.pi)+math.pi
end
rot=rot+da
previousAngle=angle
if math.abs(rot)>math.pi/2 then
break
end
simSwitchThread()
end
simSetJointTargetVelocity(leftMotor,0)
simSetJointTargetVelocity(rightMotor,0)
end
-- FONCTION UTURN
-- Make a half turn (180°)
-- vel : angular speed of wheels
uTurn=function(vel)
local rotAmount=math.pi/2
local sign=rotAmount/math.abs(rotAmount)
simSetJointTargetVelocity(leftMotor,vel*sign*0.5)
simSetJointTargetVelocity(rightMotor,-vel*sign*0.5)
local previousAngle=simGetObjectOrientation(ePuckBase,-1)[3]
local rot=0
local i = 0
while (i < 1000) do --and (math.abs(rot) < math.pi/2)
local angle=simGetObjectOrientation(ePuckBase,-1)[3]
local da=angle-previousAngle
if da>=0 then
da=math.mod(da+math.pi,2*math.pi)-math.pi
else
da=math.mod(da-math.pi,2*math.pi)+math.pi
end
rot=rot+da
previousAngle=angle
if math.abs(rot)>math.pi then
break
end
simSwitchThread()
end
simSetJointTargetVelocity(leftMotor,0)
simSetJointTargetVelocity(rightMotor,0)
end
-- FUNCTION DISTANCE
-- Measure the absolute distance between point A(xa, yx) and B(xb, yb)
-- xa : coordinates x of first point (A)
-- ya : coordinates y of first point (A)
-- xb : coordinates x of second point (B)
-- yb : coordinates y of second point (B)
-- return : absolute distance between points
distanceMes = function(xa, ya, xb, yb)
return math.sqrt( math.pow((xb - xa), 2) + math.pow((yb - ya), 2) )
end
-- FUNCTION SENSORS
-- Save actual state (true/false) of sensors
sensors = function()
local boolSensors = 0x0
local sc=simGetObjectSizeFactor(bodyElements)
local r = 0
local d = 0
local i=0
for i=1,8,1 do
--r,d = simCheckProximitySensor(proxSens[i], sim_handle_all)
r,d = simReadProximitySensor(proxSens[i])
mask = math.pow(2, (i-1))
notMask = simBoolXor32(mask, 0xFFFFFFFF)
-- if res > 0 and dist < 0.05*s then
if (r > 0) then
boolSensors = simBoolOr32(boolSensors, mask)
--simAddStatusbarMessage('sens[' .. i .. '] - ' .. r .. ' - ' .. d)
else
boolSensors = simBoolAnd32(boolSensors, notMask)
--simAddStatusbarMessage('sens[' .. i .. ']')
end
end
return boolSensors
end
-- NOT USED
moveDistance = function(distance, vel, vel2)
local i = 0
local distanceParcourue = 0
local p = simGetObjectPosition(ePuckBase, -1)
local p1 = simGetObjectPosition(ePuckBase, -1)
bodyElements=simGetObjectHandle('ePuck_bodyElements')
s=simGetObjectSizeFactor(bodyElements)
simSetJointTargetVelocity(leftMotor,vel)
simSetJointTargetVelocity(rightMotor,vel)
velLeft=vel
velRight=vel
maxVel = vel
while (i < 1000 and distanceParcourue < distance) do
noDetectionDistance=0.05*s --0.05
proxSensDist={noDetectionDistance,noDetectionDistance,noDetectionDistance,noDetectionDistance,noDetectionDistance,noDetectionDistance,noDetectionDistance,noDetectionDistance}
for i=1,8,1 do
res,dist=simReadProximitySensor(proxSens[i])
if (res>0) and (dist<noDetectionDistance) then
proxSensDist[i]=dist
end
end
if (proxSensDist[1] < 0.2*noDetectionDistance) then
velLeft=velLeft + maxVel * 0
velRight=velRight + maxVel * -0.05 * (1-(proxSensDist[2]/noDetectionDistance))
--velRight=velRight + maxVel * -0.05
elseif (proxSensDist[6] < 0.2*noDetectionDistance) then
velLeft=velLeft + maxVel * -0.05 * (1-(proxSensDist[4]/noDetectionDistance))
--velLeft=velLeft + maxVel * -0.05
velRight=velRight + maxVel * 0
else
velLeft=vel
velRight=vel
end
p1 = simGetObjectPosition(ePuckBase, -1)
distanceParcourue = distanceMes(p[1], p[2], p1[1], p1[2])
i = i + 1
simSetJointTargetVelocity(leftMotor,velLeft)
simSetJointTargetVelocity(rightMotor,velRight)
simSwitchThread()
end --while
simSetJointTargetVelocity(leftMotor,0)
simSetJointTargetVelocity(rightMotor,0)
end --function
actualizeLEDs=function()
if (relLedPositions==nil) then
relLedPositions={{-0.0343,0,0.0394},{-0.0297,0.0171,0.0394},{0,0.0343,0.0394},
{0.0297,0.0171,0.0394},{0.0343,0,0.0394},{0.0243,-0.0243,0.0394},
{0.006,-0.0338,0.0394},{-0.006,-0.0338,0.0394},{-0.0243, -0.0243,0.0394}}
end
if (drawingObject) then
simRemoveDrawingObject(drawingObject)
end
type=sim_drawing_painttag+sim_drawing_followparentvisibility+sim_drawing_spherepoints+
sim_drawing_50percenttransparency+sim_drawing_itemcolors+sim_drawing_itemsizes+
sim_drawing_backfaceculling+sim_drawing_emissioncolor
drawingObject=simAddDrawingObject(type,0,0,bodyElements,27)
m=simGetObjectMatrix(ePuckBase,-1)
itemData={0,0,0,0,0,0,0}
simSetLightParameters(ledLight,0)
for i=1,9,1 do
if (ledColors[i][1]+ledColors[i][2]+ledColors[i][3]~=0) then
p=simMultiplyVector(m,relLedPositions[i])
itemData[1]=p[1]
itemData[2]=p[2]
itemData[3]=p[3]
itemData[4]=ledColors[i][1]
itemData[5]=ledColors[i][2]
itemData[6]=ledColors[i][3]
simSetLightParameters(ledLight,1,{ledColors[i][1],ledColors[i][2],ledColors[i][3]})
for j=1,3,1 do
itemData[7]=j*0.003
simAddDrawingObjectItem(drawingObject,itemData)
end
end
end
end
getLightSensors=function()
data=simReceiveData(0,'EPUCK_lightSens')
if (data) then
lightSens=simUnpackFloatTable(data)
end
return lightSens
end
threadFunction=function()
while simGetSimulationState()~=sim_simulation_advancing_abouttostop do
st=simGetSimulationTime()
velLeft=0
velRight=0
move(1, 10, 10)
turnLeft(1)
move(1, 10, 10)
turnLeft(1)
move(1, 10, 10)
actualizeLEDs()
simSwitchThread() -- Don't waste too much time in here (simulation time will anyway only change in next thread switch)
end
end
-- Put some initialization code here:
simSetThreadSwitchTiming(200) -- We will manually switch in the main loop
bodyElements=simGetObjectHandle('ePuck_bodyElements')
leftMotor=simGetObjectHandle('ePuck_leftJoint')
rightMotor=simGetObjectHandle('ePuck_rightJoint')
ePuck=simGetObjectHandle('ePuck')
ePuckBase=simGetObjectHandle('ePuck_base')
ledLight=simGetObjectHandle('ePuck_ledLight')
proxSens={-1,-1,-1,-1,-1,-1,-1,-1}
for i=1,8,1 do
proxSens[i]=simGetObjectHandle('ePuck_proxSensor'..i)
end
maxVel=120*math.pi/180
ledColors={{0,0,0},{0,0,0},{0,0,0},{0,0,0},{0,0,0},{0,0,0},{0,0,0},{0,0,0},{0,0,0}}
-- Braitenberg weights for the 4 front prox sensors (avoidance):
braitFrontSens_leftMotor={1,2,-2,-1}
-- Braitenberg weights for the 2 side prox sensors (following):
braitSideSens_leftMotor={-1,0}
-- Braitenberg weights for the 8 sensors (following):
braitAllSensFollow_leftMotor={-3,-1.5,-0.5,0.8,1,0,0,-4}
braitAllSensFollow_rightMotor={0,1,0.8,-0.5,-1.5,-3,-4,0}
braitAllSensAvoid_leftMotor={0,0.5,1,-1,-0.5,-0.5,0,0}
braitAllSensAvoid_rightMotor={-0.5,-0.5,-1,1,0.5,0,0,0}
-- Here we execute the regular thread code:
res,err=xpcall(threadFunction,function(err) return debug.traceback(err) end)
if not res then
simAddStatusbarMessage('Lua runtime error: '..err)
end
-- Put some clean-up code here:
for i=1,9,1 do
ledColors[i]={0,0,0} -- no light
end
actualizeLEDs()
A Mobile Robot Solving a Virtual Maze Environment.pdf GENETIC-ALGORITHM SEEDING OF IDIOTYPIC NETWORKS FOR MOBILE-ROBOT NAVIGATION.pdf
Track = {}
Track.__index = Track
function Track.new(parent, name, roller_diam, depth, length, num_rollers)
local self = setmetatable({}, Track)
self.name = name
self.roller_diam = roller_diam
self.num_rollers = num_rollers
self.body = nil
self.roller_j = {}
self.roller = {}
self.roller_d = {}
local color_mask = false
local smooth = false
if type(self.roller_diam) ~= 'table' then
self.roller_diam = {self.roller_diam, self.roller_diam}
end
local min_d = math.min(self.roller_diam[1], self.roller_diam[2])
self.body = simCreatePureShape(0, 2, {length, min_d, 0.999*depth}, 0.06)
simSetObjectName(self.body, name)
simSetObjectParent(self.body, parent, false)
for i=1,num_rollers do
self.roller_j[i] = simCreateJoint(sim_joint_revolute_subtype, sim_jointmode_force, 0, {depth, 0.02})
simSetObjectName(self.roller_j[i], self.name .. '_r' .. i .. '_j')
simSetObjectParent(self.roller_j[i], self.body, true)
simSetObjectIntParameter(self.roller_j[i], 2000, 1)
simSetObjectPosition(self.roller_j[i], self.body, {length * (-0.5 + (i - 1) / (self.num_rollers - 1)), 0, 0})
simSetObjectOrientation(self.roller_j[i], self.body, {math.pi*0, 0, 0})
self.roller_d[i] = ((i - 1) / (self.num_rollers - 1)) * (self.roller_diam[1] - self.roller_diam[2]) + self.roller_diam[2]
self.roller[i] = simCreatePureShape(2, 2+(smooth and 4 or 0)+8, {self.roller_d[i], self.roller_d[i], depth}, 0.06)
simSetObjectName(self.roller[i], self.name .. '_r' .. i)
simSetObjectParent(self.roller[i], self.roller_j[i], false)
local k = (i - 1) % 8
simSetObjectIntParameter(self.roller[i], 3019, 2^k+(2^8-1)*2^8)
simResetDynamicObject(self.roller[i])
if color_mask then simSetShapeColor(self.roller[i], nil, sim_colorcomponent_ambient_diffuse, ({{1,0,0}, {0,1,0}, {0,0,1}, {1,1,0}, {1,0,1}, {0,0,0}, {0,1,1}, {1,1,1}})[1+k]) end
end
return self
end
function Track.setVelocity(self, vel)
for i=1,self.num_rollers do
simSetJointTargetVelocity(self.roller_j[i], 2 * vel / self.roller_d[i])
end
end
TrackedRobot = {}
TrackedRobot.__index = TrackedRobot
function TrackedRobot.new(parent, name, body_size, hoff, joffx, joffz, track_length, flipper_length, track_diam, flipper_diam, track_depth, flipper_depth, num_rollers, body_track_spacing, track_flipper_spacing)
local self = setmetatable({}, TrackedRobot)
self.name = name
self.track_diam = track_diam
self.flipper_diam = flipper_diam
self.num_rollers = num_rollers
self.lr = {'l', 'r'}
self.fr = {'f', 'r'}
self.body = nil
self.track_j = {}
self.track = {}
self.flipper_j = {{},{}}
self.flipper = {{},{}}
local static_root = false
local flippers = true
self.body = simCreatePureShape(0, 2+8+(static_root and 16 or 0), body_size, 0.006)
simSetObjectName(self.body, self.name)
local joffy = {0.5*(body_size[2]+track_depth)+body_track_spacing, -0.5*(body_size[2]+track_depth)-body_track_spacing}
local toffy = {0.5*track_depth, -0.5*track_depth}
local jrot = {math.pi, 0}
for t=1,2 do
self.track_j[t] = simCreateJoint(sim_joint_revolute_subtype, sim_jointmode_force, 0, {track_depth, 0.02})
simSetObjectName(self.track_j[t], self.name .. '_t' .. self.lr[t] .. '_j')
simSetObjectParent(self.track_j[t], self.body, false)
simSetObjectPosition(self.track_j[t], self.body, {joffx,joffy[t],-0.5*body_size[3]-hoff+joffz})
simSetObjectOrientation(self.track_j[t], self.body, {math.pi*0.5,jrot[t],0})
simSetObjectIntParameter(self.track_j[t], 2000, 1)
simSetJointForce(self.track_j[t], 20)
self.track[t] = Track.new(self.track_j[t], self.name .. '_t' .. self.lr[t], track_diam, track_depth, track_length, num_rollers)
local xoff = {-0.5*track_length, 0.5*track_length}
local aoff = {0, math.pi}
for f=1,(flippers and 2 or 0) do
self.flipper_j[t][f] = simCreateJoint(sim_joint_revolute_subtype, sim_jointmode_force, 0, {track_depth+flipper_depth, 0.02})
simSetObjectName(self.flipper_j[t][f], self.name .. '_t' .. self.lr[t] .. '_f' .. self.fr[f] .. '_j')
simSetObjectParent(self.flipper_j[t][f], self.track[t].body, false)
simSetObjectPosition(self.flipper_j[t][f], self.track[t].body, {xoff[f],0,track_flipper_spacing+0.5*track_depth+0.5*flipper_depth})
simSetObjectOrientation(self.flipper_j[t][f], self.track[t].body, {0,0,0})
simSetObjectIntParameter(self.flipper_j[t][f], 2000, 1)
self.flipper[t][f] = Track.new(self.flipper_j[t][f], self.name .. '_t' .. self.lr[t] .. '_f' .. self.fr[f], {track_diam, flipper_diam}, flipper_depth, flipper_length, num_rollers)
simSetObjectPosition(self.flipper[t][f].body, self.flipper_j[t][f], {-0.5*flipper_length, 0, 0})
simSetJointPosition(self.flipper_j[t][f], aoff[f])
end
end
simSetObjectParent(self.body, parent, true)
local script = simAddScript(sim_scripttype_childscript)
simAssociateScriptWithObject(script, self.body)
simSetScriptText(script, [[
if (sim_call_type==sim_childscriptcall_initialization) then
left_track_j = simGetObjectHandle(']]..name..[[_tl_j')
right_track_j = simGetObjectHandle(']]..name..[[_tr_j')
end
if (sim_call_type==sim_childscriptcall_actuation) then
local l = simGetJointPosition(left_track_j)
local r = simGetJointPosition(right_track_j)
local m = (l+r)/2
simSetJointTargetVelocity(left_track_j, m-l)
simSetJointTargetVelocity(right_track_j, m-r)
end
]])
simSetModelProperty(self.body, 0)
return self
end
function TrackedRobot.setVelocity(self, vel)
local vs = {-1, 1}
for t=1,2 do
self.track[t]:setVelocity(vel[t]*vs[t])
self.flipper[t][1]:setVelocity(vel[t]*vs[t])
self.flipper[t][2]:setVelocity(vel[t]*vs[t])
end
end
self=simGetObjectAssociatedWithScript(sim_handle_self)
--[[
simInt simCreatePureShape(simInt primitiveType,simInt options,
const simFloat* sizes,simFloat mass,const simInt* precision)
primitiveType: 0 for a cuboid, 1 for a sphere, 2 for a cylinder and 3 for a cone
options: Bit-coded: if bit0 is set (1), backfaces are culled. If bit1 is set (2),
edges are visible. If bit2 is set (4), the shape appears smooth.
If bit3 is set (8), the shape is respondable.
If bit4 is set (16), the shape is static. If bit5 is set (32), the cylinder has open ends
sizes: 3 values indicating the size of the shape
mass: the mass of the shape
precision: 2 values that allow specifying the number of sides and faces of a cylinder or sphere.
Can be NULL for default values
]]
local ball1 = simCreatePureShape(1, 8, {0.2, 0, 0}, 0, nil)
simSetObjectPosition(ball1, self, {0.25 , 1 , 1})
simSetObjectName(ball1, "ball1")
local ball2 = simCreatePureShape(1, 8, {0.2, 0, 0}, 0, nil)
simSetObjectPosition(ball2, self, {-0.25 , 1 , 2})
simSetObjectName(ball2, "ball2")
另一範例:
-- Save current selection state:
currentSelection=simGetObjectSelection()
-- Copy an object:
simRemoveObjectFromSelection(sim_handle_all,-1)
simAddObjectToSelection(sim_handle_single,shapeHandle)
simCopyPasteSelectedObjects()
copy=simGetObjectSelection()[1] -- this is the copy
-- now change some parameters of the copy (e.g. its color):
simSetShapeColor(copy,nil,0,{0.67,0.16,0.16})
-- Restore the initial selection state:
simRemoveObjectFromSelection(sim_handle_all,-1)
simAddObjectToSelection(currentSelection)
Above code is taken from the demo scene blobDetectionWithPickAndPlace.ttt, from the child script attached to object partsProducer.
local seen={}
function dump(t,i)
seen[t]=true
local s={}
local n=0
for k in pairs(t) do
n=n+1 s[n]=k
end
table.sort(s)
for k,v in ipairs(s) do
print(i,v)
v=t[v]
if type(v)=="table" and not seen[v] then
dump(v,i.."\t")
end
end
end
dump(_G,"")
Github 倉儲中的 Lua 程式碼
取自 https://gist.github.com/daurnimator/9dd8168ab14846e880e4b50546b39110#file-fengari-vue-lua
取自 https://gist.github.com/daurnimator/5a7fa933e96e14333962093322e0ff95#file-object-lua
取自 https://gist.github.com/daurnimator/f5e872f0a988f7bbd025#file-exampleseval-in-lua
取自 https://gist.github.com/daurnimator/f1c7965b47a5658b88300403645541aa#file-tarantool_cqueues-lua
取自 https://gist.github.com/daurnimator/f1c7965b47a5658b88300403645541aa#file-tarantool_http_server-lua
取自 https://gist.github.com/daurnimator/f1c7965b47a5658b88300403645541aa#file-tarantool_websocket-lua
取自 https://gist.github.com/daurnimator/72ff05933903af612bebc40aa145d519#file-dom-create-lua
取自 https://gist.github.com/daurnimator/c18b3732f452e58097c68a04f0dc2ac1#file-htmlgen-lua
取自 https://gist.github.com/daurnimator/45839b0d6bd4a94c58d2d942c04b6789#file-searchpath-lua
取自 https://gist.github.com/daurnimator/c712a77e312b4ad32f01d3cd412e21f9#file-awesome-cq-lua
取自 https://gist.github.com/daurnimator/be276c5d32329e2a9250f4aabeea48a8#file-gen_table-lua
取自 https://gist.github.com/daurnimator/192dc5b210718dd129cfc1e5986df97b#file-echo_server-lua
取自 https://gist.github.com/daurnimator/192dc5b210718dd129cfc1e5986df97b#file-nice_server-lua
取自 https://gist.github.com/daurnimator/95e9137d617689444f396b6518fbfb7c#file-brightness-lua
取自 https://gist.github.com/daurnimator/95e9137d617689444f396b6518fbfb7c#file-multimedia-lua
取自 https://gist.github.com/daurnimator/95e9137d617689444f396b6518fbfb7c#file-rc-lua
取自 https://gist.github.com/daurnimator/a19e633032c2dc5086ea63323d6a24b6#file-cleverbot-lua
取自 https://gist.github.com/daurnimator/23e36762dc62198da8804350df654ecf#file-init-lua