diff options
author | Jakob Odersky <jodersky@gmail.com> | 2015-03-26 12:24:55 +0100 |
---|---|---|
committer | Jakob Odersky <jodersky@gmail.com> | 2015-03-26 12:24:55 +0100 |
commit | b903d29793d5ac9a1379460e8700abc614e8d48a (patch) | |
tree | 624d5edcd20025636a14b7d9055d8df537a26871 | |
parent | aeb4c6a32326ef6bd7f6bf77cd4bb00d2fabac6d (diff) | |
parent | 51c998315fccb11aa56e22e66f32189a5991ba64 (diff) | |
download | mavigator-b903d29793d5ac9a1379460e8700abc614e8d48a.tar.gz mavigator-b903d29793d5ac9a1379460e8700abc614e8d48a.tar.bz2 mavigator-b903d29793d5ac9a1379460e8700abc614e8d48a.zip |
Merge branch 'chernetsov-wip/mavlink-common' into wip/mavlink-common
-rw-r--r-- | .gitignore | 1 | ||||
-rw-r--r-- | vfd-dashboard/src/main/scala/vfd/dashboard/MavlinkSocket.scala | 24 | ||||
-rw-r--r-- | vfd-dashboard/src/main/scala/vfd/dashboard/ui/panels/Primary.scala | 8 | ||||
-rw-r--r-- | vfd-index/src/main/scala/vfd/index/Main.scala | 17 | ||||
-rw-r--r-- | vfd-uav/src/main/scala/vfd/uav/Connection.scala | 2 |
5 files changed, 30 insertions, 22 deletions
@@ -26,4 +26,5 @@ project/plugins/project/ *.class *.log *~ +/.idea diff --git a/vfd-dashboard/src/main/scala/vfd/dashboard/MavlinkSocket.scala b/vfd-dashboard/src/main/scala/vfd/dashboard/MavlinkSocket.scala index dff3598..9476794 100644 --- a/vfd-dashboard/src/main/scala/vfd/dashboard/MavlinkSocket.scala +++ b/vfd-dashboard/src/main/scala/vfd/dashboard/MavlinkSocket.scala @@ -29,25 +29,21 @@ class MavlinkSocket(url: String, remoteSystemId: Int) { } private val parser = new Parser( - pckt => { - pckt match { - case Packet(seq, `remoteSystemId`, compId, msgId, payload) => - packet() = pckt - stats.packets() += 1 - case _ => - stats.wrongIds() += 1 - } + { + case pckt@Packet(seq, `remoteSystemId`, compId, msgId, payload) => + packet() = pckt + stats.packets() += 1 + case _ => + stats.wrongIds() += 1 }, - err => { - err match { - case CrcError => stats.crcErrors() += 1 - case OverflowError => stats.overflows() += 1 - } + { + case CrcError => stats.crcErrors() += 1 + case OverflowError => stats.overflows() += 1 }) private val connection = new dom.WebSocket(url) - connection.binaryType = "arraybuffer"; + connection.binaryType = "arraybuffer" connection.onopen = (e: dom.Event) => { stats.open() = true } diff --git a/vfd-dashboard/src/main/scala/vfd/dashboard/ui/panels/Primary.scala b/vfd-dashboard/src/main/scala/vfd/dashboard/ui/panels/Primary.scala index 47c9c97..b85e657 100644 --- a/vfd-dashboard/src/main/scala/vfd/dashboard/ui/panels/Primary.scala +++ b/vfd-dashboard/src/main/scala/vfd/dashboard/ui/panels/Primary.scala @@ -1,5 +1,6 @@ package vfd.dashboard.ui.panels +import org.mavlink.messages.{VfrHud, Attitude, GlobalPositionInt} import org.scalajs.dom.html import rx.core.Obs @@ -26,7 +27,12 @@ object Primary { Obs(socket.message, skipInitial = true) { socket.message() match { - //TODO match message and update UI + case a: Attitude => +// compass.update(a.yaw / Math.PI * 360) +// horizon.update(a.pitch, a.roll) + case vh: VfrHud => +// altimeter.update(vh.alt) +// compass.update(vh.heading / Math.PI * 360) case _ => () } } diff --git a/vfd-index/src/main/scala/vfd/index/Main.scala b/vfd-index/src/main/scala/vfd/index/Main.scala index ce66f14..779b682 100644 --- a/vfd-index/src/main/scala/vfd/index/Main.scala +++ b/vfd-index/src/main/scala/vfd/index/Main.scala @@ -21,18 +21,23 @@ object Main { val active = Var(Set.empty[ActiveVehicle]) val parser = new Parser( - packet => Message.unpack(packet.messageId, packet.payload) match { - case hb: Heartbeat => - active() += ActiveVehicle.fromHeartbeat(packet.messageId, hb) - case _ => () - }) + packet => { + val m: Message = Message.unpack(packet.messageId, packet.payload) + println(m) + m match { + case hb: Heartbeat => + active() += ActiveVehicle.fromHeartbeat(packet.systemId, hb) + case _ => () + } + } + ) @JSExport def main(root: html.Element, baseAssets: String, args: js.Dictionary[String]): Unit = { val connection = new dom.WebSocket(args("socketUrl")) - connection.binaryType = "arraybuffer"; + connection.binaryType = "arraybuffer" connection.onmessage = (e: dom.MessageEvent) => { val buffer = e.data.asInstanceOf[js.typedarray.ArrayBuffer] val view = new js.typedarray.DataView(buffer) diff --git a/vfd-uav/src/main/scala/vfd/uav/Connection.scala b/vfd-uav/src/main/scala/vfd/uav/Connection.scala index b99aadd..223a787 100644 --- a/vfd-uav/src/main/scala/vfd/uav/Connection.scala +++ b/vfd-uav/src/main/scala/vfd/uav/Connection.scala @@ -35,7 +35,7 @@ trait Connection { myself: Actor => /** Adds a client to the client list and acquires a deathwatch. */ protected def register(client: ActorRef) = { - _clients += client; + _clients += client myself.context.watch(client) } |