Screaming Mouse
Published © GPL3+

Containment Sentinel: Fight Fires with Flyers #1

Containment Sentinel increases efficiency of human resources through real time automated multi-spectral firebreak monitoring and tracking.

IntermediateFull instructions provided20 hours1,926

Things used in this project

Hardware components

Raspberry Pi 3 Model B
Raspberry Pi 3 Model B
×1
Storm32 FPV 3 Axis Brushless Gimbal Gopro Stabilizer+Motors & Controller X-
×1
RDDRONE-FMUK66
NXP RDDRONE-FMUK66
×1
KIT-HGDRONEK66
NXP KIT-HGDRONEK66
×1
Camera Module
Raspberry Pi Camera Module
×1
Lepton 3.5 Thermal Image Sensor 160HX120V
×1
PURETHERMAL-2
×1

Software apps and online services

Raspbian
Raspberry Pi Raspbian
OpenCV
OpenCV
QGroundControl
PX4 QGroundControl
Google Maps
Google Maps

Story

Read more

Schematics

Flame_small

flame image for Display

Hotspot log file

log file to demonstrate Display_hotspots_submission.html

Code

Containment_Sentinel_executive.py

Python
Executive control Loop

To use Containment_Sentinel_executive.py
OpenCV and executive file operate on Python 2.7
The PiCamera shall be connected to the RPi native video port.
The Purthermal 2 Carrier board with a Lepton 3.5 shall be connected to a USB port.
The STorM32BGC 3 Axis stabilizer gimbal shall be connected to a USB port.
RPi listens to Mavlink via the USART on header pins 8 & 10.
To autostart on a Raspberry Pi Add Containment Sentinel_executive in /etc/xdg/autostart/arandr-autostart.desktop

[Desktop Entry]
Type=Application
Name=Containment_Sentinel
Exec=Python /home/Containment_Sentinel_executive.py
#!/usr/bin/env python
# -*- coding: utf-8 -*-
#
#  t
#  
#  Copyright 2020  Martin Lee 
#  
#  This program is free software; you can redistribute it and/or modify
#  it under the terms of the GNU General Public License as published by
#  the Free Software Foundation; either version 2 of the License, or
#  (at your option) any later version.
#  
#  This program is distributed in the hope that it will be useful,
#  but WITHOUT ANY WARRANTY; without even the implied warranty of
#  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
#  GNU General Public License for more details.
#  
#  pymavlink is GPLV3 license. https://github.com/mavlink/mavlink
#  OpenCV:
#  Copyright (C) 2000-2019, Intel Corporation, all rights reserved.
#  Copyright (C) 2009-2011, Willow Garage Inc., all rights reserved.
#  Copyright (C) 2009-2016, NVIDIA Corporation, all rights reserved.
#  Copyright (C) 2010-2013, Advanced Micro Devices, Inc., all rights reserved.
#  Copyright (C) 2015-2016, OpenCV Foundation, all rights reserved.
#  Copyright (C) 2015-2016, Itseez Inc., all rights reserved.
#  Third party copyrights are property of their respective owners.
#  
#picam has a 45 deg FOV
import sys
from pymavlink import mavutil
from helper_func import hot_spot
from helper_func import get_distance_metres
import csv
from storm_ctrl import setAngle
import serial
#import storm_ctrl

  # import the necessary packages
from picamera import PiCamera
import picamera
import picamera.array


import time
import cv2
import numpy as np;
import threading

from PIL import Image
import datetime
from Function_Lib_2 import read_thermal_camera
from Function_Lib_2 import find_thermal_src
from Function_Lib_2 import analyze_hotspots
from Function_Lib_2 import annotate_image
from Function_Lib_2 import save_image
from Function_Lib_2 import value_min_max
from Function_Lib_2 import update_camera
font = cv2.FONT_HERSHEY_SIMPLEX

lat = 0.0
lon = 0.0
hdg = 0.0
rel_alt = 0.0
targ_ang = 245.0 #90.0
encroach = 0
gps_time = 0
CH09 = 0.0 # left shoulder wheel
CH10 = 0.0 # right shoulder wheel
gimbal_pitch = 45.0
gimbal_roll = 0.0
gimbal_yaw = 0.0
yaw_skip = 0.0
pitch_skip = 0.0
rel_alt = 0

