# # Include files # include "string.bzz" include "vec2.bzz" include "update.bzz" include "barrier.bzz" # don't use a stigmergy id=11 with this header. include "uavstates.bzz" # require an 'action' function to be defined here. include "graphs/shapes_square.bzz" ROBOT_RADIUS=50 ROBOT_DIAMETER=2.0*ROBOT_RADIUS ROBOT_SAFETYDIST=2.0*ROBOT_DIAMETER # # Global variables # # #Save message from all neighours #the indexes are as 1,2,3..., while each value is a table that store the information of a neighbour robot m_MessageState={}#store received neighbour message m_MessageLable={}#store received neighbour message m_MessageReqLable={}#store received neighbour message m_MessageReqID={}#store received neighbour message m_MessageResponse={}#store received neighbour message m_MessageRange={}#store received neighbour message m_MessageBearing={}#store received neighbour message m_neighbourCunt=0#used to cunt neighbours #Save message from one neighbour #the indexes are as State(received state),Lable(received lable),ReqLable,ReqID,Response,Range,Bearing m_receivedMessage={.State=s2i("STATE_FREE"),.Lable=0,.ReqLable=0,.ReqID=0,.Response=r2i("REQ_NONE"),.Range=0,.Bearing=0} # #Save the message to send #The keys of the talbe is State(current state),Lable(current lable),ReqLable(requested lable),ReqID(request id),Response(reply message{REQ_NONE,REQ_GRANTED,REQ_RESEND}) m_selfMessage={.State=s2i("STATE_FREE"),.Lable=0,.ReqLable=0,.ReqID=0,.Response=r2i("REQ_NONE")} #Current robot state m_eState="STATE_FREE" #navigation vector m_navigation={.x=0,.y=0} #Debug message to be displayed in qt-opengl #m_ossDebugMsg #Debug vector to draw #CVector2 m_cDebugVector #Current label being requested or chosen (-1 when none) m_nLabel=-1 m_messageID={} #neighbor distance to lock the current pattern lock_neighbor_id={} lock_neighbor_dis={} #Label request id m_unRequestId=0 #Global bias, used to map local coordinate to global coordinate m_bias=0 #Vector to predecessor,range is the distance between robots, bearing is the angle of pred wrt self in local coordinate of self, globalbearing is the angle of self wrt pred in global coordinate m_cMeToPred={.Range=0.0,.Bearing=0.0,.GlobalBearing=0.0} #Counter to wait for something to happen m_unWaitCount=0 #Number of steps to wait before looking for a free label m_unLabelSearchWaitTime=0 #Number of steps to wait for an answer to be received m_unResponseTimeThreshold=0 #Number of steps to wait until giving up joining m_unJoiningLostPeriod=0 #Tolerance distance to a target location m_fTargetDistanceTolerance=0 #step cunt step_cunt=0 #virtual stigmergy v_tag = stigmergy.create(1) # Lennard-Jones parameters, may need change EPSILON = 13.5 #the LJ parameter for other robots EPSILON_FOR1 = 10.0 #the LJ parameter for the robot labeled 1 # Lennard-Jones interaction magnitude function FlockInteraction(dist,target,epsilon){ var mag = -(epsilon / dist) * ((target / dist)^4 - (target / dist)^2) return mag } function LimitAngle(angle){ if(angle>2*math.pi) return angle-2*math.pi else if (angle<0) return angle+2*math.pi else return angle } # # Calculates the angle of the given vector2. # PARAM v: The vector2. # RETURN: The angle of the vector. # Angle = function(v) { return math.atan(v.y, v.x) } # #return the number of value in table # function count(table,value){ var number=0 var i=0 while(i=0){ pon=0 } else{ pon=1 } var b=math.abs(send_table.Bearing) send_value=r_id*1000+pon*100+b return send_value } # #unpack message # function unpackmessage(recv_value){ var wan=(recv_value-recv_value%10000)/10000 recv_value=recv_value-wan*10000 var qian=(recv_value-recv_value%1000)/1000 recv_value=recv_value-qian*1000 var bai=(recv_value-recv_value%100)/100 recv_value=recv_value-bai*100 var shi=(recv_value-recv_value%10)/10 recv_value=recv_value-shi*10 var ge=recv_value var return_table={.State=0.0,.Lable=0.0,.Reqlable=0.0,.ReqID=0.0,.Response=0.0} return_table.State=wan return_table.Lable=qian return_table.ReqLable=bai return_table.ReqID=shi return_table.Response=ge return return_table } # #unpack guide message # function unpack_guide_msg(recv_value){ log(id,"I pass value=",recv_value) var qian=(recv_value-recv_value%1000)/1000 recv_value=recv_value-qian*1000 var bai=(recv_value-recv_value%100)/100 recv_value=recv_value-bai*100 var b=recv_value var return_table={.Label=0.0,.Bearing=0.0} return_table.Label=qian if(bai==1){ b=b*-1.0 } return_table.Bearing=b return return_table } #get the target distance to neighbr nei_id function target4label(nei_id){ var return_val="miss" var i=0 while(i0) and (m_vecNodes[i].State=="ASSIGNING")){ m_vecNodes[i].StateAge=m_vecNodes[i].StateAge-1 if(m_vecNodes[i].StateAge==0) m_vecNodes[i].State="UNASSIGNED" } i=i+1 } } # #Transistion to state free # function TransitionToFree(){ m_eState="STATE_FREE" m_unWaitCount=m_unLabelSearchWaitTime m_selfMessage.State=s2i(m_eState) } # #Transistion to state asking # function TransitionToAsking(un_label){ m_eState="STATE_ASKING" m_nLabel=un_label m_unRequestId=id #don't know why the random numbers are the same, add id to make the ReqID different m_selfMessage.State=s2i(m_eState) m_selfMessage.ReqLable=m_nLabel m_selfMessage.ReqID=m_unRequestId m_unWaitCount=m_unResponseTimeThreshold } # #Transistion to state joining # function TransitionToJoining(){ m_eState="STATE_JOINING" m_selfMessage.State=s2i(m_eState) m_selfMessage.Lable=m_nLabel m_unWaitCount=m_unJoiningLostPeriod neighbors.listen("r", function(vid,value,rid){ var recv_table={.Label=0,.Bearing=0.0} recv_table=unpack_guide_msg(value) #store the received message if(recv_table.Label==m_nLabel){ m_cMeToPred.GlobalBearing=recv_table.Bearing } }) } # #Transistion to state joined # function TransitionToJoined(){ m_eState="STATE_JOINED" m_selfMessage.State=s2i(m_eState) m_selfMessage.Lable=m_nLabel m_vecNodes[m_nLabel].State="ASSIGNED" neighbors.ignore("r") #write statues v_tag.put(m_nLabel, 1) m_navigation.x=0.0 m_navigation.y=0.0 uav_moveto(m_navigation.x/100.0,m_navigation.y/100.0) } # #Transistion to state Lock, lock the current formation # # #Transistion to state Lock, lock the current formation # function TransitionToLock(){ m_eState="STATE_LOCK" m_selfMessage.State=s2i(m_eState) m_selfMessage.Lable=m_nLabel m_vecNodes[m_nLabel].State="ASSIGNED" #record neighbor distance lock_neighbor_id={} lock_neighbor_dis={} var i=0 while(i0) m_unWaitCount=m_unWaitCount-1 #find a set of joined robots var setJoinedLables={} var setJoinedIndexes={} var i=0 var j=0 while(i0){ TransitionToAsking(unFoundLable) return } #navigation #if there is a joined robot within sight, move around joined robots #else, gather with other free robots if(size(setJoinedIndexes)>0){ var tempvec_P={.x=0.0,.y=0.0} var tempvec_N={.x=0.0,.y=0.0} i=0 while(imath.pi) S2PGlobalBearing=m_cMeToPred.GlobalBearing-math.pi else S2PGlobalBearing=m_cMeToPred.GlobalBearing+math.pi var S2Pred=math.vec2.newp(m_cMeToPred.Range,S2PGlobalBearing) #the vector from self to target in global coordinate var S2Target=math.vec2.add(S2Pred,P2Target) #change the vector to local coordinate of self var S2Target_bearing=Angle(S2Target) m_bias=m_cMeToPred.Bearing-S2PGlobalBearing S2Target_bearing=S2Target_bearing+m_bias # commented out by DS'06/17 m_navigation=math.vec2.newp(math.vec2.length(S2Target),S2Target_bearing) uav_moveto(m_navigation.x/100.0,m_navigation.y/100.0) #test if is already in desired position if(math.abs(S2Target.x)m_MessageRange[mapRequests[i]]) ReqIndex=i i=i+1 } #get the best index, whose Reqlable and Reqid are ReqLable=m_MessageReqLable[mapRequests[ReqIndex]] var ReqID=m_MessageReqID[mapRequests[ReqIndex]] m_selfMessage.ReqLable=ReqLable m_selfMessage.ReqID=ReqID m_selfMessage.Response=r2i("REQ_GRANTED") } #lost pred, wait for some time and transit to free #if(seenPred==0){ #m_unWaitCount=m_unWaitCount-1 #if(m_unWaitCount==0){ #TransitionToFree() #return #} #} m_navigation.x=0.0 m_navigation.y=0.0 uav_moveto(m_navigation.x/100.0,m_navigation.y/100.0) #check if should to transists to lock if(v_tag.size()==ROBOTS){ TransitionToLock() } } # #Do Lock # function DoLock(){ m_selfMessage.State=s2i(m_eState) m_selfMessage.Lable=m_nLabel m_navigation.x=0.0 m_navigation.y=0.0 #calculate motion vection if(m_nLabel==0){ m_navigation.x=0.0#change value so that robot 0 will move m_navigation.y=0.0 log(";",m_nLabel,";",0) } if(m_nLabel!=0){ m_navigation=motion_vector() } #move goto(m_navigation.x,m_navigation.y) } function action(){ statef=action UAVSTATE="GRAPH" } # # Executed at init # function init() { # #Adjust parameters here # m_unResponseTimeThreshold=10 m_unLabelSearchWaitTime=10 m_fTargetDistanceTolerance=10 m_unJoiningLostPeriod=100 # # Join Swarm # uav_initswarm() Reset(); } # # Executed every step # function step(){ uav_rccmd() uav_neicmd() #update the graph UpdateNodeInfo() #reset message package to be sent m_selfMessage={.State=s2i("STATE_FREE"),.Lable=0,.ReqLable=0,.ReqID=0,.Response=r2i("REQ_NONE")} # #act according to current state # if(UAVSTATE=="GRAPH"){ if(m_eState=="STATE_FREE") DoFree() else if(m_eState=="STATE_ESCAPE") DoEscape() else if(m_eState=="STATE_ASKING") DoAsking() else if(m_eState=="STATE_JOINING") DoJoining() else if(m_eState=="STATE_JOINED") DoJoined() else if(m_eState=="STATE_LOCK") DoLock() } statef() debug(m_eState,m_nLabel) log("Current state: ", UAVSTATE) log("Swarm size: ", ROBOTS) #navigation #broadcast messag neighbors.broadcast("m",packmessage(m_selfMessage)) # #clean message storage m_MessageState={}#store received neighbour message m_MessageLable={}#store received neighbour message m_MessageReqLable={}#store received neighbour message m_MessageReqID={}#store received neighbour message m_MessageResponse={}#store received neighbour message m_MessageRange={}#store received neighbour message m_MessageBearing={}#store received neighbour message m_neighbourCunt=0 #step cunt+1 step_cunt=step_cunt+1 } # # Executed when reset # function Reset(){ #m_vecNodes={} #m_vecNodes = parse_graph("/home/dave/ROS_WS/src/rosbuzz/buzz_scripts/include/Graph_drone.graph")#change the .graph file when necessary # m_vecNodes_fixed={} # m_vecNodes_fixed=parse_graph_fixed("/home/dave/ROS_WS/src/rosbuzz/buzz_scripts/include/Graph_fixed.graph") m_nLabel=-1 #start listening start_listen() # #set initial state, only one robot choose [A], while the rest choose [B] # #[A]The robot used to triger the formation process is defined as joined, if(id==0){ m_nLabel=0 TransitionToJoined() } #[B]Other robots are defined as free. else{ TransitionToFree() } } # # Executed upon destroy # function destroy() { #clear neighbour message uav_moveto(0.0,0.0) m_vecNodes={} #stop listening neighbors.ignore("m") }