diff options
author | Jakob Odersky <jakob@odersky.com> | 2016-02-24 20:29:30 -0800 |
---|---|---|
committer | Jakob Odersky <jakob@odersky.com> | 2016-02-24 20:31:14 -0800 |
commit | a41de68066007852d7d3dbf019d75b4caf7463ad (patch) | |
tree | b4446408291c9f179e1c270a561523023ac6a105 /mavigator-uav | |
parent | 245faaf1e2ff4d0fbda292dbb35f4b49426d4380 (diff) | |
download | mavigator-a41de68066007852d7d3dbf019d75b4caf7463ad.tar.gz mavigator-a41de68066007852d7d3dbf019d75b4caf7463ad.tar.bz2 mavigator-a41de68066007852d7d3dbf019d75b4caf7463ad.zip |
Major refactorings
Diffstat (limited to 'mavigator-uav')
-rw-r--r-- | mavigator-uav/src/main/resources/reference.conf (renamed from mavigator-uav/src/main/resources/application.conf) | 6 | ||||
-rw-r--r-- | mavigator-uav/src/main/scala/mavigator/uav/MavlinkUtil.scala | 6 | ||||
-rw-r--r-- | mavigator-uav/src/main/scala/mavigator/uav/Uav.scala | 18 | ||||
-rw-r--r-- | mavigator-uav/src/main/scala/mavigator/uav/mock/MockConnection.scala | 36 |
4 files changed, 37 insertions, 29 deletions
diff --git a/mavigator-uav/src/main/resources/application.conf b/mavigator-uav/src/main/resources/reference.conf index f468111..3b43d37 100644 --- a/mavigator-uav/src/main/resources/application.conf +++ b/mavigator-uav/src/main/resources/reference.conf @@ -31,7 +31,9 @@ mavigator.uav { mock { # Mavlink system ID of the simulated UAV remote_system_id = 42 - # Delay between simulated messages - frequency = 50 + # Mavlink component ID of the simulated UAV + remote_system_id = 0 + # Divide simulated message frequency + prescaler = 1 } }
\ No newline at end of file diff --git a/mavigator-uav/src/main/scala/mavigator/uav/MavlinkUtil.scala b/mavigator-uav/src/main/scala/mavigator/uav/MavlinkUtil.scala index 3756dd6..0fb56b0 100644 --- a/mavigator-uav/src/main/scala/mavigator/uav/MavlinkUtil.scala +++ b/mavigator-uav/src/main/scala/mavigator/uav/MavlinkUtil.scala @@ -11,16 +11,16 @@ import akka.util.ByteString /** Provides utilities for actors representing a mavlink connection. */ trait MavlinkUtil { myself: Actor with ActorLogging => - + /** Mavlink system ID of this connection. */ val systemId: Byte /** Mavlink component ID of this connection. */ val componentId: Byte - + /** Assembler for creating packets originating from this connection. */ private lazy val assembler = new Assembler(systemId, componentId) - + /** Assembles a message into a bytestring representing a packet sent from this connection. */ protected def assemble(message: Message): ByteString = { val (messageId, payload) = Message.pack(message) diff --git a/mavigator-uav/src/main/scala/mavigator/uav/Uav.scala b/mavigator-uav/src/main/scala/mavigator/uav/Uav.scala index ed677ea..06a8f00 100644 --- a/mavigator-uav/src/main/scala/mavigator/uav/Uav.scala +++ b/mavigator-uav/src/main/scala/mavigator/uav/Uav.scala @@ -1,6 +1,7 @@ package mavigator package uav +import java.lang.IllegalArgumentException import mock._ import akka._ import akka.actor._ @@ -10,6 +11,23 @@ import akka.stream.scaladsl._ class Uav(system: ExtendedActorSystem) extends Extension { private lazy val config = system.settings.config.getConfig("mavigator.uav") + private lazy val tpe = config.getString("type") + private lazy val componentId = config.getInt("componentId").toByte + private lazy val heartbeat = config.getInt("heartbeat") + private lazy val connection = config.getConfig(tpe) + + lazy val source = tpe match { + case "mock" => + new MockConnection( + connection.getInt("remote_system_id").toByte, + componentId, + connection.getDouble("prescaler") + ) + + case "serial" => ??? + + case _ => throw new IllegalArgumentException(s"Unsupported connection type: $tpe") + } def connect(): Flow[ByteString, ByteString, NotUsed] = { Flow.fromSinkAndSource( diff --git a/mavigator-uav/src/main/scala/mavigator/uav/mock/MockConnection.scala b/mavigator-uav/src/main/scala/mavigator/uav/mock/MockConnection.scala index c7bc8d4..58b4977 100644 --- a/mavigator-uav/src/main/scala/mavigator/uav/mock/MockConnection.scala +++ b/mavigator-uav/src/main/scala/mavigator/uav/mock/MockConnection.scala @@ -2,19 +2,16 @@ package mavigator package uav package mock -import org.mavlink.enums._ -import org.mavlink.messages.{Heartbeat, Message} -import akka.stream.scaladsl._ import scala.concurrent.duration._ -import scala.util.Random -import akka.stream._ + import akka.NotUsed +import akka.stream._ +import akka.stream.Attributes._ +import akka.stream.scaladsl._ import akka.util._ import org.mavlink._ -import Attributes._ - +import org.mavlink.messages.{Heartbeat, Message} -//case class Heartbeat(`type`: Byte, autopilot: Byte, baseMode: Byte, customMode: Int, systemStatus: Byte, mavlinkVersion: Byte) extends Message class MockConnection( remoteSystemId: Byte, @@ -23,12 +20,14 @@ class MockConnection( ) { import MockConnection._ + private lazy val assembler = new Assembler(remoteSystemId, remoteComponentId) + private def delayed(delaySeconds: Double)(message: RandomFlightPlan => Message): Flow[RandomFlightPlan, Message, NotUsed] = { val dt = delaySeconds / prescaler Flow[RandomFlightPlan].withAttributes(inputBuffer(1,1)).delay(dt.seconds).map(message) } - val messages: Source[Message, _] = streamFromPlan(new RandomFlightPlan)( + private val messages: Source[Message, NotUsed] = fromPlan(new RandomFlightPlan)( delayed(2)(_.heartbeat), delayed(0.2)(_.position), delayed(0.05)(_.attitude), @@ -36,31 +35,20 @@ class MockConnection( delayed(0.1)(_.distance) ) - - private lazy val assembler = new Assembler(remoteSystemId, remoteComponentId) - - /** Assembles a message into a bytestring representing a packet sent from this connection. */ - def assemble(message: Message): ByteString = { + val data: Source[ByteString, NotUsed] = messages.map{ message => val (messageId, payload) = Message.pack(message) - val packet: Packet = assembler.assemble(messageId, payload) + val packet = assembler.assemble(messageId, payload) ByteString(packet.toArray) } - val data = messages.map{ msg => - if (msg.isInstanceOf[Heartbeat]){println(msg)} - assemble(msg) - } - } object MockConnection { - final val ClockTick: FiniteDuration = 0.01.seconds - - private def streamFromPlan(plan: RandomFlightPlan)(messages: Flow[RandomFlightPlan, Message, _]*): Source[Message, NotUsed] = { + final val ClockTick: FiniteDuration = 0.02.seconds + private def fromPlan(plan: RandomFlightPlan)(messages: Flow[RandomFlightPlan, Message, _]*): Source[Message, NotUsed] = { import GraphDSL.Implicits._ - Source.fromGraph(GraphDSL.create() { implicit b => val clock = Source.tick(ClockTick, ClockTick, plan) map { plan => |