point_list = [] #def __init__(self, time, lat, lon, en_type, size, image_taken):

cur_time = datetime.datetime.now()
most_rec_encroach = hot_spot(cur_time, lat, lon, 1, 2, False)
point_list.append( hot_spot(cur_time, lat, lon, 1, 2, False))

print(len(point_list))
print(point_list.pop().time)
print(len(point_list))
    


def mavlink_listen ():
    global lat
    global lon
    global hdg
    global rel_alt
    global CH09
    global CH10
    global gimbal_pitch
    global gimbal_roll
    global gimbal_yaw
    scale = 0.005
    prev_pitch = 45.0
    prev_roll = 0.0
    prev_yaw = 0.0
    yaw_skip = time.time()
    pitch_skip = time.time()
    #time.sleet(2.0)
    master = mavutil.mavlink_connection(
        '/dev/ttyAMA0', 
        baud=57600)
        
        
        
    # serial to STorM32
    # use: 'dmesg | grep tty' to view avalible serial ports
    ser = serial.Serial(
       port='/dev/ttyACM0', # was ttyS0
       baudrate = 115200,
       parity=serial.PARITY_NONE,
       stopbits=serial.STOPBITS_ONE,
       bytesize=serial.EIGHTBITS,
       timeout=1
    )
    #lat = 0.0
    #lon = 0.0
    time.sleep(0.5) #0.5
    setAngle(45.0, 0.0, 0.0, ser) #pitch, roll, yaw, serial channel
    
    try:
        #master.mav.MAV_CMD_SET_MESSAGE_INTERVAL(2,0,0) # display time
        #master.mav.MAV_CMD_SET_MESSAGE_INTERVAL(340,0,0)# Time command
        print ('time command success')
    except:
        print('MAV_CMD fail')
    
    while True:
        
        msg = master.recv_match()
        #lat, lon, hdg, rel_alt, CH09, CH10 = receive_MavLink(msg, lat, lon, hdg, rel_alt, CH09, CH10)
        
         
        if not msg:
        #try:
            #master.mav.MAV_CMD_SET_MESSAGE_INTERVAL(340,0,0)
        #except:
            continue
        if msg.get_type() == 'GLOBAL_POSITION_INT': #33
            #print("\n\n*****Got message: %s*****" % msg.get_type())
            #print("Message: %s" % msg)
            #print("\nAs dictionary: %s" % msg.to_dict())
            # Armed = MAV_STATE_STANDBY (4), Disarmed = MAV_STATE_ACTIVE (3)
            #print("\nSystem status: %s" % msg.system_status)
            #print(msg.lat)
            #print(msg)
            lat = msg.lat / 1e7 #10000000.0
            #print(lat)
            lon = msg.lon / 1e7 #10000000.0
            #print(lon)
            hdg = msg.hdg /100.0
            #print(hdg)
            rel_alt = msg.relative_alt # in millimeters above ground or home location
            #print(rel_alt)
            
        elif msg.get_type() == 'RC_CHANNELS': ##65
            #print("\n\n*****Got message: %s*****" % msg.get_type())
            #print("Message: %s" % msg)
            #print("\nAs dictionary: %s" % msg.to_dict())
            CH09 = float(msg.chan9_raw)
            #print('CH09', CH09) #1033 to 2000, center is 1514 Lower value is CCW
            CH10 = float(msg.chan10_raw)
            #print('CH10: ', CH10) #1033 to 2000, center is 1514 Lower value is CW
            
        elif msg.get_type() == 'SYSTEM_TIME': #2
            #print("\n\n*****Got message: %s*****" % msg.get_type())
            #print("Message: %s" % msg)
            got_time = True
        elif msg.get_type() == 'UTM_GLOBAL_POSITION': #340 #UTM_GLOBAL_POSITION
            #pass
            print("\n\n*****Got message: %s*****" % msg.get_type())
            #print("Message: %s" % msg)
        
    
        gimbal_yaw, yaw_skip, gimbal_pitch, pitch_skip = update_camera(CH09, CH10, gimbal_yaw, yaw_skip, gimbal_pitch, pitch_skip, scale)
        
        if gimbal_pitch != prev_pitch or gimbal_yaw != prev_yaw:
            prev_pitch = gimbal_pitch
            prev_yaw = gimbal_yaw
            setAngle(gimbal_pitch, 0.0, gimbal_yaw, ser) #pitch, roll, yaw, serial channel
        

        

    
    
        

