Skip to content

Instantly share code, notes, and snippets.

@rayjanwilson
Created May 15, 2015 20:46
Show Gist options
  • Select an option

  • Save rayjanwilson/fb90afc31e85f0cb48a0 to your computer and use it in GitHub Desktop.

Select an option

Save rayjanwilson/fb90afc31e85f0cb48a0 to your computer and use it in GitHub Desktop.
var MAVLink, MavParams, SerialPort, UavConnection, attachDataEventListener, config, connection, dataEventName, dgram, fs, gcsSysId, glob, hasConnected, heartbeatMonitor, isAttached, isConnected, lastError, lastHeartbeat, latestBinaryLog, log, lostConnection, moment, net, os, protocol, receivedBinaryLog, sendHeartbeatInterval, sentBinaryLog, started, timeSinceLastHeartbeat, uavComponentId, uavSysId, util, _;
UavConnection = function(configObject, protocolParser, logObject) {
"use strict";
var config, log, protocol;
_.bindAll(this, "closeConnection", "handleDataEvent", "changeState", "heartbeat", "invokeState", "start", "getState", "updateHeartbeat", "disconnected", "connecting", "connected", "write");
log = logObject;
config = configObject;
protocol = protocolParser;
this.state = "disconnected";
return this.startLogging();
};
SerialPort = require("serialport").SerialPort;
util = require("util");
dgram = require("dgram");
net = require("net");
_ = require("underscore");
fs = require("fs");
os = require("os");
glob = require("glob");
moment = require("moment");
MAVLink = require("mavlink_ardupilotmega_v1.0");
MavParams = require("./mavParam");
log = void 0;
receivedBinaryLog = void 0;
latestBinaryLog = void 0;
sentBinaryLog = void 0;
config = void 0;
started = false;
isConnected = false;
connection = undefined;
uavSysId = undefined;
uavComponentId = 1;
gcsSysId = undefined;
dataEventName = undefined;
protocol = void 0;
attachDataEventListener = true;
isAttached = false;
heartbeatMonitor = false;
lastHeartbeat = undefined;
timeSinceLastHeartbeat = undefined;
sendHeartbeatInterval = void 0;
hasConnected = false;
lostConnection = false;
lastError = void 0;
util.inherits(UavConnection, events.EventEmitter);
UavConnection.prototype.hasStarted = function() {
log.silly("Status of UavConnection.hasStarted: %s", started);
return started;
};
UavConnection.prototype.startLogging = function() {
var logTime;
logTime = moment().format("-MM-DD-YYYY-HH-mm-ss");
receivedBinaryLog = fs.createWriteStream(config.get("logging:root") + config.get("logging:receivedBinary") + logTime);
receivedBinaryLog.on("error", function(err) {
return log.error("unable to log received binary mavlink stream: " + err);
});
latestBinaryLog = fs.createWriteStream(config.get("logging:root") + "latest");
sentBinaryLog = fs.createWriteStream(config.get("logging:root") + config.get("logging:sentBinary") + logTime);
return sentBinaryLog.on("error", function(err) {
return log.error("unable to log sent binary mavlink stream: " + err);
});
};
UavConnection.prototype.stopLogging = function() {
receivedBinaryLog.end();
latestBinaryLog.end();
return sentBinaryLog.end();
};
UavConnection.prototype.changeState = function(newState) {
this.state = newState;
this.emit(this.state);
log.verbose("[UavConnection] Changing state to [" + this.state + "]");
return this.invokeState(this.state);
};
UavConnection.prototype.heartbeat = function() {
timeSinceLastHeartbeat = Date.now() - lastHeartbeat;
this.emit(this.state);
this.emit("heartbeat");
this.invokeState(this.state);
return log.heartbeat("time since last heartbeat: %d", timeSinceLastHeartbeat);
};
UavConnection.prototype.getTimeSinceLastHeartbeat = function() {
return timeSinceLastHeartbeat;
};
UavConnection.prototype.invokeState = function() {
return this[this.state]();
};
UavConnection.prototype.start = function() {
if (true === started) {
log.warn("Asked to start connection manager, but connection already started, refused.");
return;
}
log.info("Starting connection manager...");
started = true;
return this.changeState("disconnected");
};
UavConnection.prototype.getState = function() {
return this.state;
};
UavConnection.prototype.updateHeartbeat = function() {
try {
log.heartbeat("Heartbeat updated: " + Date.now());
lastHeartbeat = Date.now();
if (false === isConnected) {
isConnected = true;
timeSinceLastHeartbeat = 0;
return this.changeState("connected");
}
} catch (e) {
console.log("***");
console.log(e.stack);
console.log(e);
return log.error("error when updating heartbeat: " + util.inspect(e));
}
};
UavConnection.prototype.sendHeartbeat = function() {
var heartbeatMessage;
heartbeatMessage = void 0;
if (!heartbeatMessage) {
heartbeatMessage = new mavlink.messages.heartbeat(mavlink.MAV_TYPE_GCS, mavlink.MAV_AUTOPILOT_INVALID, 0, 0, 0, 3);
}
log.heartbeat("Sending GCS heartbeat to UAV...");
return this.sendAsGcs(heartbeatMessage);
};
UavConnection.prototype.getUSBSerial = function() {
var usbSerialPath;
usbSerialPath = (os.platform() === "darwin" ? "/dev/cu.usbserial-*" : "/dev/ttyUSB*");
if (config.get("serial:device") === "auto") {
log.silly("[UavConnection] usb serial: auto-detecting");
return glob.sync(usbSerialPath)[0];
} else {
log.silly("[UavConnection] usb serial: reading from config file");
return config.get("serial:device");
}
};
UavConnection.prototype.disconnected = function() {
var serialDevice;
lastHeartbeat = undefined;
timeSinceLastHeartbeat = undefined;
isConnected = false;
clearInterval(heartbeatMonitor);
clearInterval(sendHeartbeatInterval);
heartbeatMonitor = setInterval(this.heartbeat, config.get("connection:updateIntervals:heartbeatMs"));
attachDataEventListener = true;
log.silly("[UavConnection] Trying to connect from disconnected state...");
try {
switch (config.get("connection:type")) {
case "serial":
dataEventName = "data";
serialDevice = this.getUSBSerial();
log.silly("[UavConnection] usb serial is using ", serialDevice);
connection = new SerialPort(serialDevice, {
baudrate: config.get("serial:baudrate"),
disconnectedCallback: _.bind(this.changeState, this, "disconnected")
});
connection.on("error", function(err) {
return log.error("error establishing serial connection: " + err);
});
connection.on("open", _.bind(this.changeState, this, "connecting"));
return connection.on("close", _.bind(this.changeState, this, "disconnected"));
case "udp":
connection = dgram.createSocket("udp4");
dataEventName = "message";
connection.on("listening", _.bind(this.changeState, this, "connecting"));
return connection.bind(config.get("udp:port"));
case "tcp":
dataEventName = "data";
connection = net.connect({
host: config.get("tcp:host"),
port: config.get("tcp:port")
}, _.bind(function() {
log.verbose("[UavConnection] TCP connection established on port " + config.get("tcp:port"));
return this.changeState("connecting");
}, this));
return connection.on("error", function(e) {
if (lastError !== e.code) {
log.error("[UavConnection] TCP connection error message: " + e);
}
lastError = e.code;
return lastError;
});
default:
return log.error("Connection type not understood (%s)", config.get("connection:type"));
}
} catch (e) {
return log.error("error", util.inspect(e));
}
};
UavConnection.prototype.connecting = function() {
var mavParam;
try {
isConnected = false;
log.silly("establishing MAVLink connection...", {
ifAttach: attachDataEventListener
});
if (true === attachDataEventListener && false === isAttached) {
isAttached = true;
log.silly("attaching data event listener & connection bindings in UavConnection");
protocol.file = connection;
protocol.once("HEARTBEAT", function(msg) {
uavSysId = msg.header.srcSystem;
uavComponentId = msg.header.srcComponent;
protocol.srcSystem = uavSysId;
protocol.srcComponent = uavComponentId;
return mavParam.get("SYSID_THISMAV").then(_.bind(function(sysid_thismav) {
if (sysid_thismav !== uavSysId) {
return log.warn("UAV parameter SYSID_THISMAV does not match heartbeat srcSystem! %d %d", sysid_thismav, uavSysId);
} else {
return log.debug("Confirmed, SYSID_THISMAV matches heartbeat.srcSystem OK");
}
}, this)).fail(function(e) {
return log.error(util.inspect(e));
});
});
protocol.on("HEARTBEAT", this.updateHeartbeat);
connection.on(dataEventName, this.handleDataEvent);
mavParam = new MavParams(protocol, log);
mavParam.get("SYSID_MYGCS").then(_.bind(function(sysid_mygcs) {
gcsSysId = sysid_mygcs;
log.debug("Got GCS sysid %d", sysid_mygcs);
if (gcsSysId !== config.get("identities:gcsId")) {
return log.error("GCS ID mismatch between UAV and local GCS.");
}
}, this)).fail(function(e) {
return log.error(util.inspect(e));
});
}
attachDataEventListener = false;
if (timeSinceLastHeartbeat > config.get("connection:timeout:hard")) {
log.warn("Hard loss of link, returning to Disconnected state in UavConnection");
attachDataEventListener = true;
protocol.removeListener("HEARTBEAT", this.updateHeartbeat);
connection.removeListener(dataEventName, this.handleDataEvent);
return this.closeConnection();
}
} catch (e) {
log.error(e);
throw e;
}
};
UavConnection.prototype.closeConnection = function() {
var callback;
log.debug("Closing connection in UavConnection");
callback = _.bind(function() {
return this.changeState("disconnected");
}, this);
switch (config.get("connection:type")) {
case "tcp":
connection.end();
return this.changeState("disconnected");
case "udp":
connection.close();
return this.changeState("disconnected");
case "serial":
return connection.close(callback);
default:
log.error("Unknown connection type attempted in UavConnection.closeConnection()");
return this.changeState("disconnected");
}
};
UavConnection.prototype.handleDataEvent = function(message) {
receivedBinaryLog.write(message);
latestBinaryLog.write(message);
return protocol.parseBuffer(message);
};
UavConnection.prototype.requestDataStream = _.once(function() {
var request;
request = new mavlink.messages.request_data_stream(uavSysId, uavComponentId, mavlink.MAV_DATA_STREAM_ALL, config.get("connection:updateIntervals:streamHz"), 1);
log.silly("Requesting data streams at interval %d...", config.get("connection:updateIntervals:streamHz"));
return protocol.send(request);
});
UavConnection.prototype.startSendingHeartbeats = _.once(function() {
return setInterval(_.bind(this.sendHeartbeat, this), config.get("connection:updateIntervals:sendHeartbeatMs"));
});
UavConnection.prototype.connected = function() {
this.requestDataStream();
sendHeartbeatInterval = this.startSendingHeartbeats();
if (true === lostConnection) {
log.info("Connection re-established from lost state.");
lostConnection = false;
this.emit("connection:regained");
}
if ((timeSinceLastHeartbeat > config.get("connection:timeout:soft") || true === _.isNaN(timeSinceLastHeartbeat)) && true === hasConnected) {
this.emit("connection:lost");
log.warn("Connection lost.");
lostConnection = true;
this.changeState("connecting");
}
hasConnected = true;
return hasConnected;
};
UavConnection.prototype.write = function(data) {
switch (config.get("connection:type")) {
case "tcp":
case "serial":
try {
sentBinaryLog.write(data);
return connection.write(data);
} catch (e) {
return log.error("Error in UavConnection: ", e);
}
}
};
UavConnection.prototype.sendAsGcs = function(message) {
var buf;
buf = new Buffer(message.pack(protocol.seq, config.get("identities:gcsId"), config.get("identities:gcsComponent")));
this.write(buf);
protocol.seq = (protocol.seq + 1) % 255;
protocol.total_packets_sent += 1;
return protocol.total_bytes_sent += buf.length;
};
exports.UavConnection = UavConnection;
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment