Refactoring. Developing composer

This commit is contained in:
Alexander Nozik 2023-10-25 22:31:36 +03:00
parent 7f71d0c9e9
commit 1619fdadf2
27 changed files with 388 additions and 76 deletions

View File

@ -13,7 +13,7 @@ val xodusVersion by extra("2.0.1")
allprojects { allprojects {
group = "space.kscience" group = "space.kscience"
version = "0.2.2-dev-3" version = "0.3.0-dev-1"
repositories{ repositories{
maven("https://maven.pkg.jetbrains.space/spc/p/sci/dev") maven("https://maven.pkg.jetbrains.space/spc/p/sci/dev")
} }

View File

@ -0,0 +1,20 @@
plugins {
id("space.kscience.gradle.mpp")
`maven-publish`
}
description = """
A low-code constructor foe composite devices simulation
""".trimIndent()
kscience{
jvm()
js()
dependencies {
api(projects.controlsCore)
}
}
readme{
maturity = space.kscience.gradle.Maturity.PROTOTYPE
}

View File

@ -0,0 +1,51 @@
package center.sciprog.controls.devices.misc
import kotlinx.coroutines.Job
import space.kscience.controls.api.Device
import space.kscience.controls.spec.DeviceBySpec
import space.kscience.controls.spec.DevicePropertySpec
import space.kscience.controls.spec.DeviceSpec
import space.kscience.controls.spec.doubleProperty
import space.kscience.dataforge.context.Context
import space.kscience.dataforge.meta.transformations.MetaConverter
/**
* A single axis drive
*/
public interface Drive : Device {
/**
* Get or set target value
*/
public var target: Double
/**
* Current position value
*/
public val position: Double
public companion object : DeviceSpec<Drive>() {
public val target: DevicePropertySpec<Drive, Double> by property(MetaConverter.double, Drive::target)
public val position: DevicePropertySpec<Drive, Double> by doubleProperty { position }
}
}
/**
* Virtual [Drive] with speed limit
*/
public class VirtualDrive(
context: Context,
value: Double,
private val speed: Double,
) : DeviceBySpec<Drive>(Drive, context), Drive {
private var moveJob: Job? = null
override var position: Double = value
private set
override var target: Double = value
}

View File

@ -0,0 +1,31 @@
package center.sciprog.controls.devices.misc
import space.kscience.controls.api.Device
import space.kscience.controls.spec.DeviceBySpec
import space.kscience.controls.spec.DevicePropertySpec
import space.kscience.controls.spec.DeviceSpec
import space.kscience.controls.spec.booleanProperty
import space.kscience.dataforge.context.Context
/**
* A limit switch device
*/
public interface LimitSwitch : Device {
public val locked: Boolean
public companion object : DeviceSpec<LimitSwitch>() {
public val locked: DevicePropertySpec<LimitSwitch, Boolean> by booleanProperty { locked }
}
}
/**
* Virtual [LimitSwitch]
*/
public class VirtualLimitSwitch(
context: Context,
private val lockedFunction: () -> Boolean,
) : DeviceBySpec<LimitSwitch>(LimitSwitch, context), LimitSwitch {
override val locked: Boolean get() = lockedFunction()
}

View File

@ -0,0 +1,146 @@
package center.sciprog.controls.devices.misc
import kotlinx.coroutines.Job
import kotlinx.coroutines.delay
import kotlinx.coroutines.isActive
import kotlinx.coroutines.launch
import kotlinx.coroutines.sync.Mutex
import kotlinx.coroutines.sync.withLock
import kotlinx.datetime.Clock
import kotlinx.datetime.Instant
import space.kscience.controls.api.Device
import space.kscience.controls.spec.DeviceBySpec
import space.kscience.controls.spec.DeviceSpec
import space.kscience.controls.spec.doubleProperty
import space.kscience.dataforge.context.Context
import space.kscience.dataforge.context.Factory
import space.kscience.dataforge.meta.Meta
import space.kscience.dataforge.meta.double
import space.kscience.dataforge.meta.get
import space.kscience.dataforge.meta.transformations.MetaConverter
import kotlin.math.pow
import kotlin.time.Duration
import kotlin.time.Duration.Companion.milliseconds
import kotlin.time.DurationUnit
interface PidRegulator : Device {
/**
* Proportional coefficient
*/
val kp: Double
/**
* Integral coefficient
*/
val ki: Double
/**
* Differential coefficient
*/
val kd: Double
/**
* The target value for PID
*/
var target: Double
/**
* Read current value
*/
suspend fun read(): Double
companion object : DeviceSpec<PidRegulator>() {
val target by property(MetaConverter.double, PidRegulator::target)
val value by doubleProperty { read() }
}
}
/**
*
*/
class VirtualPid(
context: Context,
override val kp: Double,
override val ki: Double,
override val kd: Double,
val mass: Double,
override var target: Double = 0.0,
private val dt: Duration = 0.5.milliseconds,
private val clock: Clock = Clock.System,
) : DeviceBySpec<PidRegulator>(PidRegulator, context), PidRegulator {
private val mutex = Mutex()
private var lastTime: Instant = clock.now()
private var lastValue: Double = target
private var value: Double = target
private var velocity: Double = 0.0
private var acceleration: Double = 0.0
private var integral: Double = 0.0
private var updateJob: Job? = null
override suspend fun onStart() {
updateJob = launch {
while (isActive) {
delay(dt)
mutex.withLock {
val realTime = clock.now()
val delta = target - value
val dtSeconds = (realTime - lastTime).toDouble(DurationUnit.SECONDS)
integral += delta * dtSeconds
val derivative = (value - lastValue) / dtSeconds
//set last time and value to new values
lastTime = realTime
lastValue = value
// compute new value based on velocity and acceleration from the previous step
value += velocity * dtSeconds + acceleration * dtSeconds.pow(2) / 2
// compute new velocity based on acceleration on the previous step
velocity += acceleration * dtSeconds
//compute force for the next step based on current values
acceleration = (kp * delta + ki * integral + kd * derivative) / mass
check(value.isFinite() && velocity.isFinite()) {
"Value $value is not finite"
}
}
}
}
}
override fun onStop() {
updateJob?.cancel()
super<PidRegulator>.stop()
}
override suspend fun read(): Double = value
suspend fun readVelocity(): Double = velocity
suspend fun readAcceleration(): Double = acceleration
suspend fun write(newTarget: Double) = mutex.withLock {
require(newTarget.isFinite()) { "Value $newTarget is not valid" }
target = newTarget
}
companion object : Factory<Device> {
override fun build(context: Context, meta: Meta) = VirtualPid(
context,
meta["kp"].double ?: error("Kp is not defined"),
meta["ki"].double ?: error("Ki is not defined"),
meta["kd"].double ?: error("Kd is not defined"),
meta["m"].double ?: error("Mass is not defined"),
)
}
}

View File

@ -20,8 +20,19 @@ import space.kscience.dataforge.names.Name
* A lifecycle state of a device * A lifecycle state of a device
*/ */
public enum class DeviceLifecycleState{ public enum class DeviceLifecycleState{
/**
* Device is initializing
*/
INIT, INIT,
/**
* The Device is initialized and running
*/
OPEN, OPEN,
/**
* The Device is closed
*/
CLOSED CLOSED
} }
@ -31,13 +42,14 @@ public enum class DeviceLifecycleState{
* When canceled, cancels all running processes. * When canceled, cancels all running processes.
*/ */
@Type(DEVICE_TARGET) @Type(DEVICE_TARGET)
public interface Device : AutoCloseable, ContextAware, CoroutineScope { public interface Device : ContextAware, CoroutineScope {
/** /**
* Initial configuration meta for the device * Initial configuration meta for the device
*/ */
public val meta: Meta get() = Meta.EMPTY public val meta: Meta get() = Meta.EMPTY
/** /**
* List of supported property descriptors * List of supported property descriptors
*/ */
@ -87,12 +99,12 @@ public interface Device : AutoCloseable, ContextAware, CoroutineScope {
/** /**
* Initialize the device. This function suspends until the device is finished initialization * Initialize the device. This function suspends until the device is finished initialization
*/ */
public suspend fun open(): Unit = Unit public suspend fun start(): Unit = Unit
/** /**
* Close and terminate the device. This function does not wait for the device to be closed. * Close and terminate the device. This function does not wait for the device to be closed.
*/ */
override fun close() { public fun stop() {
logger.info { "Device $this is closed" } logger.info { "Device $this is closed" }
cancel("The device is closed") cancel("The device is closed")
} }

View File

@ -25,7 +25,7 @@ public sealed class DeviceMessage {
public abstract val time: Instant? public abstract val time: Instant?
/** /**
* Update the source device name for composition. If the original name is null, resulting name is also null. * Update the source device name for composition. If the original name is null, the resulting name is also null.
*/ */
public abstract fun changeSource(block: (Name) -> Name): DeviceMessage public abstract fun changeSource(block: (Name) -> Name): DeviceMessage
@ -203,12 +203,12 @@ public data class EmptyDeviceMessage(
public data class DeviceLogMessage( public data class DeviceLogMessage(
val message: String, val message: String,
val data: Meta? = null, val data: Meta? = null,
override val sourceDevice: Name? = null, override val sourceDevice: Name = Name.EMPTY,
override val targetDevice: Name? = null, override val targetDevice: Name? = null,
override val comment: String? = null, override val comment: String? = null,
@EncodeDefault override val time: Instant? = Clock.System.now(), @EncodeDefault override val time: Instant? = Clock.System.now(),
) : DeviceMessage() { ) : DeviceMessage() {
override fun changeSource(block: (Name) -> Name): DeviceMessage = copy(sourceDevice = sourceDevice?.let(block)) override fun changeSource(block: (Name) -> Name): DeviceMessage = copy(sourceDevice = block(sourceDevice))
} }
/** /**
@ -220,7 +220,7 @@ public data class DeviceErrorMessage(
public val errorMessage: String?, public val errorMessage: String?,
public val errorType: String? = null, public val errorType: String? = null,
public val errorStackTrace: String? = null, public val errorStackTrace: String? = null,
override val sourceDevice: Name, override val sourceDevice: Name = Name.EMPTY,
override val targetDevice: Name? = null, override val targetDevice: Name? = null,
override val comment: String? = null, override val comment: String? = null,
@EncodeDefault override val time: Instant? = Clock.System.now(), @EncodeDefault override val time: Instant? = Clock.System.now(),

View File

@ -12,10 +12,10 @@ import space.kscience.dataforge.meta.descriptors.MetaDescriptorBuilder
@Serializable @Serializable
public class PropertyDescriptor( public class PropertyDescriptor(
public val name: String, public val name: String,
public var info: String? = null, public var description: String? = null,
public var metaDescriptor: MetaDescriptor = MetaDescriptor(), public var metaDescriptor: MetaDescriptor = MetaDescriptor(),
public var readable: Boolean = true, public var readable: Boolean = true,
public var writable: Boolean = false public var mutable: Boolean = false
) )
public fun PropertyDescriptor.metaDescriptor(block: MetaDescriptorBuilder.()->Unit){ public fun PropertyDescriptor.metaDescriptor(block: MetaDescriptorBuilder.()->Unit){

View File

@ -40,7 +40,7 @@ public class DeviceManager : AbstractPlugin(), DeviceHub {
public fun <D : Device> DeviceManager.install(name: String, device: D): D { public fun <D : Device> DeviceManager.install(name: String, device: D): D {
registerDevice(NameToken(name), device) registerDevice(NameToken(name), device)
device.launch { device.launch {
device.open() device.start()
} }
return device return device
} }

View File

@ -1,12 +1,9 @@
package space.kscience.controls.spec package space.kscience.controls.spec
import kotlinx.coroutines.CoroutineName import kotlinx.coroutines.*
import kotlinx.coroutines.Job
import kotlinx.coroutines.SupervisorJob
import kotlinx.coroutines.channels.BufferOverflow import kotlinx.coroutines.channels.BufferOverflow
import kotlinx.coroutines.flow.MutableSharedFlow import kotlinx.coroutines.flow.MutableSharedFlow
import kotlinx.coroutines.flow.SharedFlow import kotlinx.coroutines.flow.SharedFlow
import kotlinx.coroutines.newCoroutineContext
import kotlinx.coroutines.sync.Mutex import kotlinx.coroutines.sync.Mutex
import kotlinx.coroutines.sync.withLock import kotlinx.coroutines.sync.withLock
import space.kscience.controls.api.* import space.kscience.controls.api.*
@ -69,8 +66,28 @@ public abstract class DeviceBase<D : Device>(
override val actionDescriptors: Collection<ActionDescriptor> override val actionDescriptors: Collection<ActionDescriptor>
get() = actions.values.map { it.descriptor } get() = actions.values.map { it.descriptor }
private val sharedMessageFlow: MutableSharedFlow<DeviceMessage> = MutableSharedFlow(
replay = meta["message.buffer"].int ?: 1000,
onBufferOverflow = BufferOverflow.DROP_OLDEST
)
override val coroutineContext: CoroutineContext by lazy { override val coroutineContext: CoroutineContext by lazy {
context.newCoroutineContext(SupervisorJob(context.coroutineContext[Job]) + CoroutineName("Device $this")) context.newCoroutineContext(
SupervisorJob(context.coroutineContext[Job]) +
CoroutineName("Device $this") +
CoroutineExceptionHandler { _, throwable ->
launch {
sharedMessageFlow.emit(
DeviceErrorMessage(
errorMessage = throwable.message,
errorType = throwable::class.simpleName,
errorStackTrace = throwable.stackTraceToString()
)
)
}
}
)
} }
@ -79,11 +96,6 @@ public abstract class DeviceBase<D : Device>(
*/ */
private val logicalState: HashMap<String, Meta?> = HashMap() private val logicalState: HashMap<String, Meta?> = HashMap()
private val sharedMessageFlow: MutableSharedFlow<DeviceMessage> = MutableSharedFlow(
replay = meta["message.buffer"].int ?: 1000,
onBufferOverflow = BufferOverflow.DROP_OLDEST
)
public override val messageFlow: SharedFlow<DeviceMessage> get() = sharedMessageFlow public override val messageFlow: SharedFlow<DeviceMessage> get() = sharedMessageFlow
@Suppress("UNCHECKED_CAST") @Suppress("UNCHECKED_CAST")
@ -180,18 +192,30 @@ public abstract class DeviceBase<D : Device>(
override var lifecycleState: DeviceLifecycleState = DeviceLifecycleState.INIT override var lifecycleState: DeviceLifecycleState = DeviceLifecycleState.INIT
protected set protected set
@OptIn(DFExperimental::class) protected open suspend fun onStart() {
override suspend fun open() {
super.open()
lifecycleState = DeviceLifecycleState.OPEN
} }
@OptIn(DFExperimental::class) @OptIn(DFExperimental::class)
override fun close() { final override suspend fun start() {
lifecycleState = DeviceLifecycleState.CLOSED super.start()
super.close() lifecycleState = DeviceLifecycleState.INIT
onStart()
lifecycleState = DeviceLifecycleState.OPEN
} }
protected open fun onStop() {
}
@OptIn(DFExperimental::class)
final override fun stop() {
onStop()
lifecycleState = DeviceLifecycleState.CLOSED
super.stop()
}
abstract override fun toString(): String abstract override fun toString(): String
} }

View File

@ -16,15 +16,14 @@ public open class DeviceBySpec<D : Device>(
override val properties: Map<String, DevicePropertySpec<D, *>> get() = spec.properties override val properties: Map<String, DevicePropertySpec<D, *>> get() = spec.properties
override val actions: Map<String, DeviceActionSpec<D, *, *>> get() = spec.actions override val actions: Map<String, DeviceActionSpec<D, *, *>> get() = spec.actions
override suspend fun open(): Unit = with(spec) { override suspend fun onStart(): Unit = with(spec) {
super.open()
self.onOpen() self.onOpen()
} }
override fun close(): Unit = with(spec) { override fun onStop(): Unit = with(spec){
self.onClose() self.onClose()
super.close()
} }
override fun toString(): String = "Device(spec=$spec)" override fun toString(): String = "Device(spec=$spec)"
} }

View File

@ -20,7 +20,7 @@ public annotation class InternalDeviceAPI
/** /**
* Specification for a device read-only property * Specification for a device read-only property
*/ */
public interface DevicePropertySpec<in D : Device, T> { public interface DevicePropertySpec<in D, T> {
/** /**
* Property descriptor * Property descriptor
*/ */
@ -53,7 +53,7 @@ public interface WritableDevicePropertySpec<in D : Device, T> : DevicePropertySp
} }
public interface DeviceActionSpec<in D : Device, I, O> { public interface DeviceActionSpec<in D, I, O> {
/** /**
* Action descriptor * Action descriptor
*/ */

View File

@ -53,7 +53,7 @@ public abstract class DeviceSpec<D : Device> {
val deviceProperty = object : DevicePropertySpec<D, T> { val deviceProperty = object : DevicePropertySpec<D, T> {
override val descriptor: PropertyDescriptor = PropertyDescriptor(property.name).apply { override val descriptor: PropertyDescriptor = PropertyDescriptor(property.name).apply {
//TODO add type from converter //TODO add type from converter
writable = true mutable = true
}.apply(descriptorBuilder) }.apply(descriptorBuilder)
override val converter: MetaConverter<T> = converter override val converter: MetaConverter<T> = converter
@ -78,7 +78,7 @@ public abstract class DeviceSpec<D : Device> {
override val descriptor: PropertyDescriptor = PropertyDescriptor(property.name).apply { override val descriptor: PropertyDescriptor = PropertyDescriptor(property.name).apply {
//TODO add the type from converter //TODO add the type from converter
writable = true mutable = true
}.apply(descriptorBuilder) }.apply(descriptorBuilder)
override val converter: MetaConverter<T> = converter override val converter: MetaConverter<T> = converter
@ -127,7 +127,7 @@ public abstract class DeviceSpec<D : Device> {
PropertyDelegateProvider { _: DeviceSpec<D>, property: KProperty<*> -> PropertyDelegateProvider { _: DeviceSpec<D>, property: KProperty<*> ->
val propertyName = name ?: property.name val propertyName = name ?: property.name
val deviceProperty = object : WritableDevicePropertySpec<D, T> { val deviceProperty = object : WritableDevicePropertySpec<D, T> {
override val descriptor: PropertyDescriptor = PropertyDescriptor(propertyName, writable = true) override val descriptor: PropertyDescriptor = PropertyDescriptor(propertyName, mutable = true)
.apply(descriptorBuilder) .apply(descriptorBuilder)
override val converter: MetaConverter<T> = converter override val converter: MetaConverter<T> = converter
@ -224,7 +224,7 @@ public fun <T, D : DeviceBase<D>> DeviceSpec<D>.logicalProperty(
val propertyName = name ?: property.name val propertyName = name ?: property.name
override val descriptor: PropertyDescriptor = PropertyDescriptor(propertyName).apply { override val descriptor: PropertyDescriptor = PropertyDescriptor(propertyName).apply {
//TODO add type from converter //TODO add type from converter
writable = true mutable = true
}.apply(descriptorBuilder) }.apply(descriptorBuilder)
override val converter: MetaConverter<T> = converter override val converter: MetaConverter<T> = converter

View File

@ -0,0 +1,36 @@
package space.kscience.controls.spec
import space.kscience.controls.api.Device
import space.kscience.controls.api.DeviceHub
import space.kscience.controls.manager.DeviceManager
import space.kscience.dataforge.context.Factory
import space.kscience.dataforge.meta.Meta
import space.kscience.dataforge.meta.get
import space.kscience.dataforge.names.NameToken
import kotlin.collections.Map
import kotlin.collections.component1
import kotlin.collections.component2
import kotlin.collections.mapValues
import kotlin.collections.mutableMapOf
import kotlin.collections.set
public class DeviceTree(
public val deviceManager: DeviceManager,
public val meta: Meta,
builder: Builder,
) : DeviceHub {
public class Builder(public val manager: DeviceManager) {
internal val childrenFactories = mutableMapOf<NameToken, Factory<Device>>()
public fun <D : Device> device(name: String, factory: Factory<Device>) {
childrenFactories[NameToken.parse(name)] = factory
}
}
override val devices: Map<NameToken, Device> = builder.childrenFactories.mapValues { (token, factory) ->
val devicesMeta = meta["devices"]
factory.build(deviceManager.context, devicesMeta?.get(token) ?: Meta.EMPTY)
}
}

View File

@ -237,7 +237,7 @@ public fun <D : Device> D.bindProcessImage(
image.setLocked(true) image.setLocked(true)
if (openOnBind) { if (openOnBind) {
launch { launch {
open() start()
} }
} }
return image return image

View File

@ -20,16 +20,14 @@ public open class ModbusDeviceBySpec<D: Device>(
private val disposeMasterOnClose: Boolean = true, private val disposeMasterOnClose: Boolean = true,
meta: Meta = Meta.EMPTY, meta: Meta = Meta.EMPTY,
) : ModbusDevice, DeviceBySpec<D>(spec, context, meta){ ) : ModbusDevice, DeviceBySpec<D>(spec, context, meta){
override suspend fun open() { override suspend fun onStart() {
master.connect() master.connect()
super<DeviceBySpec>.open()
} }
override fun close() { override fun onStop() {
if(disposeMasterOnClose){ if(disposeMasterOnClose){
master.disconnect() master.disconnect()
} }
super<ModbusDevice>.close()
} }
} }

View File

@ -63,8 +63,7 @@ public open class OpcUaDeviceBySpec<D : Device>(
} }
} }
override fun close() { override fun onStop() {
client.disconnect() client.disconnect()
super<DeviceBySpec>.close()
} }
} }

View File

@ -73,11 +73,11 @@ public class DeviceNameSpace(
//for now, use DF paths as ids //for now, use DF paths as ids
nodeId = newNodeId("${deviceName.tokens.joinToString("/")}/$propertyName") nodeId = newNodeId("${deviceName.tokens.joinToString("/")}/$propertyName")
when { when {
descriptor.readable && descriptor.writable -> { descriptor.readable && descriptor.mutable -> {
setAccessLevel(AccessLevel.READ_WRITE) setAccessLevel(AccessLevel.READ_WRITE)
setUserAccessLevel(AccessLevel.READ_WRITE) setUserAccessLevel(AccessLevel.READ_WRITE)
} }
descriptor.writable -> { descriptor.mutable -> {
setAccessLevel(AccessLevel.WRITE_ONLY) setAccessLevel(AccessLevel.WRITE_ONLY)
setUserAccessLevel(AccessLevel.WRITE_ONLY) setUserAccessLevel(AccessLevel.WRITE_ONLY)
} }

View File

@ -40,9 +40,10 @@ class OpcUaClientTest {
@Test @Test
@Ignore @Ignore
fun testReadDouble() = runTest { fun testReadDouble() = runTest {
DemoOpcUaDevice.build().use{ val device = DemoOpcUaDevice.build()
println(it.read(DemoOpcUaDevice.randomDouble)) device.start()
} println(device.read(DemoOpcUaDevice.randomDouble))
device.stop()
} }
} }

View File

@ -78,7 +78,7 @@ class DemoController : Controller(), ContextAware {
logger.info { "Visualization server stopped" } logger.info { "Visualization server stopped" }
magixServer?.stop(1000, 5000) magixServer?.stop(1000, 5000)
logger.info { "Magix server stopped" } logger.info { "Magix server stopped" }
device?.close() device?.stop()
logger.info { "Device server stopped" } logger.info { "Device server stopped" }
context.close() context.close()
} }

View File

@ -44,7 +44,7 @@ class DemoDevice(context: Context, meta: Meta) : DeviceBySpec<IDemoDevice>(Compa
metaDescriptor { metaDescriptor {
type(ValueType.NUMBER) type(ValueType.NUMBER)
} }
info = "Real to virtual time scale" description = "Real to virtual time scale"
} }
val sinScale by mutableProperty(MetaConverter.double, IDemoDevice::sinScaleState) val sinScale by mutableProperty(MetaConverter.double, IDemoDevice::sinScaleState)

View File

@ -14,7 +14,6 @@ import space.kscience.dataforge.names.Name
import space.kscience.magix.api.MagixEndpoint import space.kscience.magix.api.MagixEndpoint
import space.kscience.magix.api.subscribe import space.kscience.magix.api.subscribe
import space.kscience.magix.rsocket.rSocketWithWebSockets import space.kscience.magix.rsocket.rSocketWithWebSockets
import kotlin.time.ExperimentalTime
class MagixVirtualCar(context: Context, meta: Meta) : VirtualCar(context, meta) { class MagixVirtualCar(context: Context, meta: Meta) : VirtualCar(context, meta) {
@ -31,17 +30,13 @@ class MagixVirtualCar(context: Context, meta: Meta) : VirtualCar(context, meta)
} }
@OptIn(ExperimentalTime::class) override suspend fun onStart() {
override suspend fun open() {
super.open()
val magixEndpoint = MagixEndpoint.rSocketWithWebSockets( val magixEndpoint = MagixEndpoint.rSocketWithWebSockets(
meta["magixServerHost"].string ?: "localhost", meta["magixServerHost"].string ?: "localhost",
) )
launch { magixEndpoint.launchMagixVirtualCarUpdate()
magixEndpoint.launchMagixVirtualCarUpdate()
}
} }
companion object : Factory<MagixVirtualCar> { companion object : Factory<MagixVirtualCar> {

View File

@ -100,8 +100,7 @@ open class VirtualCar(context: Context, meta: Meta) : DeviceBySpec<VirtualCar>(I
} }
@OptIn(ExperimentalTime::class) @OptIn(ExperimentalTime::class)
override suspend fun open() { override suspend fun onStart() {
super<DeviceBySpec>.open()
//initializing the clock //initializing the clock
timeState = Clock.System.now() timeState = Clock.System.now()
//starting regular updates //starting regular updates

View File

@ -71,9 +71,9 @@ class VirtualCarController : Controller(), ContextAware {
logger.info { "Shutting down..." } logger.info { "Shutting down..." }
magixServer?.stop(1000, 5000) magixServer?.stop(1000, 5000)
logger.info { "Magix server stopped" } logger.info { "Magix server stopped" }
magixVirtualCar?.close() magixVirtualCar?.stop()
logger.info { "Magix virtual car server stopped" } logger.info { "Magix virtual car server stopped" }
virtualCar?.close() virtualCar?.stop()
logger.info { "Virtual car server stopped" } logger.info { "Virtual car server stopped" }
context.close() context.close()
} }

View File

@ -138,7 +138,7 @@ class PiMotionMasterDevice(
override fun build(context: Context, meta: Meta): PiMotionMasterDevice = PiMotionMasterDevice(context) override fun build(context: Context, meta: Meta): PiMotionMasterDevice = PiMotionMasterDevice(context)
val connected by booleanProperty(descriptorBuilder = { val connected by booleanProperty(descriptorBuilder = {
info = "True if the connection address is defined and the device is initialized" description = "True if the connection address is defined and the device is initialized"
}) { }) {
port != null port != null
} }
@ -201,7 +201,7 @@ class PiMotionMasterDevice(
val timeout by mutableProperty(MetaConverter.duration, PiMotionMasterDevice::timeoutValue) { val timeout by mutableProperty(MetaConverter.duration, PiMotionMasterDevice::timeoutValue) {
info = "Timeout" description = "Timeout"
} }
} }
@ -267,7 +267,7 @@ class PiMotionMasterDevice(
) )
val enabled by axisBooleanProperty("EAX") { val enabled by axisBooleanProperty("EAX") {
info = "Motor enable state." description = "Motor enable state."
} }
val halt by unitAction { val halt by unitAction {
@ -275,20 +275,20 @@ class PiMotionMasterDevice(
} }
val targetPosition by axisNumberProperty("MOV") { val targetPosition by axisNumberProperty("MOV") {
info = """ description = """
Sets a new absolute target position for the specified axis. Sets a new absolute target position for the specified axis.
Servo mode must be switched on for the commanded axis prior to using this command (closed-loop operation). Servo mode must be switched on for the commanded axis prior to using this command (closed-loop operation).
""".trimIndent() """.trimIndent()
} }
val onTarget by booleanProperty({ val onTarget by booleanProperty({
info = "Queries the on-target state of the specified axis." description = "Queries the on-target state of the specified axis."
}) { }) {
readAxisBoolean("ONT?") readAxisBoolean("ONT?")
} }
val reference by booleanProperty({ val reference by booleanProperty({
info = "Get Referencing Result" description = "Get Referencing Result"
}) { }) {
readAxisBoolean("FRF?") readAxisBoolean("FRF?")
} }
@ -298,36 +298,36 @@ class PiMotionMasterDevice(
} }
val minPosition by doubleProperty({ val minPosition by doubleProperty({
info = "Minimal position value for the axis" description = "Minimal position value for the axis"
}) { }) {
mm.requestAndParse("TMN?", axisId)[axisId]?.toDoubleOrNull() mm.requestAndParse("TMN?", axisId)[axisId]?.toDoubleOrNull()
?: error("Malformed `TMN?` response. Should include float value for $axisId") ?: error("Malformed `TMN?` response. Should include float value for $axisId")
} }
val maxPosition by doubleProperty({ val maxPosition by doubleProperty({
info = "Maximal position value for the axis" description = "Maximal position value for the axis"
}) { }) {
mm.requestAndParse("TMX?", axisId)[axisId]?.toDoubleOrNull() mm.requestAndParse("TMX?", axisId)[axisId]?.toDoubleOrNull()
?: error("Malformed `TMX?` response. Should include float value for $axisId") ?: error("Malformed `TMX?` response. Should include float value for $axisId")
} }
val position by doubleProperty({ val position by doubleProperty({
info = "The current axis position." description = "The current axis position."
}) { }) {
mm.requestAndParse("POS?", axisId)[axisId]?.toDoubleOrNull() mm.requestAndParse("POS?", axisId)[axisId]?.toDoubleOrNull()
?: error("Malformed `POS?` response. Should include float value for $axisId") ?: error("Malformed `POS?` response. Should include float value for $axisId")
} }
val openLoopTarget by axisNumberProperty("OMA") { val openLoopTarget by axisNumberProperty("OMA") {
info = "Position for open-loop operation." description = "Position for open-loop operation."
} }
val closedLoop by axisBooleanProperty("SVO") { val closedLoop by axisBooleanProperty("SVO") {
info = "Servo closed loop mode" description = "Servo closed loop mode"
} }
val velocity by axisNumberProperty("VEL") { val velocity by axisNumberProperty("VEL") {
info = "Velocity value for closed-loop operation" description = "Velocity value for closed-loop operation"
} }
val move by action(MetaConverter.meta, MetaConverter.unit) { val move by action(MetaConverter.meta, MetaConverter.unit) {

View File

@ -10,4 +10,4 @@ publishing.sonatype=false
org.gradle.configureondemand=true org.gradle.configureondemand=true
org.gradle.jvmargs=-Xmx4096m org.gradle.jvmargs=-Xmx4096m
toolsVersion=0.15.0-kotlin-1.9.20-RC toolsVersion=0.15.0-kotlin-1.9.20-RC2

View File

@ -50,6 +50,7 @@ include(
// ":controls-mongo", // ":controls-mongo",
":controls-storage", ":controls-storage",
":controls-storage:controls-xodus", ":controls-storage:controls-xodus",
":controls-constructor",
":magix", ":magix",
":magix:magix-api", ":magix:magix-api",
":magix:magix-server", ":magix:magix-server",