def detect_blobs():
    global encroach
    wpos = 0
    captured = False
    global gimbal_pitch
    global gimbal_roll
    global gimbal_yaw
    global CH09
    global CH10
    global rel_alt
    save_folder = "/home/pi/fire_records/"
    scale = 0.1
    last_capture_time = datetime.datetime.now().second
    #color_image = (640, 480, 3)
    
    # Setup SimpleBlobDetector parameters.
    params = cv2.SimpleBlobDetector_Params()
 
    # Change thresholds
    params.minThreshold = 0
    params.maxThreshold = 100
    
    # Filter by Area.
    params.filterByArea = True
    params.minArea = 100
    params.maxArea = 9000
    
    
    # Set up the detector with default parameters.
    #detector = cv2.SimpleBlobDetector(params)
    # Create a detector with the parameters
    ver = (cv2.__version__).split('.')
    if int(ver[0]) < 3 :
        detector = cv2.SimpleBlobDetector(params)
    else : 
        detector = cv2.SimpleBlobDetector_create(params)
    
    
     
    # initialize the Pi camera and grab a reference to the raw camera capture
    camera = PiCamera() #PiCam is typically logical 0
    camera.exposure_mode = 'auto'
    #sleep(5)
    #camera.awb_mode = 'auto'
    camera.resolution = (640, 480)
    camera.framerate = 10 #32
    camera.start_preview()
    print(camera.exposure_speed)
    #camera.shutter_speed = 7000 #1000
    
    #color_image = 
    # allow the camera to warmup
    time.sleep(0.1)
    #img = cv2.imread('/home/pi/learn_camera/image_2.jpg',0)
    
    #find and configure the thermal array
    thermal_addr = find_thermal_src()
    print("find_thermal_scr returned: ", thermal_addr)
    cap = cv2.VideoCapture(thermal_addr) #1 is the logical number for first UVC source PureThermal2. The RPi camera is typically 0
    
    time.sleep(1.5)
   
    
    while True:
        
        camera.exposure_mode = 'auto'
        ret, frame = cap.read()
        image, image_2, thermal_pass_though = read_thermal_camera(frame)
        
        #thresh1 = image #= frame.array
        ret,thresh1 = cv2.threshold(image,220,255,cv2.THRESH_BINARY)

        #invert image
        thresh1 = cv2.bitwise_not(thresh1)
        
        # Detect blobs.
        keypoints = detector.detect(thresh1)
        #print keypoints
        #print len(keypoints)
        
        #log encroacments if they are in the correct spot
        encroach = analyze_hotspots(keypoints, point_list, wpos, datetime, lat, lon, encroach, save_folder+"img/", rel_alt)
        
        image_with_keypoints, wpos = annotate_image(image_2, keypoints, wpos, hdg, targ_ang, font)
        
        if encroach > 0:
            encroach = 0
            #store encroachment image
            save_image(image_with_keypoints,"infrared", datetime.datetime.now(),save_folder+"img/")
            save_image(thermal_pass_though,"pass_through",datetime.datetime.now(),save_folder+"img/")
        
            #print("datetime seconds delta",datetime.datetime.now().second - last_capture_time)
            if abs(datetime.datetime.now().second - last_capture_time) > 10:
                last_capture_time = datetime.datetime.now().second
                
                cv2.namedWindow('frame_color', cv2.WINDOW_NORMAL)
                with picamera.array.PiRGBArray(camera) as stream:
                    camera.capture(stream, format='bgr')
                    # At this point the image is available as stream.array
                    image_color = stream.array
                    cv2.resizeWindow('frame_color', 640,480)
                    cv2.imshow('frame_color', image_color)
                save_image(image_color,"Area_image", datetime.datetime.now(),save_folder+"img/")
                
        # show the frame
        
        cv2.imshow("Frame2", image_with_keypoints)
        cv2.imshow("Frame", thresh1)
        key = cv2.waitKey(1) & 0xFF
     
     
        #if the `q` key was pressed, break from the loop
        if key == ord("q"):
            break
    
                

