2017-12-22 17:48:39 -04:00
########################################
#
# FLIGHT-RELATED FUNCTIONS
#
########################################
include "utils/vec2.bzz"
include "act/barrier.bzz"
include "utils/conversions.bzz"
2018-11-11 16:11:41 -04:00
include "utils/quickhull.bzz"
2018-10-18 23:18:12 -03:00
include "act/naviguation.bzz"
include "act/CA.bzz"
include "act/neighborcomm.bzz"
2017-12-22 17:48:39 -04:00
TARGET_ALTITUDE = 15.0 # m.
BVMSTATE = "TURNEDOFF"
PICTURE_WAIT = 20 # steps
2018-11-04 17:27:11 -04:00
WP_STIG = 8
2018-09-06 13:47:38 -03:00
2017-12-22 17:48:39 -04:00
path_it = 0
pic_time = 0
g_it = 0
2018-10-18 23:18:12 -03:00
# Core state function when on the ground
2017-12-22 17:48:39 -04:00
function turnedoff() {
BVMSTATE = "TURNEDOFF"
}
2018-10-18 23:18:12 -03:00
# Core state function when hovering
2017-12-22 17:48:39 -04:00
function idle() {
BVMSTATE = "IDLE"
}
2018-10-18 23:18:12 -03:00
# Core state function to launch the robot: takeoff and wait for others, or stop (land)
2017-12-22 17:48:39 -04:00
function launch() {
BVMSTATE = "LAUNCH"
2018-11-11 16:11:41 -04:00
log("AUTO_LAUNCH_STATE: ", AUTO_LAUNCH_STATE)
2018-09-06 13:47:38 -03:00
if(V_TYPE == 0 or V_TYPE == 1) { # flying vehicle so TAKE_OFF
2017-12-22 17:48:39 -04:00
homegps = {.lat=pose.position.latitude, .long=pose.position.longitude}
2018-09-23 23:02:05 -03:00
if(pose.position.altitude >= TARGET_ALTITUDE-TARGET_ALTITUDE/20.0) {
2018-09-06 13:47:38 -03:00
barrier_set(ROBOTS, AUTO_LAUNCH_STATE, "STOP", 22)
barrier_ready(22)
2017-12-22 17:48:39 -04:00
} else {
log("Altitude: ", pose.position.altitude)
neighbors.broadcast("cmd", 22)
uav_takeoff(TARGET_ALTITUDE)
}
} else {
2018-09-06 13:47:38 -03:00
barrier_set(ROBOTS, AUTO_LAUNCH_STATE, "STOP", 22)
barrier_ready(22)
2017-12-22 17:48:39 -04:00
}
}
2018-10-18 23:18:12 -03:00
# Launch function version without the timeout and stop state.
2018-10-17 20:05:13 -03:00
function launch_switch() {
BVMSTATE = "LAUNCH_SWITCH"
if(V_TYPE == 0 or V_TYPE == 1) { # flying vehicle so TAKE_OFF
homegps = {.lat=pose.position.latitude, .long=pose.position.longitude}
if(pose.position.altitude >= TARGET_ALTITUDE-TARGET_ALTITUDE/20.0) {
barrier_set(ROBOTS, AUTO_LAUNCH_STATE, AUTO_LAUNCH_STATE, 22)
barrier_ready(22)
} else {
log("Altitude: ", pose.position.altitude)
neighbors.broadcast("cmd", 22)
uav_takeoff(TARGET_ALTITUDE)
}
} else {
barrier_set(ROBOTS, AUTO_LAUNCH_STATE, AUTO_LAUNCH_STATE, 22)
barrier_ready(22)
}
}
2018-09-06 13:47:38 -03:00
gohomeT=100
2018-10-18 23:18:12 -03:00
# State function to go back to ROSBuzz recorded home GPS position (at takeoff)
2018-09-06 13:47:38 -03:00
function goinghome() {
BVMSTATE = "GOHOME"
2018-11-11 16:11:41 -04:00
if(V_TYPE == 0 or V_TYPE == 1) { # flying vehicle so TAKE_OFF
if(gohomeT > 0) { # TODO: Make a real check if home is reached
gohome()
gohomeT = gohomeT - 1
} else
BVMSTATE = AUTO_LAUNCH_STATE
}
2018-09-06 13:47:38 -03:00
}
2018-10-18 23:18:12 -03:00
# Core state function to stop and land.
2017-12-22 17:48:39 -04:00
function stop() {
2018-09-06 13:47:38 -03:00
BVMSTATE = "STOP"
2017-12-22 17:48:39 -04:00
if(V_TYPE == 0 or V_TYPE == 1) { # flying vehicle so LAND
neighbors.broadcast("cmd", 21)
uav_land()
2018-09-27 13:18:43 -03:00
if(pose.position.altitude <= 0.2) {
2018-11-11 16:11:41 -04:00
BVMSTATE = "STOP"
barrier_set(ROBOTS,"TURNEDOFF","STOP", 21)
barrier_ready(21)
2017-12-22 17:48:39 -04:00
}
} else {
2018-11-11 16:11:41 -04:00
BVMSTATE = "STOP"
barrier_set(ROBOTS,"TURNEDOFF","STOP", 21)
barrier_ready(21)
2018-09-06 13:47:38 -03:00
}
2017-12-22 17:48:39 -04:00
}
2018-10-29 02:47:39 -03:00
# State functions for individual waypoint control
2018-11-06 05:01:16 -04:00
2018-10-29 02:47:39 -03:00
wpreached = 1
2018-10-18 23:18:12 -03:00
function indiWP() {
2018-11-07 13:01:40 -04:00
BVMSTATE = "WAYPOINT"
2018-11-06 05:01:16 -04:00
check_rc_wp()
2018-10-29 02:47:39 -03:00
2018-11-06 05:01:16 -04:00
wpi = v_wp.get(id)
if(wpi!=nil) {
wp = unpackWP2i(wpi)
if(wp.pro == 0) {
wpreached = 0
storegoal(wp.lat, wp.lon, pose.position.altitude)
var ls = packWP2i(wp.lat, wp.lon, 1)
v_wp.put(id,ls)
return
}
}
2018-10-19 03:34:18 -03:00
2018-10-29 02:47:39 -03:00
if(wpreached!=1)
goto_gps(indiWP_done)
2018-10-18 23:18:12 -03:00
}
2018-10-29 02:47:39 -03:00
function indiWP_done() {
2018-11-06 05:01:16 -04:00
BVMSTATE = "WAYPOINT"
2018-10-29 02:47:39 -03:00
wpreached = 1
}
2018-10-18 23:18:12 -03:00
# State function to take a picture from the camera server (developed by HS)
2017-12-22 17:48:39 -04:00
function take_picture() {
BVMSTATE="PICTURE"
2018-09-06 13:47:38 -03:00
setgimbal(0.0, 0.0, -90.0, 20.0)
2017-12-22 17:48:39 -04:00
if(pic_time==PICTURE_WAIT/2) { # wait for the drone to stabilize
2018-09-06 13:47:38 -03:00
takepicture()
2017-12-22 17:48:39 -04:00
} else if(pic_time>=PICTURE_WAIT) { # wait for the picture
2018-03-03 20:41:54 -04:00
BVMSTATE="IDLE"
2018-09-07 01:05:19 -03:00
pic_time=0
2017-12-22 17:48:39 -04:00
}
pic_time=pic_time+1
}
2018-10-18 23:18:12 -03:00
# State function to follow a moving attractor (GPS sent from a user phone)
2017-12-22 17:48:39 -04:00
function follow() {
if(size(targets)>0) {
BVMSTATE = "FOLLOW"
attractor=math.vec2.newp(0,0)
foreach(targets, function(id, tab) {
force=(0.05)*(tab.range)^4
attractor=math.vec2.add(attractor, math.vec2.newp(force, tab.bearing))
})
2018-03-03 20:41:54 -04:00
goto_abs(attractor.x, attractor.y, 0.0, 0.0)
2017-12-22 17:48:39 -04:00
} else {
log("No target in local table!")
BVMSTATE = "IDLE"
}
}
2018-10-18 23:18:12 -03:00
# State function to converge to centroid
2018-03-03 20:41:54 -04:00
function aggregate() {
BVMSTATE="AGGREGATE"
centroid = neighbors.reduce(function(rid, data, centroid) {
centroid = math.vec2.add(centroid, math.vec2.newp(data.distance, data.azimuth))
return centroid
}, {.x=0, .y=0})
if(neighbors.count() > 0)
2018-03-05 01:10:18 -04:00
centroid = math.vec2.scale(centroid, 1.0 / neighbors.count())
cmdbin = math.vec2.sub(centroid, math.vec2.newp(3.0, id * 2 * math.pi / ROBOTS))
2018-03-04 22:44:39 -04:00
cmdbin = LimitSpeed(cmdbin, 1.0/2.0)
2018-09-07 01:05:19 -03:00
goto_abs(cmdbin.x, cmdbin.y, 0.0, 0.0)
2018-03-03 20:41:54 -04:00
}
2018-10-18 23:18:12 -03:00
# State fucntion to circle all together around centroid
2018-03-03 20:41:54 -04:00
function pursuit() {
BVMSTATE="PURSUIT"
2018-09-06 13:47:38 -03:00
rd = 20.0
2018-03-05 01:10:18 -04:00
pc = 3.2
vd = 15.0
r_vec = neighbors.reduce(function(rid, data, r_vec) {
r_vec = math.vec2.add(r_vec, math.vec2.newp(data.distance, data.azimuth))
return r_vec
2018-03-04 22:44:39 -04:00
}, {.x=0, .y=0})
if(neighbors.count() > 0)
2018-03-05 01:10:18 -04:00
r_vec = math.vec2.scale(r_vec, 1.0 / neighbors.count())
r = math.vec2.length(r_vec)
2018-09-06 13:47:38 -03:00
var sqr = (r-rd)*(r-rd)+pc*pc*r*r
gamma = vd / math.sqrt(sqr)
2018-03-05 01:10:18 -04:00
dr = -gamma * (r-rd)
dT = gamma * pc
vfg = math.vec2.newp(r+dr*0.1, math.vec2.angle(r_vec)+dT*0.1)
vfg = LimitSpeed(vfg, 2.0)
2018-09-07 01:05:19 -03:00
goto_abs(vfg.x, vfg.y, 0.0, 0.0)
2018-03-03 20:41:54 -04:00
}
# Lennard-Jones interaction magnitude
2018-11-07 11:24:06 -04:00
TARGET = 8.0
2018-11-06 05:01:16 -04:00
EPSILON = 30.0 #30
GAIN_ATT = 50.0
GAIN_REP = 30.0
2018-03-03 20:41:54 -04:00
function lj_magnitude(dist, target, epsilon) {
2018-11-07 11:24:06 -04:00
lj = -(epsilon / dist) * ((target / dist)^4 - (target / dist)^2) #repulse only to avoid each other
2018-03-04 22:44:39 -04:00
return lj
2018-03-03 20:41:54 -04:00
}
2018-09-07 01:05:19 -03:00
2018-03-03 20:41:54 -04:00
# Neighbor data to LJ interaction vector
function lj_vector(rid, data) {
return math.vec2.newp(lj_magnitude(data.distance, TARGET, EPSILON), data.azimuth)
}
2018-09-07 01:05:19 -03:00
2018-03-03 20:41:54 -04:00
# Accumulator of neighbor LJ interactions
function lj_sum(rid, data, accum) {
return math.vec2.add(data, accum)
}
2018-09-07 01:05:19 -03:00
2018-11-06 05:01:16 -04:00
# State function that calculates and actuates LJ flocking interaction with vstig targets (attractor/repulsors)
function lennardjones() {
BVMSTATE="POTENTIAL"
check_rc_wp()
2018-11-11 16:11:41 -04:00
if(V_TYPE == 2) # NOT MOVING!
return
2018-03-03 20:41:54 -04:00
# Calculate accumulator
2018-03-04 22:44:39 -04:00
accum_lj = neighbors.map(lj_vector).reduce(lj_sum, math.vec2.new(0.0, 0.0))
2018-03-03 20:41:54 -04:00
if(neighbors.count() > 0)
2018-03-05 01:10:18 -04:00
accum_lj = math.vec2.scale(accum_lj, 1.0 / neighbors.count())
2018-11-06 05:01:16 -04:00
# Add attractor/repulsor effects
log(v_wp.size())
accum_t = math.vec2.new(0.0, 0.0);
v_wp.foreach(
function(key, value, robot){
wp = unpackWP2i(value)
dvec = vec_from_gps(wp.lat, wp.lon, 0)
Tdist = math.vec2.length(dvec)
if(key > 99 and Tdist < 40)
accum_t = math.vec2.sub(accum_t, math.vec2.newp(GAIN_REP*(TARGET/Tdist)^4, math.vec2.angle(dvec)))
else if(key > 49 and Tdist > 10)
accum_t = math.vec2.add(accum_t, math.vec2.newp(GAIN_ATT*(TARGET/Tdist)^2, math.vec2.angle(dvec)))
})
if(v_wp.size() > 0)
accum_t = math.vec2.scale(accum_t, 1.0 / v_wp.size())
#log(math.vec2.length(accum_t),math.vec2.length(accum_lj))
accum_lj = LimitSpeed(math.vec2.add(accum_t,accum_lj), 1.0) #1/3
2018-09-06 13:47:38 -03:00
goto_abs(accum_lj.x, accum_lj.y, 0.0, 0.0)
2018-03-03 20:41:54 -04:00
}
2018-11-07 11:24:06 -04:00
# State function that calculates and actuates Voronoi Centroidal tessellation coverage (attractor/repulsors)
counter = 0
function voronoicentroid() {
BVMSTATE="DEPLOY"
2018-11-11 16:11:41 -04:00
check_rc_wp()
log("V_wp size:",v_wp.size())
if(V_TYPE == 2) # NOT MOVING!
return
if(not(v_wp.size() > 0))
return
it_pts = 0
att = {}
v_wp.foreach(
function(key, value, robot){
wp = unpackWP2i(value)
if(key > 99)
log("Nothing planed for the repulsors yet....")
else if(key > 49)
att[it_pts]=vec_from_gps(wp.lat, wp.lon, 0)
it_pts = it_pts + 1
})
# Boundaries from Geofence
#it_pts = 0
#foreach(GPSlimit, function(key, value) {
# bounds[it_pts]=vec_from_gps(value.lat, value.lng, 0)
# it_pts = it_pts + 1
#})
# Boundaries from user attractors
#att = {.0=vec_from_gps(45.510283, -73.609633, 0), .1=vec_from_gps(45.510398, -73.609281, 0)}
bounds = QuickHull(att)
if(size(bounds)<3 )
return
if(counter==0) {
pts = {.np=size(bounds)}
it_pts = 0
foreach(bounds, function(key, value) {
pts[it_pts]=value
it_pts = it_pts + 1
})
pts[it_pts] = {.x=0, .y=0} #add itself
it_pts = it_pts + 1
2018-11-07 11:24:06 -04:00
if(neighbors.count() > 0) {
neighbors.foreach(function(rid, data) {
2018-11-10 04:46:27 -04:00
if(rid!=0){ #remove GS (?)
2018-11-11 16:11:41 -04:00
pts[it_pts]=math.vec2.newp(data.distance,data.azimuth)
2018-11-10 04:46:27 -04:00
it_pts = it_pts + 1
}
})
2018-11-07 11:24:06 -04:00
#table_print(pts)
voronoi(pts)
}
2018-11-11 16:11:41 -04:00
counter=4
2018-11-07 11:24:06 -04:00
}
counter=counter-1
goto_gps(voronoicentroid_done)
}
function voronoicentroid_done() {
BVMSTATE="DEPLOY"
}
2018-10-18 23:18:12 -03:00
# Custom state function for the developer to play with
function cusfun(){
BVMSTATE="CUSFUN"
2018-10-26 19:26:07 -03:00
#log("cusfun: yay!!!")
#LOCAL_TARGET = math.vec2.new(5 ,0 )
#local_set_point = math.vec2.new(LOCAL_TARGET.x - pose.position.x ,LOCAL_TARGET.y - pose.position.y ) # has to move 5 meters in x from the home location
#if(math.vec2.length(local_set_point) > GOTODIST_TOL){
# local_set_point = LimitSpeed(local_set_point, 1.0)
# goto_abs(local_set_point.x, local_set_point.y, 0.0, 0.0)
#}
#else{
# log("TARGET REACHED")
#}
initialPoint = 0
# Get waypoint list
if (id == 1) {
waypoints = {
.0 = math.vec2.new(-5.0, -5.0),
.1 = math.vec2.new(5.0, 5.0)
}
} else if (id == 2 ) {
waypoints = {
.0 = math.vec2.new(5.0, 5.0),
.1 = math.vec2.new(-5.0, -5.0)
}
}
# Current waypoint
target_point = waypoints[point]
# Get drone position and transform to global frame - depends on lauch file
offset_x = 0.0
offset_y = 0.0
if (id == 1) {
offset_x = 5.0
offset_y = 5.0
} else if (id == 2 ) {
offset_x = -5.0
offset_y = -5.0
}
pos_x = pose.position.x + offset_x;
pos_y = pose.position.y + offset_y;
# Get a vector pointing to target and target distance
vector_to_target = math.vec2.sub(target_point, math.vec2.new(pos_x, pos_y))
distance_to_target = math.vec2.length(vector_to_target)
# Run LCA and increment waypoint
if(distance_to_target > 0.2){
2018-10-26 19:32:11 -03:00
vector_to_target = LCA(vector_to_target)
2018-10-26 19:26:07 -03:00
vector_to_target = LimitSpeed(vector_to_target, 0.5)
goto_abs(vector_to_target.x, vector_to_target.y, 0.0, 0.0)
} else {
if(point < size(waypoints) - 1){
point = point + 1
} else {
point = 0
}
}
2018-10-18 23:18:12 -03:00
}