t1 = threading.Thread(target=mavlink_listen, args=())
t2 = threading.Thread(target=detect_blobs, args=())


t1.start()
t2.start()

Function_Lib_2.py

Python
Helper functions for Containment_Sentinel_executive.py
#  Copyright 2020  Martin Lee 
#  
#  This program is free software; you can redistribute it and/or modify
#  it under the terms of the GNU General Public License as published by
#  the Free Software Foundation; either version 2 of the License, or
#  (at your option) any later version.
#  
#  This program is distributed in the hope that it will be useful,
#  but WITHOUT ANY WARRANTY; without even the implied warranty of
#  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
#  GNU General Public License for more details.
#  OpenCV:
#  Copyright (C) 2000-2019, Intel Corporation, all rights reserved.
#  Copyright (C) 2009-2011, Willow Garage Inc., all rights reserved.
#  Copyright (C) 2009-2016, NVIDIA Corporation, all rights reserved.
#  Copyright (C) 2010-2013, Advanced Micro Devices, Inc., all rights reserved.
#  Copyright (C) 2015-2016, OpenCV Foundation, all rights reserved.
#  Copyright (C) 2015-2016, Itseez Inc., all rights reserved.
#  Third party copyrights are property of their respective owners.
### Functions for hotspot detector.
import cv2
import numpy as np;
import os #added for find thermal
import v4l2capture #added for find thermal
from helper_func import hot_spot # added for analyze hot spots
from pymavlink import mavutil
import csv
import time

def read_thermal_camera(image_frame):
    
    #***next lines are copies from thermal open CV example***
    #ret, frame = cap.read()
    gray = cv2.cvtColor(image_frame, cv2.COLOR_BGR2GRAY)
    #*************
    gray = cv2.resize(gray, (800,600),interpolation = cv2.INTER_CUBIC)
    thermal_pass_through = gray
    img_avg = np.average(gray) / 2
    #gray = cv2.subtract(gray, np.array([img_avg]))

    image = gray
    image_2 = gray
    return image, image_2, thermal_pass_through


#!/usr/bin/python
#
# python-v4l2capture
#
# 2009, 2010 Fredrik Portstrom
#
# I, the copyright holder of this file, hereby release it into the
# public domain. This applies worldwide. In case this is not legally
# possible: I grant anyone the right to use this work for any
# purpose, without any conditions, unless such conditions are
# required by law.

def find_thermal_src():
    file_names = [x for x in os.listdir("/dev") if x.startswith("video")]
    file_names.sort()
    for file_name in file_names:
        path = "/dev/" + file_name
        print path
        try:
            video = v4l2capture.Video_device(path)
            driver, card, bus_info, capabilities = video.get_info()
            print "    driver:       %s\n    card:         %s" \
                "\n    bus info:     %s\n    capabilities: %s" % (
                    driver, card, bus_info, ", ".join(capabilities))

            if "PureThermal" == card[0:11]:
                print(card[0:11])
            
            if "PureThermal" in card and "readwrite" in capabilities and "streaming" in capabilities and "video_capture" in capabilities:
                print("Thermal camera is at: ", file_name[5:])
                thermal_addr = int(file_name[5:])
                print(thermal_addr)
                video.close()
                return thermal_addr
                break
            video.close()
        except IOError, e:
            print "    " + str(e)
        
    return thermal_addr
        

def analyze_hotspots(keypoints, point_list, wpos, datetime, lat, lon, encroach, save_folder, rel_alt):#,folder_loc):
    if len(keypoints) > 0:
        cur_time = datetime.datetime.now()

        print(encroach)
        print('encroach at: ', lat,', ', lon)


        for i in range(0, len(keypoints)):
            #print("x= ",keypoints[i].pt[0]," y= ",keypoints[i].pt[1], "Diameter= ", keypoints[i].size, "\n")
            print(i)
            #patrol pat shall be routed to keep the cold side on the left and the hot side on the right.
            #hot spots on the right are allowed.
            #hot spots on the left are flagged as encroachments.
            if (keypoints[i].pt[0] < wpos): # if hotspot is to the left
                encroach = encroach + 1
            ##add lockout for encroachments in previous field of view. or do we let multiple hits indicate spark longevity.
                point_list.append( hot_spot(cur_time, lat, lon, 1, keypoints[i].size, False))##
                most_rec_encroach = point_list[len(point_list)-1]
            #def __init__(self, time, lat, lon, en_type, size, image_taken):
            
        if len(point_list) > 10:
            print('file updated')
            filename = save_folder + "points_" + str(cur_time.year) + "_" + str(cur_time.month) + "_" + str(cur_time.day) + "_" + str(cur_time.hour) + "00.csv"
            fieldnames = ['lat', 'lon', 'size', 'date_time','en_type','image_taken', 'rel_alt']
            try:
                with open(filename) as csvfile: #check to see if file for this hour exists
                    csvfile.close()
                with open(filename, 'a') as csvfile:# If it does exist append encroachments
                    
                    writer = csv.DictWriter(csvfile, fieldnames=fieldnames)
                
                    
                    for i in range(len(point_list)):
                        att = point_list.pop(0)
                        writer.writerow({'lat': att.lat, 'lon': att.lon, 'size': att.size,
                        'date_time': att.time, 'en_type': att.en_type, 'image_taken': att.image_taken, 'rel_alt':rel_alt})
                        #print(att.time.year, att.size)
                        #hot spot is: def __init__(self, time, lat, lon, en_type, size, image_taken):
                        if len(point_list) < 1:
                            most_rec_encroach = att
                            print(att.time)
            except:
                with open(filename, 'w') as csvfile: # file didn't exist, so start a new one with a header
                    
                    writer = csv.DictWriter(csvfile, fieldnames=fieldnames)
                
                    writer.writeheader()
                    #writer.writerow({'lat': 46.2, 'lon': 117, 'seq':3})
                    for i in range(len(point_list)):
                        att = point_list.pop(0)
                        writer.writerow({'lat': att.lat, 'lon': att.lon, 'size': att.size,
                        'date_time': att.time, 'en_type': att.en_type, 'image_taken': att.image_taken, 'rel_alt': rel_alt})
                        #print(att.time.year, att.size)
                        #hot spot is: def __init__(self, time, lat, lon, en_type, size, image_taken):
                        if len(point_list) < 1:
                            most_rec_encroach = att
                            print(att.time)
        
    return encroach

def annotate_image(image_in, keypoints, wpos, hdg, targ_ang, font):
        
    # Draw detected blobs as red circles.
    # cv2.DRAW_MATCHES_FLAGS_DRAW_RICH_KEYPOINTS ensures the size of the circle corresponds to the size of blob
    image_with_keypoints = cv2.drawKeypoints(image_in, keypoints, np.array([]), (0,0,255), cv2.DRAW_MATCHES_FLAGS_DRAW_RICH_KEYPOINTS)
    cv2.drawKeypoints
    h, w, cha = image_with_keypoints.shape
    
    disp_ang = str(hdg)
    ang_dif = targ_ang - hdg #target - heading = ang_dif
    #fov = 45 deg
    pix_per_deg = w/45 #width divided by FOV
    wpos = w/2 #
    wpos = int(wpos)
    
    #cv2.line(image, start, end, color bgr, width)
    cv2.line(image_with_keypoints,(wpos,0),(wpos,h),(255,255,255),3)
    
    cv2.putText(image_with_keypoints, disp_ang,(wpos,30),font,1,(0,255,0),2,cv2.LINE_AA)
    return image_with_keypoints, wpos


def save_image(src_image, postfix, cur_time, save_folder):

    #print(cur_time)
    #filename = prefix + str(cur_time.minute) + "_"+ str(cur_time.second) + ".jpg"
    filename = str(cur_time.year) + "-" + str(cur_time.month) + "-" + str(cur_time.day) + "-" + str(cur_time.hour) + "-" + str(cur_time.minute) + "-"+ str(cur_time.second) + "_" + postfix + ".jpg"
    filename = save_folder + filename
    #print(filename)
    # Using cv2.imwrite() method 
    # Saving the image 
    cv2.imwrite(filename, src_image) 
    captured = True
        
    



def value_min_max (input_val, lower, upper):
    #print ('input_raw', input_val)
    input_val = max(input_val, lower) # ensure input is atleast as large as lower
    #print('in after max', input_val)
    input_val = min(input_val, upper) # ensure input is no larger than upper
    #print ('in after min', input_val)
    #seconds = time.time()
    #print("Seconds since epoch =", seconds)
    return input_val
    

def update_camera(yaw_input, pitch_input, yaw_current, yaw_skip, pitch_current, pitch_skip, scale):
    center = 1514 # 1.515mS
    deadband = 50
    #print('CH09: ', yaw_input)
    #print('CH10: ', pitch_input)
    #coherce inputs.
    if yaw_input < 100:
        yaw_input = center
    if pitch_input < 100:
        pitch_input = center
    yaw_input = value_min_max(yaw_input, 1033, 2000) # make sure input is atleast 1033 #1033 to 2000, center is 1514
    pitch_input = value_min_max(pitch_input, 1033, 2000)
    #apply if outside deadband.
    #print ("yaw_input: ", yaw_input)
    
    if abs(yaw_input - center) > deadband and (yaw_skip - time.time()) < -0.10 :
        yaw_skip = time.time()
        #print('yaw delta' , yaw_input-center)
        yaw_current = yaw_current - (yaw_input - center) * scale
        yaw_current = value_min_max(yaw_current, -180.0, 180.0)
        #print('yaw current: ', yaw_current)
    
    if abs(pitch_input - center) > deadband and (pitch_skip - time.time()) < -0.10:
        pitch_skip = time.time()
        pitch_current = pitch_current + (pitch_input - center) * scale
        pitch_current = value_min_max(pitch_current, -180.0, 180.0)
        #print('pitch_current: ', pitch_current)
        
        
    return yaw_current, yaw_skip, pitch_current, pitch_skip

Display_hotspots_submission.html

HTML
To use the Display_Hotspots_submission.html
Make sure the small_flame.png is in the same folder as the html file.
Obtain and insert your own Google Maps API key in the call back script location.
Replace the token: <YOUR_API_KEY> with your API key.

Launch the html file in a webbrowser.
Click the browse button.
Select the formatted hot_spot_example_1.csv
Click the process File button.
<!DOCTYPE html>
<html>

<head>
    <style>
        /* 
        Copyright 2020  Martin Lee 
        This program is distributed in the hope that it will be useful,
        but WITHOUT ANY WARRANTY; without even the implied warranty of
        MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
        Map display adapted from GOOGLE Maps API examples https://developers.google.com/maps/documentation/javascript/markers
        API keys may also be obtained from links on this site.
        'flame_small.png', //flame image must be in the same folder as the html
        */
        /* Always set the map height explicitly to define the size of the div
       * element that contains the map. */
        #map {
            height: 100%;
        }

        /* Optional: Makes the sample page fill the window. */
        html,
        body {
            height: 100%;
            margin: 0;
            padding: 0;
        }
    </style>
</head>

<body>
    <form onsubmit="return processFile();" action="#" name="myForm" id="aForm" method="POST">
        <input type="file" id="myFile" name="myFile"><br>
        <input type="submit" name="submitMe" value="Process File">
    </form>
    <section>
        <table id="myTable"></table>
    </section>
    <div id="map"></div>
    <script>
        
        var map;
        function initMap() {
            map = new google.maps.Map(document.getElementById('map'), {
                zoom: 2,
                //center: new google.maps.LatLng(2.8,-187.3),
                center: new google.maps.LatLng(47.7421062, -117.1868899), zoom: 16,
                mapTypeId: 'satellite'

                //mapTypeId: 'terrain'
            });

            // Create a <script> tag and set the USGS URL as the source.
            var script = document.createElement('script');
            // This example uses a local copy of the GeoJSON stored at
            // http://earthquake.usgs.gov/earthquakes/feed/v1.0/summary/2.5_week.geojsonp
            script.src = 'https://developers.google.com/maps/documentation/javascript/examples/json/earthquake_GeoJSONP.js';
            document.getElementsByTagName('head')[0].appendChild(script);
        }

        // Loop through the results array and place a marker for each
        // set of coordinates.
        window.eqfeed_callback = function (results) {
            //callback from google API refernce. remove if time permitts.
            var dummy_var = 5;
            //for (var i = 0; i < results.features.length; i++) {
            //var coords = results.features[i].geometry.coordinates;
            //var latLng = new google.maps.LatLng(coords[1], coords[0]);
            //var marker = new google.maps.Marker({
            //position: latLng,
            //map: map
            //});
            //}
        }
        function processFile() {
            var fileSize = 0;
            //var theFile = document.getElementById("myFile").files[0];
            //file://C:\Martin\geo-location\google_maps\coords.csv
            var theFile = document.getElementById("myFile").files[0];
            if (theFile) {
                var table = document.getElementById("myTable");
                var headerLine = "myFile";
                var myReader = new FileReader();
                myReader.onload = function (e) {
                    var content = myReader.result;
                    var lines = content.split("\r");
                    //alert(rowContent[lines.length]);
                    for (var count = 0; count < lines.length; count++) {
                        var row = document.createElement("tr");
                        var rowContent = lines[count].split(",");
                        var marker = new google.maps.Marker({
                            position: new google.maps.LatLng(rowContent[0], rowContent[1]),
                            icon: 'flame_small.png', //flame image must be in the same folder as the html
                            map: map
                        });
                        //alert(rowContent[lines.length]);
                        //alert(rowContent[0].length);
                        //The following conditional finds the highest and lowest of the supplied coordinates
                        if (0 ==count){
                            var dummy_var = 1;//do nothing
                        }
                        else if (1 == count) {
                            var lowest_lat = (rowContent[0]);
                            var highest_lat = (rowContent[0]);
                            var lowest_lon = (rowContent[1]);
                            var highest_lon = (rowContent[1]);
                            //alert(rowContent[0]);
                        } 
                        //else if (Number.isNaN(rowContent[0])){
                        else if (rowContent[0].length == 1){
                            //alert('empty row');

                        }
                        else {
                            lowest_lat = Math.min(lowest_lat, rowContent[0]);
                            highest_lat = Math.max(highest_lat, rowContent[0]);
                            lowest_lon = Math.min(lowest_lon, rowContent[1]);
                            highest_lon = Math.max(highest_lon, rowContent[1]);
                            //alert(lowest_lat);
                        }
                        //find center of displayed points
                        var map_center_lat = (highest_lat - lowest_lat) / 2 + lowest_lat; 
                        var map_center_lon = (highest_lon - lowest_lon) / 2 + lowest_lon;

                        for (var i = 0; i < rowContent.length; i++) {
                            if (count == 0) {
                                var cellElement = document.createElement("th");
                            } else {
                                var cellElement = document.createElement("td");
                                //var latLng = new google.maps.LatLng(coords[1], coords[0]);
                                //var latLng = (rowContent[0], rowContent[1]);
                                //parseInt(text, 10)
                                if (1 == count) {
                                    var lowest_lat = rowContent[0];
                                }
                                //var latLng = (parseInt(rowContent[0],10), parseInt(rowContent[1],10));
                                //alert(rowContent[0]);
                                new google.maps.LatLng(rowContent[0], rowContent[1])

                                //var marker = new google.maps.Marker({
                                //position: new google.maps.LatLng(rowContent[0], rowContent[1]),

                                //map: map
                                //});
                            }
                            var cellContent = document.createTextNode(rowContent[i]);
                            cellElement.appendChild(cellContent);
                            row.appendChild(cellElement);
                        }
                        //myTable.appendChild(row);
                    }
                    map.panTo(new google.maps.LatLng(map_center_lat, map_center_lon));
                }
                myReader.readAsText(theFile);
            }
            return false;
        }
    </script>
    <script async defer
        src="https://maps.googleapis.com/maps/api/js?key=<YOUR_API_KEY>&callback=initMap">
        </script>

</body>

</html>

Credits

Screaming Mouse

Screaming Mouse

1 project • 2 followers
Thanks to Amanda Lee and Fredrik Portstrom python-v4l2capture.

Comments