WIP: Простая конфигурация устройств через спецификации #12

Draft
kolpakov.mm wants to merge 2 commits from dev-maxim into dev
19 changed files with 1820 additions and 69 deletions

View File

@ -16,10 +16,14 @@ kscience{
useSerialization() useSerialization()
commonMain { commonMain {
api(projects.controlsCore) api(projects.controlsCore)
implementation("org.jetbrains.kotlinx:kotlinx-coroutines-core:1.8.1")
Review

Use libs.versions for version storage or use spclibs reference

Use libs.versions for version storage or use `spclibs` reference
implementation("org.jetbrains.kotlinx:multik-core:0.2.3")
} }
commonTest{ commonTest{
implementation(spclibs.logback.classic) implementation(spclibs.logback.classic)
implementation("org.jetbrains.kotlinx:kotlinx-coroutines-core:1.8.1")
implementation("org.jetbrains.kotlinx:kotlinx-coroutines-test:1.9.0")
} }
} }

View File

@ -74,6 +74,18 @@ public interface StateContainer : ContextAware, CoroutineScope {
}.launchIn(this@StateContainer).also { }.launchIn(this@StateContainer).also {
registerElement(ConnectionConstrucorElement(reads + this, writes)) registerElement(ConnectionConstrucorElement(reads + this, writes))
} }
/**
* Create and register a derived state.
*/
public fun <T> derivedState(
Review

What is the reason for this method in the state container? Why computeValue does not take parameters?

What is the reason for this method in the state container? Why `computeValue` does not take parameters?
dependencies: List<DeviceState<*>>,
computeValue: () -> T,
Review

Should be suspended

Should be suspended
): DeviceStateWithDependencies<T> {
val state = DeviceState.derived(this, dependencies, computeValue)
registerElement(StateConstructorElement(state))
return state
}
} }
/** /**
@ -210,7 +222,7 @@ public fun <T1, T2, R> StateContainer.combineTo(
): Job { ): Job {
val descriptor = ConnectionConstrucorElement(setOf(sourceState1, sourceState2), setOf(targetState)) val descriptor = ConnectionConstrucorElement(setOf(sourceState1, sourceState2), setOf(targetState))
registerElement(descriptor) registerElement(descriptor)
return kotlinx.coroutines.flow.combine(sourceState1.valueFlow, sourceState2.valueFlow, transformation).onEach { return combine(sourceState1.valueFlow, sourceState2.valueFlow, transformation).onEach {
targetState.value = it targetState.value = it
}.launchIn(this).apply { }.launchIn(this).apply {
invokeOnCompletion { invokeOnCompletion {
@ -231,7 +243,7 @@ public inline fun <reified T, R> StateContainer.combineTo(
): Job { ): Job {
val descriptor = ConnectionConstrucorElement(sourceStates, setOf(targetState)) val descriptor = ConnectionConstrucorElement(sourceStates, setOf(targetState))
registerElement(descriptor) registerElement(descriptor)
return kotlinx.coroutines.flow.combine(sourceStates.map { it.valueFlow }, transformation).onEach { return combine(sourceStates.map { it.valueFlow }, transformation).onEach {
targetState.value = it targetState.value = it
}.launchIn(this).apply { }.launchIn(this).apply {
invokeOnCompletion { invokeOnCompletion {

View File

@ -2,10 +2,7 @@ package space.kscience.controls.constructor
import kotlinx.coroutines.CoroutineScope import kotlinx.coroutines.CoroutineScope
import kotlinx.coroutines.Job import kotlinx.coroutines.Job
import kotlinx.coroutines.flow.Flow import kotlinx.coroutines.flow.*
import kotlinx.coroutines.flow.launchIn
import kotlinx.coroutines.flow.map
import kotlinx.coroutines.flow.onEach
import space.kscience.controls.constructor.units.NumericalValue import space.kscience.controls.constructor.units.NumericalValue
import space.kscience.controls.constructor.units.UnitsOfMeasurement import space.kscience.controls.constructor.units.UnitsOfMeasurement
import kotlin.reflect.KProperty import kotlin.reflect.KProperty
@ -44,18 +41,43 @@ public operator fun <T> MutableDeviceState<T>.setValue(thisRef: Any?, property:
} }
/** /**
* Device state with a value that depends on other device states * DeviceState with dependencies on other DeviceStates.
*/ */
public interface DeviceStateWithDependencies<T> : DeviceState<T> { public interface DeviceStateWithDependencies<T> : DeviceState<T> {
public val dependencies: Collection<DeviceState<*>> public val dependencies: Collection<DeviceState<*>>
} }
/**
* Extension function to create a DerivedDeviceState.
*/
public fun <T> DeviceState.Companion.derived(
scope: CoroutineScope,
dependencies: List<DeviceState<*>>,
computeValue: () -> T
Review

Should use suspended function

Should use suspended function
): DeviceStateWithDependencies<T> = DerivedDeviceState(scope, dependencies, computeValue)
public fun <T> DeviceState<T>.withDependencies( public fun <T> DeviceState<T>.withDependencies(
dependencies: Collection<DeviceState<*>>, dependencies: Collection<DeviceState<*>>,
): DeviceStateWithDependencies<T> = object : DeviceStateWithDependencies<T>, DeviceState<T> by this { ): DeviceStateWithDependencies<T> = object : DeviceStateWithDependencies<T>, DeviceState<T> by this {
override val dependencies: Collection<DeviceState<*>> = dependencies override val dependencies: Collection<DeviceState<*>> = dependencies
} }
public fun <T> DeviceState.Companion.fromFlow(
Review

Should be documented

Should be documented
scope: CoroutineScope,
flow: Flow<T>,
initialValue: T
): DeviceState<T> {
val stateFlow = flow.stateIn(scope, SharingStarted.Eagerly, initialValue)
return object : DeviceState<T> {
override val value: T get() = stateFlow.value
override val valueFlow: Flow<T> get() = stateFlow
override fun toString(): String {
return "DeviceState.fromFlow(scope=$scope, flow=$flow, initialValue=$initialValue)"
}
}
}
/** /**
* Create a new read-only [DeviceState] that mirrors receiver state by mapping the value with [mapper]. * Create a new read-only [DeviceState] that mirrors receiver state by mapping the value with [mapper].
*/ */
@ -101,3 +123,27 @@ public fun <T1, T2, R> DeviceState.Companion.combine(
override fun toString(): String = "DeviceState.combine(state1=$state1, state2=$state2)" override fun toString(): String = "DeviceState.combine(state1=$state1, state2=$state2)"
} }
/**
* A DeviceState that derives its value from other DeviceStates.
*/
public class DerivedDeviceState<T>(
scope: CoroutineScope,
override val dependencies: List<DeviceState<*>>,
computeValue: () -> T
) : DeviceStateWithDependencies<T> {
private val _valueFlow: StateFlow<T>
init {
Review

Don't assign values in init. Use fake constructor if needed

Don't assign values in init. Use fake constructor if needed
val flows = dependencies.map { it.valueFlow }
_valueFlow = combine(flows) {
computeValue()
}.stateIn(scope, SharingStarted.Eagerly, computeValue())
}
override val value: T get() = _valueFlow.value
override val valueFlow: Flow<T> get() = _valueFlow
override fun toString(): String {
TODO("Not yet implemented")
}
}

View File

@ -3,7 +3,7 @@ package space.kscience.controls.constructor.devices
import space.kscience.controls.constructor.DeviceConstructor import space.kscience.controls.constructor.DeviceConstructor
import space.kscience.controls.constructor.MutableDeviceState import space.kscience.controls.constructor.MutableDeviceState
import space.kscience.controls.constructor.property import space.kscience.controls.constructor.property
import space.kscience.controls.constructor.units.NewtonsMeters import space.kscience.controls.constructor.units.NewtonMeters
import space.kscience.controls.constructor.units.NumericalValue import space.kscience.controls.constructor.units.NumericalValue
import space.kscience.controls.constructor.units.numerical import space.kscience.controls.constructor.units.numerical
import space.kscience.dataforge.context.Context import space.kscience.dataforge.context.Context
@ -13,7 +13,7 @@ import space.kscience.dataforge.meta.MetaConverter
public class Drive( public class Drive(
context: Context, context: Context,
force: MutableDeviceState<NumericalValue<NewtonsMeters>> = MutableDeviceState(NumericalValue(0)), force: MutableDeviceState<NumericalValue<NewtonMeters>> = MutableDeviceState(NumericalValue(0)),
) : DeviceConstructor(context) { ) : DeviceConstructor(context) {
public val force: MutableDeviceState<NumericalValue<NewtonsMeters>> by property(MetaConverter.numerical(), force) public val force: MutableDeviceState<NumericalValue<NewtonMeters>> by property(MetaConverter.numerical(), force)
} }

View File

@ -4,7 +4,7 @@ import space.kscience.controls.constructor.*
import space.kscience.controls.constructor.models.PidParameters import space.kscience.controls.constructor.models.PidParameters
import space.kscience.controls.constructor.models.PidRegulator import space.kscience.controls.constructor.models.PidRegulator
import space.kscience.controls.constructor.units.Meters import space.kscience.controls.constructor.units.Meters
import space.kscience.controls.constructor.units.NewtonsMeters import space.kscience.controls.constructor.units.NewtonMeters
import space.kscience.controls.constructor.units.NumericalValue import space.kscience.controls.constructor.units.NumericalValue
import space.kscience.controls.constructor.units.numerical import space.kscience.controls.constructor.units.numerical
import space.kscience.dataforge.context.Context import space.kscience.dataforge.context.Context
@ -24,7 +24,7 @@ public class LinearDrive(
public val position: DeviceState<NumericalValue<Meters>> by property(MetaConverter.numerical(), position) public val position: DeviceState<NumericalValue<Meters>> by property(MetaConverter.numerical(), position)
public val drive: Drive by device(drive) public val drive: Drive by device(drive)
public val pid: PidRegulator<Meters, NewtonsMeters> = model( public val pid: PidRegulator<Meters, NewtonMeters> = model(
PidRegulator( PidRegulator(
context = context, context = context,
position = position, position = position,

View File

@ -55,7 +55,7 @@ public class Inertia<U : UnitsOfMeasurement, V : UnitsOfMeasurement>(
public fun circular( public fun circular(
context: Context, context: Context,
force: DeviceState<NumericalValue<NewtonsMeters>>, force: DeviceState<NumericalValue<NewtonMeters>>,
momentOfInertia: NumericalValue<KgM2>, momentOfInertia: NumericalValue<KgM2>,
position: MutableDeviceState<NumericalValue<Degrees>>, position: MutableDeviceState<NumericalValue<Degrees>>,
velocity: MutableDeviceState<NumericalValue<DegreesPerSecond>> = MutableDeviceState(NumericalValue(0.0)), velocity: MutableDeviceState<NumericalValue<DegreesPerSecond>> = MutableDeviceState(NumericalValue(0.0)),

View File

@ -16,7 +16,7 @@ public class Leadscrew(
) : ModelConstructor(context) { ) : ModelConstructor(context) {
public fun torqueToForce( public fun torqueToForce(
stateOfTorque: DeviceState<NumericalValue<NewtonsMeters>>, stateOfTorque: DeviceState<NumericalValue<NewtonMeters>>,
): DeviceState<NumericalValue<Newtons>> = DeviceState.map(stateOfTorque) { torque -> ): DeviceState<NumericalValue<Newtons>> = DeviceState.map(stateOfTorque) { torque ->
NumericalValue(torque.value / leverage.value ) NumericalValue(torque.value / leverage.value )
} }

View File

@ -5,7 +5,6 @@ import space.kscience.dataforge.meta.MetaConverter
import space.kscience.dataforge.meta.double import space.kscience.dataforge.meta.double
import kotlin.jvm.JvmInline import kotlin.jvm.JvmInline
/** /**
* A value without identity coupled to units of measurements. * A value without identity coupled to units of measurements.
*/ */

View File

@ -1,60 +1,244 @@
package space.kscience.controls.constructor.units package space.kscience.controls.constructor.units
import kotlin.math.*
public interface UnitsOfMeasurement /**
* Represents a unit of measurement.
* Provides methods to convert values to and from the base unit.
*/
public interface UnitsOfMeasurement {
/**
* Symbol representing the unit (e.g., "m" for meters).
*/
public val symbol: String
/**/ /**
* Converts a value from this unit to the base unit.
*/
public fun toBase(value: Double): Double
Review

Not clear how we select the base unit. Probably better documentation is needed. Is it better than the external dispatch that is used right now?

Not clear how we select the base unit. Probably better documentation is needed. Is it better than the external dispatch that is used right now?
/**
* Converts a value from the base unit to this unit.
*/
public fun fromBase(value: Double): Double
}
/**
* Base unit, where conversion to base unit is identity.
*/
public open class BaseUnit(
override val symbol: String,
) : UnitsOfMeasurement {
override fun toBase(value: Double): Double = value
override fun fromBase(value: Double): Double = value
}
/**
* Derived unit with a conversion factor to the base unit.
*/
public class DerivedUnit(
override val symbol: String,
private val conversionFactor: Double, // Factor to convert to base unit.
) : UnitsOfMeasurement {
override fun toBase(value: Double): Double = value * conversionFactor
override fun fromBase(value: Double): Double = value / conversionFactor
}
/**
* Enumeration of SI prefixes with their symbols and factors.
*/
public enum class SIPrefix(
public val symbol: String,
public val factor: Double
) {
YOTTA("Y", 1e24),
ZETTA("Z", 1e21),
EXA("E", 1e18),
PETA("P", 1e15),
TERA("T", 1e12),
GIGA("G", 1e9),
MEGA("M", 1e6),
KILO("k", 1e3),
HECTO("h", 1e2),
DECA("da", 1e1),
NONE("", 1.0),
DECI("d", 1e-1),
CENTI("c", 1e-2),
MILLI("m", 1e-3),
MICRO("μ", 1e-6),
NANO("n", 1e-9),
PICO("p", 1e-12),
FEMTO("f", 1e-15),
ATTO("a", 1e-18),
ZEPTO("z", 1e-21),
YOCTO("y", 1e-24),
}
/**
* Creates a new unit by applying an SI prefix to the current unit.
*/
public fun <U : UnitsOfMeasurement> U.withPrefix(prefix: SIPrefix): UnitsOfMeasurement {
val prefixedSymbol = prefix.symbol + this.symbol
val prefixedFactor = prefix.factor
return object : UnitsOfMeasurement {
override val symbol: String = prefixedSymbol
override fun toBase(value: Double): Double = this@withPrefix.toBase(value * prefixedFactor)
override fun fromBase(value: Double): Double = this@withPrefix.fromBase(value) / prefixedFactor
}
}
/**
* Interface for units of length.
*/
public interface UnitsOfLength : UnitsOfMeasurement public interface UnitsOfLength : UnitsOfMeasurement
public data object Meters : UnitsOfLength /**
* Base unit for length: Meter.
*/
public data object Meters : UnitsOfLength {
override val symbol: String = "m"
override fun toBase(value: Double): Double = value // Base unit
override fun fromBase(value: Double): Double = value
}
/**/
/**
* Interface for units of time.
*/
public interface UnitsOfTime : UnitsOfMeasurement public interface UnitsOfTime : UnitsOfMeasurement
public data object Seconds : UnitsOfTime /**
* Base unit for time: Second.
/**/ */
public data object Seconds : UnitsOfTime {
override val symbol: String = "s"
override fun toBase(value: Double): Double = value // Base unit
override fun fromBase(value: Double): Double = value
}
/**
* Interface for units of velocity.
*/
public interface UnitsOfVelocity : UnitsOfMeasurement public interface UnitsOfVelocity : UnitsOfMeasurement
public data object MetersPerSecond : UnitsOfVelocity /**
* Derived unit for velocity: Meters per Second.
*/
public data object MetersPerSecond : UnitsOfVelocity {
override val symbol: String = "m/s"
override fun toBase(value: Double): Double = value // Base unit for velocity
override fun fromBase(value: Double): Double = value
}
/**/ /**/
/**
* Sealed interface for units of angles.
*/
public sealed interface UnitsOfAngles : UnitsOfMeasurement public sealed interface UnitsOfAngles : UnitsOfMeasurement
public data object Radians : UnitsOfAngles /**
public data object Degrees : UnitsOfAngles * Base unit for angles: Radian.
*/
public data object Radians : UnitsOfAngles {
override val symbol: String = "rad"
override fun toBase(value: Double): Double = value // Base unit
override fun fromBase(value: Double): Double = value
}
/**
* Unit for angles: Degree.
*/
public data object Degrees : UnitsOfAngles {
override val symbol: String = "deg"
override fun toBase(value: Double): Double = value * (PI / 180.0)
override fun fromBase(value: Double): Double = value * (180.0 / PI)
}
/**/ /**/
/**
* Sealed interface for units of angular velocity.
*/
public sealed interface UnitsAngularOfVelocity : UnitsOfMeasurement public sealed interface UnitsAngularOfVelocity : UnitsOfMeasurement
public data object RadiansPerSecond : UnitsAngularOfVelocity /**
* Base unit for angular velocity: Radians per Second.
*/
public data object RadiansPerSecond : UnitsAngularOfVelocity {
override val symbol: String = "rad/s"
override fun toBase(value: Double): Double = value // Base unit
override fun fromBase(value: Double): Double = value
}
public data object DegreesPerSecond : UnitsAngularOfVelocity /**
* Unit for angular velocity: Degrees per Second.
*/
public data object DegreesPerSecond : UnitsAngularOfVelocity {
override val symbol: String = "deg/s"
override fun toBase(value: Double): Double = value * (PI / 180.0)
override fun fromBase(value: Double): Double = value * (180.0 / PI)
}
/**/ /**
public interface UnitsOfForce: UnitsOfMeasurement * Interface for units of force.
*/
public interface UnitsOfForce : UnitsOfMeasurement
public data object Newtons: UnitsOfForce /**
* Base unit for force: Newton.
*/
public data object Newtons : UnitsOfForce {
override val symbol: String = "N"
override fun toBase(value: Double): Double = value // Base unit
override fun fromBase(value: Double): Double = value
}
/**/ /**
* Interface for units of torque.
*/
public interface UnitsOfTorque : UnitsOfMeasurement
public interface UnitsOfTorque: UnitsOfMeasurement /**
* Base unit for torque: Newton Meter.
*/
public data object NewtonMeters : UnitsOfTorque {
override val symbol: String = "N·m"
override fun toBase(value: Double): Double = value // Base unit
override fun fromBase(value: Double): Double = value
}
public data object NewtonsMeters: UnitsOfTorque /**
* Interface for units of mass.
*/
public interface UnitsOfMass : UnitsOfMeasurement
/**/ /**
* Base unit for mass: Kilogram.
*/
public data object Kilograms : UnitsOfMass {
override val symbol: String = "kg"
override fun toBase(value: Double): Double = value // Base unit
override fun fromBase(value: Double): Double = value
}
public interface UnitsOfMass: UnitsOfMeasurement /**
* Interface for units of moment of inertia.
*/
public interface UnitsOfMomentOfInertia : UnitsOfMeasurement
public data object Kilograms : UnitsOfMass /**
* Base unit for moment of inertia: Kilogram Meter Squared.
/**/ */
public data object KgM2 : UnitsOfMomentOfInertia {
public interface UnitsOfMomentOfInertia: UnitsOfMeasurement override val symbol: String = "kg·m²"
override fun toBase(value: Double): Double = value // Base unit
public data object KgM2: UnitsOfMomentOfInertia override fun fromBase(value: Double): Double = value
}

View File

@ -0,0 +1,806 @@
package space.kscience.controls.constructor
import kotlinx.coroutines.*
import kotlinx.coroutines.test.runTest
import space.kscience.controls.api.LifecycleState
import space.kscience.controls.spec.*
import space.kscience.dataforge.context.Context
import space.kscience.dataforge.meta.*
import kotlin.test.Test
import kotlin.test.assertEquals
import kotlin.test.assertFalse
import kotlin.test.assertTrue
// Спецификация шагового мотора
object StepperMotorSpec : DeviceSpec<StepperMotorDevice>() {
val position by intProperty(
read = { propertyName -> getPosition() },
write = { propertyName, value -> setPosition(value) }
)
val maxPosition by intProperty(
read = { propertyName -> maxPosition }
)
override fun createDevice(context: Context, meta: Meta): StepperMotorDevice {
return StepperMotorDevice(context, meta)
}
}
// Реализация устройства шагового мотора
class StepperMotorDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<StepperMotorDevice>(StepperMotorSpec, context, meta) {
private var _position: Int = 0
val maxPosition: Int = meta["maxPosition"].int ?: 100
// Получить текущую позицию мотора
suspend fun getPosition(): Int = _position
Review

probably better to use readPosition instead of getPosition. It communicates what the functions do better.

probably better to use `readPosition` instead of `getPosition`. It communicates what the functions do better.
// Установить позицию мотора
suspend fun setPosition(value: Int) {
Review

Consider encapsulating those functions.

Consider encapsulating those functions.
if (value in 0..maxPosition) {
_position = value
println("StepperMotorDevice: Перемещен в позицию $_position")
delay(100) // Имитация времени на перемещение
} else {
println("StepperMotorDevice: Неверная позиция $value (макс: $maxPosition)")
}
}
override fun toString(): String = "StepperMotorDevice"
}
// Спецификация клапана
object ValveSpec : DeviceSpec<ValveDevice>() {
val state by booleanProperty(
read = { propertyName -> getState() },
write = { propertyName, value -> setState(value) }
)
override fun createDevice(context: Context, meta: Meta): ValveDevice {
return ValveDevice(context, meta)
}
}
// Реализация устройства клапана
class ValveDevice(
Review

Maybe call it VirtualValv or similar to discriminate between virtual devices and real ones.

Maybe call it `VirtualValv` or similar to discriminate between virtual devices and real ones.
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<ValveDevice>(ValveSpec, context, meta) {
private var _state: Boolean = false
// Получить состояние клапана
suspend fun getState(): Boolean = _state
// Установить состояние клапана
suspend fun setState(value: Boolean) {
_state = value
val stateStr = if (_state) "открыт" else "закрыт"
println("ValveDevice: Клапан теперь $stateStr")
Review

Remove debug prints. Use property subscription for testing. Don't use Russian.

Remove debug prints. Use property subscription for testing. Don't use Russian.
delay(50) // Имитация времени на изменение состояния
}
// Метод для щелчка клапана
suspend fun click() {
println("ValveDevice: Клик клапана...")
setState(true)
delay(50)
setState(false)
println("ValveDevice: Клик клапана завершен")
}
override fun toString(): String = "ValveDevice"
}
// Спецификация камеры давления
object PressureChamberSpec : DeviceSpec<PressureChamberDevice>() {
val pressure by doubleProperty(
read = { propertyName -> getPressure() },
write = { propertyName, value -> setPressure(value) }
)
override fun createDevice(context: Context, meta: Meta): PressureChamberDevice {
return PressureChamberDevice(context, meta)
}
}
// Реализация устройства камеры давления
class PressureChamberDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<PressureChamberDevice>(PressureChamberSpec, context, meta) {
private var _pressure: Double = 0.0
// Получить текущее давление
suspend fun getPressure(): Double = _pressure
Review

readPressure?

readPressure?
// Установить давление
suspend fun setPressure(value: Double) {
_pressure = value
println("PressureChamberDevice: Давление установлено на $_pressure")
delay(50)
}
override fun toString(): String = "PressureChamberDevice"
}
// Спецификация шприцевого насоса
object SyringePumpSpec : DeviceSpec<SyringePumpDevice>() {
val volume by doubleProperty(
read = { propertyName -> getVolume() },
write = { propertyName, value -> setVolume(value) }
)
override fun createDevice(context: Context, meta: Meta): SyringePumpDevice {
return SyringePumpDevice(context, meta)
}
}
// Реализация устройства шприцевого насоса
class SyringePumpDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<SyringePumpDevice>(SyringePumpSpec, context, meta) {
private var _volume: Double = 0.0
val maxVolume: Double = meta["maxVolume"].double ?: 5.0
// Получить текущий объем
suspend fun getVolume(): Double = _volume
// Установить объем
suspend fun setVolume(value: Double) {
if (value in 0.0..maxVolume) {
_volume = value
println("SyringePumpDevice: Объем установлен на $_volume мл")
delay(100)
} else {
println("SyringePumpDevice: Неверный объем $value (макс: $maxVolume)")
}
}
override fun toString(): String = "SyringePumpDevice"
}
// Спецификация датчика реагента
object ReagentSensorSpec : DeviceSpec<ReagentSensorDevice>() {
val isPresent by booleanProperty(
read = { propertyName -> checkReagent() }
)
override fun createDevice(context: Context, meta: Meta): ReagentSensorDevice {
return ReagentSensorDevice(context, meta)
}
}
// Реализация устройства датчика реагента
class ReagentSensorDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<ReagentSensorDevice>(ReagentSensorSpec, context, meta) {
// Проверить наличие реагента
suspend fun checkReagent(): Boolean {
println("ReagentSensorDevice: Проверка наличия реагента...")
delay(100) // Имитация времени на проверку
val isPresent = true // Предполагаем, что реагент присутствует
println("ReagentSensorDevice: Реагент ${if (isPresent) "обнаружен" else "не обнаружен"}")
return isPresent
}
override fun toString(): String = "ReagentSensorDevice"
}
// Спецификация иглы
object NeedleSpec : DeviceSpec<NeedleDevice>() {
val mode by enumProperty(
enumValues = NeedleDevice.Mode.entries.toTypedArray(),
read = { propertyName -> getMode() },
write = { propertyName, value -> setMode(value) }
)
val position by doubleProperty(
read = { propertyName -> getPosition() },
write = { propertyName, value -> setPosition(value) }
)
override fun createDevice(context: Context, meta: Meta): NeedleDevice {
return NeedleDevice(context, meta)
}
}
// Реализация устройства иглы
class NeedleDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<NeedleDevice>(NeedleSpec, context, meta) {
// Режимы работы иглы
enum class Mode { SAMPLING, WASHING }
private var mode: Mode = Mode.WASHING
private var position: Double = 0.0 // в мм
// Получить текущий режим
suspend fun getMode(): Mode = mode
// Установить режим
suspend fun setMode(value: Mode) {
mode = value
println("NeedleDevice: Режим установлен на $mode")
delay(50)
}
// Получить текущую позицию
suspend fun getPosition(): Double = position
// Установить позицию
suspend fun setPosition(value: Double) {
if (value in 0.0..100.0) {
position = value
println("NeedleDevice: Перемещена в позицию $position мм")
delay(100)
} else {
println("NeedleDevice: Неверная позиция $value мм")
}
}
// Выполнить промывку
suspend fun performWashing(duration: Int) {
println("NeedleDevice: Промывка в течение $duration секунд")
delay(duration * 1000L) // Имитация промывки (1 секунда = 1000 мс)
}
// Выполнить забор пробы
suspend fun performSampling() {
println("NeedleDevice: Забор пробы в позиции $position мм")
Review

Remove debug prints. If needed, use device log

Remove debug prints. If needed, use device log
delay(500) // Имитация забора пробы
}
override fun toString(): String = "NeedleDevice"
}
// Спецификация шейкера
object ShakerSpec : DeviceSpec<ShakerDevice>() {
val verticalMotor by device(StepperMotorSpec, name = "verticalMotor")
val horizontalMotor by device(StepperMotorSpec, name = "horizontalMotor")
override fun createDevice(context: Context, meta: Meta): ShakerDevice {
return ShakerDevice(context, meta)
}
}
// Реализация устройства шейкера
class ShakerDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<ShakerDevice>(ShakerSpec, context, meta) {
val verticalMotor: StepperMotorDevice
get() = nestedDevices["verticalMotor"] as StepperMotorDevice
val horizontalMotor: StepperMotorDevice
get() = nestedDevices["horizontalMotor"] as StepperMotorDevice
// Метод встряхивания
suspend fun shake(cycles: Int) {
println("ShakerDevice: Начало встряхивания, циклов: $cycles")
repeat(cycles) {
verticalMotor.setPosition(3)
verticalMotor.setPosition(1)
}
println("ShakerDevice: Встряхивание завершено")
}
override fun toString(): String = "ShakerDevice"
}
// Спецификация системы транспортировки
object TransportationSystemSpec : DeviceSpec<TransportationSystem>() {
val slideMotor by device(StepperMotorSpec, name = "slideMotor")
val pushMotor by device(StepperMotorSpec, name = "pushMotor")
val receiveMotor by device(StepperMotorSpec, name = "receiveMotor")
override fun createDevice(context: Context, meta: Meta): TransportationSystem {
return TransportationSystem(context, meta)
}
}
// Реализация системы транспортировки
class TransportationSystem(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<TransportationSystem>(TransportationSystemSpec, context, meta) {
val slideMotor: StepperMotorDevice
get() = nestedDevices["slideMotor"] as StepperMotorDevice
val pushMotor: StepperMotorDevice
get() = nestedDevices["pushMotor"] as StepperMotorDevice
val receiveMotor: StepperMotorDevice
get() = nestedDevices["receiveMotor"] as StepperMotorDevice
override fun toString(): String = "TransportationSystem"
}
// Спецификация анализатора
object AnalyzerSpec : DeviceSpec<AnalyzerDevice>() {
val transportationSystem by device(TransportationSystemSpec, name = "transportationSystem")
val shakerDevice by device(ShakerSpec, name = "shakerDevice")
val needleDevice by device(NeedleSpec, name = "needleDevice")
val valveV20 by device(ValveSpec, name = "valveV20")
val valveV17 by device(ValveSpec, name = "valveV17")
val valveV18 by device(ValveSpec, name = "valveV18")
val valveV35 by device(ValveSpec, name = "valveV35")
val pressureChamberHigh by device(PressureChamberSpec, name = "pressureChamberHigh")
val pressureChamberLow by device(PressureChamberSpec, name = "pressureChamberLow")
val syringePumpMA100 by device(SyringePumpSpec, name = "syringePumpMA100")
val syringePumpMA25 by device(SyringePumpSpec, name = "syringePumpMA25")
val reagentSensor1 by device(ReagentSensorSpec, name = "reagentSensor1")
val reagentSensor2 by device(ReagentSensorSpec, name = "reagentSensor2")
val reagentSensor3 by device(ReagentSensorSpec, name = "reagentSensor3")
override fun createDevice(context: Context, meta: Meta): AnalyzerDevice {
return AnalyzerDevice(context, meta)
}
}
// Реализация анализатора
class AnalyzerDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<AnalyzerDevice>(AnalyzerSpec, context, meta) {
val transportationSystem: TransportationSystem
get() = nestedDevices["transportationSystem"] as TransportationSystem
Review

Probably better to use DeviceGroup API?

Probably better to use DeviceGroup API?
val shakerDevice: ShakerDevice
get() = nestedDevices["shakerDevice"] as ShakerDevice
val needleDevice: NeedleDevice
get() = nestedDevices["needleDevice"] as NeedleDevice
val valveV20: ValveDevice
get() = nestedDevices["valveV20"] as ValveDevice
val valveV17: ValveDevice
get() = nestedDevices["valveV17"] as ValveDevice
val valveV18: ValveDevice
get() = nestedDevices["valveV18"] as ValveDevice
val valveV35: ValveDevice
get() = nestedDevices["valveV35"] as ValveDevice
val pressureChamberHigh: PressureChamberDevice
get() = nestedDevices["pressureChamberHigh"] as PressureChamberDevice
val pressureChamberLow: PressureChamberDevice
get() = nestedDevices["pressureChamberLow"] as PressureChamberDevice
val syringePumpMA100: SyringePumpDevice
get() = nestedDevices["syringePumpMA100"] as SyringePumpDevice
val syringePumpMA25: SyringePumpDevice
get() = nestedDevices["syringePumpMA25"] as SyringePumpDevice
val reagentSensor1: ReagentSensorDevice
get() = nestedDevices["reagentSensor1"] as ReagentSensorDevice
val reagentSensor2: ReagentSensorDevice
get() = nestedDevices["reagentSensor2"] as ReagentSensorDevice
val reagentSensor3: ReagentSensorDevice
get() = nestedDevices["reagentSensor3"] as ReagentSensorDevice
// Процесс обработки проб
suspend fun processSample() {
println("Начало процесса забора пробы")
// Шаг 1: Открыть клапан V20 и начать забор пробы с помощью шприца MA 100 мкл
valveV20.setState(true)
syringePumpMA100.setVolume(0.1)
delay(500) // Имитация времени для забора жидкости
valveV20.setState(false)
// Шаг 2: Открыть клапан V17 и начать подачу лизиса в WBC с помощью MA 2.5 мл
valveV17.setState(true)
syringePumpMA25.setVolume(2.5)
delay(500) // Имитация времени для подачи лизиса
valveV17.setState(false)
// Шаг 3: Очистка системы
syringePumpMA100.setVolume(0.0)
syringePumpMA25.setVolume(0.0)
println("Процесс забора пробы завершен")
}
// Реализация рецепта калибровки
suspend fun calibrate() {
println("Начало калибровки...")
// Шаг 1: Откалибровать положения всех двигателей
val motors = listOf(
transportationSystem.slideMotor,
transportationSystem.pushMotor,
transportationSystem.receiveMotor,
shakerDevice.verticalMotor,
shakerDevice.horizontalMotor
)
for (motor in motors) {
for (position in 0..motor.maxPosition) {
motor.setPosition(position)
}
motor.setPosition(0)
}
// Шаг 2: Щелкнуть всеми клапанами и перевести их в нулевое положение
val valves = listOf(valveV20, valveV17, valveV18, valveV35)
for (valve in valves) {
valve.click()
valve.setState(false)
}
// Шаг 3: Провести накачку давления в камеру повышенного давления
pressureChamberHigh.setPressure(2.0)
// Шаг 4: Провести откачку камеры пониженного давления
pressureChamberLow.setPressure(-1.0)
// Шаг 5: Заполнить гидравлическую систему
// 5.1 Проверить наличие всех реагентов
val sensors = listOf(reagentSensor1, reagentSensor2, reagentSensor3)
for (sensor in sensors) {
sensor.checkReagent()
}
// 5.2 Прокачать все шприцевые дозаторы (5 раз движение между крайними положениями)
val pumps = listOf(syringePumpMA100, syringePumpMA25)
for (pump in pumps) {
repeat(5) {
pump.setVolume(pump.maxVolume)
pump.setVolume(0.0)
}
}
// 5.3 Провести промывку иглы в положении промывки для забора пробы
needleDevice.setPosition(0.0)
needleDevice.setMode(NeedleDevice.Mode.WASHING)
needleDevice.performWashing(5)
println("Калибровка завершена")
}
// Рецепт 1 - Подача пробирки на измерение
suspend fun executeRecipe1() {
println("Выполнение Рецепта 1")
// Шаг 1: Сдвинуть планшет на одну позицию
val currentSlidePosition = transportationSystem.slideMotor.getPosition()
transportationSystem.slideMotor.setPosition(currentSlidePosition + 1)
println("Сдвинуто планшет на позицию ${currentSlidePosition + 1}")
// Шаг 2: Захват пробирки для смешивания
println("Захват пробирки для смешивания")
// 2.1 - 2.10: Управление шейкером и двигателями
shakerDevice.verticalMotor.setPosition(1)
shakerDevice.horizontalMotor.setPosition(1)
println("Шейкер: вертикальный - 1, горизонтальный - 1")
shakerDevice.horizontalMotor.setPosition(2)
println("Шейкер: горизонтальный - 2")
shakerDevice.verticalMotor.setPosition(2)
println("Шейкер: вертикальный - 2")
// Встряхивание 5 циклов
repeat(5) {
shakerDevice.verticalMotor.setPosition(3)
shakerDevice.verticalMotor.setPosition(1)
println("Шейкер: цикл ${it + 1}")
}
shakerDevice.verticalMotor.setPosition(2)
shakerDevice.horizontalMotor.setPosition(1)
println("Шейкер: окончание движения")
// Шаг 3: Забор и измерение пробы
executeSampling()
needleDevice.setPosition(0.0)
println("Игла вернулась в исходное положение")
}
// Функция для выполнения забора пробы
suspend fun executeSampling() {
println("Забор и измерение пробы")
needleDevice.setPosition(0.0)
needleDevice.setMode(NeedleDevice.Mode.WASHING)
needleDevice.performWashing(5)
needleDevice.setPosition(10.0)
needleDevice.setMode(NeedleDevice.Mode.SAMPLING)
needleDevice.performSampling()
needleDevice.setPosition(0.0)
needleDevice.setMode(NeedleDevice.Mode.WASHING)
needleDevice.performWashing(5)
needleDevice.setPosition(20.0)
println("Игла в положении WOC")
}
// Рецепт 2 - Автоматическое измерение
suspend fun executeRecipe2() {
println("Выполнение Рецепта 2 - Автоматическое измерение")
transportationSystem.receiveMotor.setPosition(transportationSystem.receiveMotor.getPosition() + 1)
println("Сдвинуто податчик на 1 позицию")
// Проверка лотка
if (!checkTrayInPushSystem()) {
println("Лоток отсутствует. Повторный сдвиг")
transportationSystem.receiveMotor.setPosition(transportationSystem.receiveMotor.getPosition() + 1)
} else {
executeSampling()
}
// Если достигнута последняя позиция, меняем планшет
if (transportationSystem.receiveMotor.getPosition() >= transportationSystem.receiveMotor.maxPosition) {
println("Смена планшета. Возврат податчика в исходное положение")
transportationSystem.receiveMotor.setPosition(0)
}
println("Рецепт 2 завершен")
needleDevice.setPosition(0.0)
println("Игла вернулась в исходное положение")
}
// Рецепт 3 - Одиночное измерение
suspend fun executeRecipe3() {
println("Выполнение Рецепта 3 - Одиночное измерение")
executeSampling()
println("Рецепт 3 завершен")
needleDevice.setPosition(0.0)
println("Игла вернулась в исходное положение")
}
// функция проверки наличия лотка
private suspend fun checkTrayInPushSystem(): Boolean {
println("Проверка наличия лотка в системе проталкивания")
delay(200)
return true // Имитация наличия лотка
}
}
// -----------------------
// Тестирование анализатора
// -----------------------
class AnalyzerTest {
@Test
fun testAnalyzerInitialization() = runTest {
val context = Context("TestContext")
val analyzer = AnalyzerDevice(context)
analyzer.start()
// Проверка состояния устройств
assertEquals(LifecycleState.STARTED, analyzer.lifecycleState)
assertEquals(LifecycleState.STARTED, analyzer.transportationSystem.lifecycleState)
assertEquals(LifecycleState.STARTED, analyzer.shakerDevice.lifecycleState)
assertEquals(LifecycleState.STARTED, analyzer.needleDevice.lifecycleState)
// Проверка начальных положений двигателей
assertEquals(0, analyzer.transportationSystem.slideMotor.getPosition())
assertEquals(0, analyzer.transportationSystem.pushMotor.getPosition())
assertEquals(0, analyzer.transportationSystem.receiveMotor.getPosition())
assertEquals(0, analyzer.shakerDevice.verticalMotor.getPosition())
assertEquals(0, analyzer.shakerDevice.horizontalMotor.getPosition())
assertEquals(0.0, analyzer.needleDevice.getPosition())
// Проверка состояния клапанов
assertFalse(analyzer.valveV20.getState())
assertFalse(analyzer.valveV17.getState())
assertFalse(analyzer.valveV18.getState())
assertFalse(analyzer.valveV35.getState())
analyzer.stop()
assertEquals(LifecycleState.STOPPED, analyzer.lifecycleState)
}
@Test
fun testCalibration() = runTest {
val context = Context("TestContext")
val analyzer = AnalyzerDevice(context)
analyzer.start()
// Запуск калибровки
analyzer.calibrate()
// Проверка состояния двигателей после калибровки
assertEquals(0, analyzer.transportationSystem.slideMotor.getPosition())
assertEquals(0, analyzer.transportationSystem.pushMotor.getPosition())
assertEquals(0, analyzer.transportationSystem.receiveMotor.getPosition())
assertEquals(0, analyzer.shakerDevice.verticalMotor.getPosition())
assertEquals(0, analyzer.shakerDevice.horizontalMotor.getPosition())
// Проверка давления после калибровки
assertEquals(2.0, analyzer.pressureChamberHigh.getPressure())
assertEquals(-1.0, analyzer.pressureChamberLow.getPressure())
// Проверка состояния реагентных сенсоров
assertTrue(analyzer.reagentSensor1.checkReagent())
assertTrue(analyzer.reagentSensor2.checkReagent())
assertTrue(analyzer.reagentSensor3.checkReagent())
analyzer.stop()
}
@Test
fun testRecipe1() = runTest {
val context = Context("TestContext")
val analyzer = AnalyzerDevice(context)
analyzer.start()
// Выполнение рецепта 1 (подачи пробирки)
analyzer.executeRecipe1()
// Проверка конечных состояний после рецепта
assertEquals(1, analyzer.transportationSystem.slideMotor.getPosition())
assertEquals(1, analyzer.shakerDevice.verticalMotor.getPosition())
assertEquals(1, analyzer.shakerDevice.horizontalMotor.getPosition())
// Проверка положения иглы после забора пробы
assertEquals(0.0, analyzer.needleDevice.getPosition())
analyzer.stop()
}
@Test
fun testRecipe2() = runTest {
val context = Context("TestContext")
val analyzer = AnalyzerDevice(context)
analyzer.start()
// Выполнение рецепта 2 (автоматическое измерение)
analyzer.executeRecipe2()
// Проверка конечного положения двигателей
assertTrue(analyzer.transportationSystem.receiveMotor.getPosition() > 0)
// Проверка иглы после выполнения рецепта
assertEquals(0.0, analyzer.needleDevice.getPosition())
analyzer.stop()
}
@Test
fun testRecipe3() = runTest {
val context = Context("TestContext")
val analyzer = AnalyzerDevice(context)
analyzer.start()
// Выполнение рецепта 3 (одиночное измерение)
analyzer.executeRecipe3()
// Проверка иглы после одиночного измерения
assertEquals(0.0, analyzer.needleDevice.getPosition())
// Проверка завершения одиночного измерения
println("Одиночное измерение завершено")
analyzer.stop()
}
@Test
fun testDetailedMotorMovements() = runTest {
val context = Context("TestContext")
val analyzer = AnalyzerDevice(context)
analyzer.start()
// Проверка движения двигателей при выполнении задач
analyzer.transportationSystem.slideMotor.setPosition(2)
assertEquals(2, analyzer.transportationSystem.slideMotor.getPosition())
analyzer.shakerDevice.verticalMotor.setPosition(1)
analyzer.shakerDevice.horizontalMotor.setPosition(3)
assertEquals(1, analyzer.shakerDevice.verticalMotor.getPosition())
assertEquals(3, analyzer.shakerDevice.horizontalMotor.getPosition())
analyzer.stop()
}
@Test
fun testValveStates() = runTest {
val context = Context("TestContext")
val analyzer = AnalyzerDevice(context)
analyzer.start()
// Проверка работы клапанов
analyzer.valveV20.setState(true)
assertTrue(analyzer.valveV20.getState())
analyzer.valveV17.setState(false)
assertFalse(analyzer.valveV17.getState())
analyzer.valveV18.click() // Щелчок клапаном
assertFalse(analyzer.valveV18.getState())
analyzer.stop()
}
@Test
fun testSyringePumpOperations() = runTest {
val context = Context("TestContext")
val analyzer = AnalyzerDevice(context)
analyzer.start()
// Проверка работы шприцевого насоса
analyzer.syringePumpMA100.setVolume(0.05)
assertEquals(0.05, analyzer.syringePumpMA100.getVolume())
analyzer.syringePumpMA100.setVolume(0.0)
assertEquals(0.0, analyzer.syringePumpMA100.getVolume())
analyzer.syringePumpMA25.setVolume(2.5)
assertEquals(2.5, analyzer.syringePumpMA25.getVolume())
analyzer.stop()
}
@Test
fun testNeedleOperations() = runTest {
val context = Context("TestContext")
val analyzer = AnalyzerDevice(context)
analyzer.start()
// Проверка работы иглы в режиме промывки и забора проб
analyzer.needleDevice.setMode(NeedleDevice.Mode.WASHING)
analyzer.needleDevice.setPosition(0.0)
assertEquals(0.0, analyzer.needleDevice.getPosition())
assertEquals(NeedleDevice.Mode.WASHING, analyzer.needleDevice.getMode())
analyzer.needleDevice.performWashing(5) // Промывка иглы
analyzer.needleDevice.setMode(NeedleDevice.Mode.SAMPLING)
analyzer.needleDevice.setPosition(10.0)
assertEquals(10.0, analyzer.needleDevice.getPosition())
assertEquals(NeedleDevice.Mode.SAMPLING, analyzer.needleDevice.getMode())
analyzer.needleDevice.performSampling() // Забор пробы
analyzer.stop()
}
}

View File

@ -0,0 +1,182 @@
package space.kscience.controls.constructor
import kotlinx.coroutines.test.runTest
import kotlin.test.Test
import kotlin.test.assertEquals
import space.kscience.controls.api.*
import space.kscience.controls.spec.*
import space.kscience.dataforge.context.Context
import space.kscience.dataforge.meta.*
class CompositeDeviceTest {
// simple MotorDevice and MotorSpec
class MotorSpec : DeviceSpec<MotorDevice>() {
val speed by doubleProperty(
name = "speed",
read = { propertyName ->
getSpeed()
},
write = { propertyName, value ->
setSpeed(value)
}
)
val position by doubleProperty(
name = "position",
read = { propertyName ->
getPosition()
}
// Assuming position is read-only
)
val reset by unitAction(
name = "reset",
execute = {
resetMotor()
}
)
override fun createDevice(context: Context, meta: Meta): MotorDevice {
return MotorDevice(context, meta)
}
}
class MotorDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<MotorDevice>(MotorSpec(), context, meta) {
private var _speed: Double = 0.0
private var _position: Double = 0.0
suspend fun getSpeed(): Double = _speed
suspend fun setSpeed(value: Double) {
_speed = value
}
suspend fun getPosition(): Double = _position
suspend fun resetMotor() {
_speed = 0.0
_position = 0.0
}
override fun toString(): String = "MotorDevice"
}
data class Position(val base: Double, val elbow: Double, val wrist: Double)
object PositionConverter : MetaConverter<Position> {
override fun readOrNull(source: Meta): Position? {
val base = source["base"]?.value?.number?.toDouble() ?: return null
val elbow = source["elbow"]?.value?.number?.toDouble() ?: return null
val wrist = source["wrist"]?.value?.number?.toDouble() ?: return null
return Position(base, elbow, wrist)
}
override fun convert(obj: Position): Meta = Meta {
"base" put obj.base
"elbow" put obj.elbow
"wrist" put obj.wrist
}
}
object RobotArmSpec : DeviceSpec<RobotArmDevice>() {
val baseMotorSpec = MotorSpec()
val elbowMotorSpec = MotorSpec()
val wristMotorSpec = MotorSpec()
val baseMotor by device(baseMotorSpec)
val elbowMotor by device(elbowMotorSpec)
val wristMotor by device(wristMotorSpec)
val moveToPosition by action(
inputConverter = PositionConverter,
outputConverter = MetaConverter.unit,
name = "moveToPosition",
execute = { input ->
baseMotor.writeProperty("speed", Meta(input.base))
elbowMotor.writeProperty("speed", Meta(input.elbow))
wristMotor.writeProperty("speed", Meta(input.wrist))
}
)
override fun createDevice(context: Context, meta: Meta): RobotArmDevice {
return RobotArmDevice(context, meta)
}
}
class RobotArmDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<RobotArmDevice>(RobotArmSpec, context, meta) {
val baseMotor: MotorDevice get() = nestedDevices["baseMotor"] as MotorDevice
val elbowMotor: MotorDevice get() = nestedDevices["elbowMotor"] as MotorDevice
val wristMotor: MotorDevice get() = nestedDevices["wristMotor"] as MotorDevice
override suspend fun onStart() {
super.onStart()
}
override suspend fun onStop() {
super.onStop()
}
override fun toString(): String = "RobotArmDevice"
}
@Test
fun testNestedDeviceInitialization() = runTest {
val context = Context("TestContext")
val robotArm = RobotArmDevice(context)
// Start the robot arm device
robotArm.start()
// Check that all motors are started
assertEquals(LifecycleState.STARTED, robotArm.baseMotor.lifecycleState)
assertEquals(LifecycleState.STARTED, robotArm.elbowMotor.lifecycleState)
assertEquals(LifecycleState.STARTED, robotArm.wristMotor.lifecycleState)
// Stop the robot arm device
robotArm.stop()
}
@Test
fun testCompositeDevicePropertyAndActionAccess() = runTest {
val context = Context("TestContext")
val robotArm = RobotArmDevice(context)
robotArm.start()
robotArm.baseMotor.writeProperty("speed", Meta(500.0))
val speedMeta = robotArm.baseMotor.getProperty("speed")
val speed = speedMeta?.value?.number?.toDouble()
assertEquals(500.0, speed)
// Stop the robot arm device
robotArm.stop()
}
@Test
fun testCompositeDeviceLifecycleManagement() = runTest {
val context = Context("TestContext")
val robotArm = RobotArmDevice(context)
// Start the robot arm device
robotArm.start()
assertEquals(LifecycleState.STARTED, robotArm.lifecycleState)
assertEquals(LifecycleState.STARTED, robotArm.baseMotor.lifecycleState)
assertEquals(LifecycleState.STARTED, robotArm.elbowMotor.lifecycleState)
assertEquals(LifecycleState.STARTED, robotArm.wristMotor.lifecycleState)
// Stop the robot arm device
robotArm.stop()
assertEquals(LifecycleState.STOPPED, robotArm.lifecycleState)
assertEquals(LifecycleState.STOPPED, robotArm.baseMotor.lifecycleState)
assertEquals(LifecycleState.STOPPED, robotArm.elbowMotor.lifecycleState)
assertEquals(LifecycleState.STOPPED, robotArm.wristMotor.lifecycleState)
}
}

View File

@ -0,0 +1,168 @@
package space.kscience.controls.constructor
import kotlin.test.Test
import kotlin.test.assertEquals
import kotlin.test.assertFailsWith
import kotlinx.coroutines.test.runTest
import space.kscience.controls.api.LifecycleState
import space.kscience.controls.spec.DeviceActionSpec
import space.kscience.controls.spec.DeviceBase
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.controls.spec.unitAction
import space.kscience.controls.spec.validate
import space.kscience.dataforge.context.Context
import space.kscience.dataforge.meta.Meta
import space.kscience.dataforge.meta.number
class DeviceSpecTest {
class MotorSpec : DeviceSpec<MotorDevice>() {
val speed by doubleProperty(
name = "speed",
read = { propertyName ->
getSpeed()
},
write = { propertyName, value ->
setSpeed(value)
}
)
val position by doubleProperty(
name = "position",
read = { propertyName ->
getPosition()
}
// Assuming position is read-only
)
val reset by unitAction(
name = "reset",
execute = {
resetMotor()
}
)
}
class MotorDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<MotorDevice>(MotorSpec(), context, meta) {
private var _speed: Double = 0.0
private var _position: Double = 0.0
suspend fun getSpeed(): Double = _speed
suspend fun setSpeed(value: Double) {
_speed = value
}
suspend fun getPosition(): Double = _position
suspend fun resetMotor() {
_speed = 0.0
_position = 0.0
}
override fun toString(): String = "MotorDevice"
}
@Test
fun testDevicePropertyDefinitionAndAccess() = runTest {
val context = Context("TestContext")
val motor = MotorDevice(context)
motor.start()
val speedMeta = Meta(1000.0)
motor.writeProperty("speed", speedMeta)
val speedMetaRead = motor.readProperty("speed")
val speed = speedMetaRead.value?.number?.toDouble()
assertEquals(1000.0, speed)
val positionMeta = motor.readProperty("position")
val position = positionMeta.value?.number?.toDouble()
assertEquals(0.0, position)
motor.stop()
}
@Test
fun testDeviceActionDefinitionAndExecution() = runTest {
val context = Context("TestContext")
val motor = MotorDevice(context)
motor.start()
val speedMeta = Meta(1000.0)
motor.writeProperty("speed", speedMeta)
motor.execute("reset", Meta.EMPTY)
val speedMetaRead = motor.readProperty("speed")
val speed = speedMetaRead.value?.number?.toDouble()
assertEquals(0.0, speed)
val positionMeta = motor.readProperty("position")
val position = positionMeta.value?.number?.toDouble()
assertEquals(0.0, position)
motor.stop()
}
@Test
fun testDeviceLifecycleManagement() = runTest {
val context = Context("TestContext")
val motor = MotorDevice(context)
assertEquals(LifecycleState.STOPPED, motor.lifecycleState)
motor.start()
assertEquals(LifecycleState.STARTED, motor.lifecycleState)
motor.stop()
assertEquals(LifecycleState.STOPPED, motor.lifecycleState)
}
@Test
fun testDeviceErrorHandling() = runTest {
val context = Context("TestContext")
val motor = MotorDevice(context)
motor.start()
assertFailsWith<IllegalStateException> {
motor.readProperty("nonExistentProperty")
}
assertFailsWith<IllegalStateException> {
motor.execute("nonExistentAction", Meta.EMPTY)
}
motor.stop()
}
@Test
fun testDeviceSpecValidation() = runTest {
val context = Context("TestContext")
val motor = MotorDevice(context)
motor.spec.validate(motor)
val invalidMotor = object : DeviceBase<MotorDevice>(context, Meta.EMPTY) {
override val properties: Map<String, DevicePropertySpec<MotorDevice, *>>
get() = emptyMap()
override val actions: Map<String, DeviceActionSpec<MotorDevice, *, *>>
get() = emptyMap()
override fun toString(): String = "InvalidMotorDevice"
}
// Expect validation to fail
assertFailsWith<IllegalStateException> {
motor.spec.validate(invalidMotor)
}
}
}

View File

@ -0,0 +1,76 @@
package space.kscience.controls.constructor
import kotlin.test.Test
import kotlin.test.assertEquals
import kotlinx.coroutines.test.runTest
import space.kscience.controls.constructor.CompositeDeviceTest.Position
import space.kscience.controls.constructor.CompositeDeviceTest.PositionConverter
import space.kscience.controls.constructor.CompositeDeviceTest.RobotArmDevice
import space.kscience.controls.spec.*
import space.kscience.dataforge.context.Context
import space.kscience.dataforge.meta.Meta
import space.kscience.dataforge.meta.number
class IntegrationTest {
@Test
fun testFullDeviceSimulation() = runTest {
val context = Context("TestContext")
val robotArm = RobotArmDevice(context)
robotArm.start()
val position = Position(base = 90.0, elbow = 45.0, wrist = 30.0)
robotArm.execute("moveToPosition", PositionConverter.convert(position))
val baseSpeedMeta = robotArm.baseMotor.readProperty("speed")
val baseSpeed = baseSpeedMeta.value?.number?.toDouble()
assertEquals(90.0, baseSpeed)
val elbowSpeedMeta = robotArm.elbowMotor.readProperty("speed")
val elbowSpeed = elbowSpeedMeta.value?.number?.toDouble()
assertEquals(45.0, elbowSpeed)
val wristSpeedMeta = robotArm.wristMotor.readProperty("speed")
val wristSpeed = wristSpeedMeta.value?.number?.toDouble()
assertEquals(30.0, wristSpeed)
robotArm.stop()
}
class SensorDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<SensorDevice>(SensorSpec, context, meta) {
private var _pressure: Double = 101325.0 // Atmospheric pressure in Pascals
suspend fun getPressure(): Double = _pressure
override fun toString(): String = "SensorDevice"
}
object SensorSpec : DeviceSpec<SensorDevice>() {
val pressure by doubleProperty(
name = "pressure",
read = { propertyName ->
getPressure()
}
)
}
@Test
fun testUnitsInDeviceProperties() = runTest {
val context = Context("TestContext")
val sensor = SensorDevice(context)
sensor.start()
val pressureMeta = sensor.readProperty("pressure")
val pressureValue = pressureMeta.value?.number?.toDouble()
assertEquals(101325.0, pressureValue)
sensor.stop()
}
}

View File

@ -0,0 +1,18 @@
package space.kscience.controls.constructor
import space.kscience.controls.constructor.units.Degrees
import space.kscience.controls.constructor.units.Meters
import space.kscience.controls.constructor.units.NumericalValue
import space.kscience.controls.constructor.units.Radians
import space.kscience.controls.constructor.units.SIPrefix
import space.kscience.controls.constructor.units.Seconds
import space.kscience.controls.constructor.units.UnitsOfMeasurement
import space.kscience.controls.constructor.units.withPrefix
import kotlin.math.PI
import kotlin.test.Test
import kotlin.test.assertEquals
import kotlin.test.assertFailsWith
class UnitsOfMeasurementTest {
}

View File

@ -0,0 +1,88 @@
package space.kscience.controls.constructor
import kotlin.test.Test
import kotlin.test.assertEquals
import kotlinx.coroutines.test.runTest
import space.kscience.controls.spec.*
import space.kscience.dataforge.context.Context
import space.kscience.dataforge.meta.Meta
import space.kscience.dataforge.meta.boolean
import space.kscience.dataforge.meta.number
class UtilitiesTest {
class SensorSpec : DeviceSpec<SensorDevice>() {
val temperature by doubleProperty(
name = "temperature",
read = { propertyName ->
getTemperature()
},
write = { propertyName, value ->
setTemperature(value)
}
)
val isActive by booleanProperty(
name = "isActive",
read = { propertyName ->
isActive()
},
write = { propertyName, value ->
setActive(value)
}
)
}
class SensorDevice(
context: Context,
meta: Meta = Meta.EMPTY
) : DeviceBySpec<SensorDevice>(SensorSpec(), context, meta) {
private var _temperature: Double = 25.0
private var _isActive: Boolean = true
suspend fun getTemperature(): Double = _temperature
suspend fun setTemperature(value: Double) {
_temperature = value
}
suspend fun isActive(): Boolean = _isActive
suspend fun setActive(value: Boolean) {
_isActive = value
}
override fun toString(): String = "SensorDevice"
}
@Test
fun testDoublePropertyUtility() = runTest {
val context = Context("TestContext")
val sensor = SensorDevice(context)
sensor.start()
sensor.writeProperty("temperature", Meta(30.0))
val tempMeta = sensor.readProperty("temperature")
val temperature = tempMeta.value?.number?.toDouble()
assertEquals(30.0, temperature)
sensor.stop()
}
@Test
fun testBooleanPropertyUtility() = runTest {
val context = Context("TestContext")
val sensor = SensorDevice(context)
sensor.start()
sensor.writeProperty("isActive", Meta(false))
val activeMeta = sensor.readProperty("isActive")
val isActive = activeMeta.value?.boolean
assertEquals(false, isActive)
sensor.stop()
}
}

View File

@ -50,6 +50,13 @@ public abstract class DeviceBase<D : Device>(
final override val meta: Meta = Meta.EMPTY, final override val meta: Meta = Meta.EMPTY,
) : CachingDevice { ) : CachingDevice {
private val stateLock = Mutex()
/**
* Logical state store
*/
private val logicalState: MutableMap<String, Meta?> = HashMap()
/** /**
* Collection of property specifications * Collection of property specifications
*/ */
@ -89,20 +96,12 @@ public abstract class DeviceBase<D : Device>(
} }
) )
/**
* Logical state store
*/
private val logicalState: HashMap<String, Meta?> = HashMap()
public override val messageFlow: SharedFlow<DeviceMessage> get() = sharedMessageFlow public override val messageFlow: SharedFlow<DeviceMessage> get() = sharedMessageFlow
@Suppress("UNCHECKED_CAST") @Suppress("UNCHECKED_CAST")
internal val self: D internal val self: D
get() = this as D get() = this as D
private val stateLock = Mutex()
/** /**
* Update logical property state and notify listeners * Update logical property state and notify listeners
*/ */

View File

@ -2,7 +2,7 @@ package space.kscience.controls.spec
import space.kscience.controls.api.Device import space.kscience.controls.api.Device
import space.kscience.dataforge.context.Context import space.kscience.dataforge.context.Context
import space.kscience.dataforge.meta.Meta import space.kscience.dataforge.meta.*
/** /**
* A device generated from specification * A device generated from specification
@ -16,14 +16,36 @@ 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
// Map to store instances of nested devices
private val _nestedDevices = hashMapOf<String, Device>()
// Provide access to nested devices
public val nestedDevices: Map<String, Device> get() = _nestedDevices
override suspend fun onStart(): Unit = with(spec) { override suspend fun onStart(): Unit = with(spec) {
for ((name, deviceSpec) in spec.nestedDeviceSpecs) {
val nestedDevice = createNestedDevice(deviceSpec, name)
_nestedDevices[name] = nestedDevice
nestedDevice.start()
}
self.onOpen() self.onOpen()
} }
override suspend fun onStop(): Unit = with(spec){ override suspend fun onStop(): Unit = with(spec){
for (device in _nestedDevices.values) {
device.stop()
}
self.onClose() self.onClose()
} }
override fun toString(): String = "Device(spec=$spec)" override fun toString(): String = "Device(spec=$spec)"
private fun <ND : Device> createNestedDevice(deviceSpec: DeviceSpec<ND>, name: String): ND {
// Create an instance of the nested device.
val nestedMeta = meta[name] ?: Meta.EMPTY
val nestedDevice = deviceSpec.createDevice(context, nestedMeta)
return nestedDevice
}
} }

View File

@ -2,6 +2,7 @@ package space.kscience.controls.spec
import kotlinx.coroutines.withContext import kotlinx.coroutines.withContext
import space.kscience.controls.api.* import space.kscience.controls.api.*
import space.kscience.dataforge.context.Context
import space.kscience.dataforge.meta.Meta import space.kscience.dataforge.meta.Meta
import space.kscience.dataforge.meta.MetaConverter import space.kscience.dataforge.meta.MetaConverter
import space.kscience.dataforge.meta.descriptors.MetaDescriptor import space.kscience.dataforge.meta.descriptors.MetaDescriptor
@ -20,15 +21,34 @@ public val MetaConverter.Companion.unit: MetaConverter<Unit> get() = UnitMetaCon
@OptIn(InternalDeviceAPI::class) @OptIn(InternalDeviceAPI::class)
public abstract class DeviceSpec<D : Device> { public abstract class DeviceSpec<D : Device> {
//initializing the metadata property for everyone // Map to store properties
private val _properties = hashMapOf<String, DevicePropertySpec<D, *>>( private val _properties = hashMapOf<String, DevicePropertySpec<D, *>>()
DeviceMetaPropertySpec.name to DeviceMetaPropertySpec
)
public val properties: Map<String, DevicePropertySpec<D, *>> get() = _properties public val properties: Map<String, DevicePropertySpec<D, *>> get() = _properties
private val _actions = HashMap<String, DeviceActionSpec<D, *, *>>() // Map to store actions
private val _actions = hashMapOf<String, DeviceActionSpec<D, *, *>>()
public val actions: Map<String, DeviceActionSpec<D, *, *>> get() = _actions public val actions: Map<String, DeviceActionSpec<D, *, *>> get() = _actions
/**
* Registers a property in the spec.
*/
public fun <T, P : DevicePropertySpec<D, T>> registerProperty(deviceProperty: P): P {
_properties[deviceProperty.name] = deviceProperty
return deviceProperty
}
// Map to store nested device specifications
private val _nestedDeviceSpecs = hashMapOf<String, DeviceSpec<*>>()
public val nestedDeviceSpecs: Map<String, DeviceSpec<*>> get() = _nestedDeviceSpecs
/**
* Registers an action in the spec.
*/
public fun <I, O> registerAction(deviceAction: DeviceActionSpec<D, I, O>): DeviceActionSpec<D, I, O> {
_actions[deviceAction.name] = deviceAction
return deviceAction
}
public open suspend fun D.onOpen() { public open suspend fun D.onOpen() {
} }
@ -36,12 +56,6 @@ public abstract class DeviceSpec<D : Device> {
public open suspend fun D.onClose() { public open suspend fun D.onClose() {
} }
public fun <T, P : DevicePropertySpec<D, T>> registerProperty(deviceProperty: P): P {
_properties[deviceProperty.name] = deviceProperty
return deviceProperty
}
public fun <T> property( public fun <T> property(
converter: MetaConverter<T>, converter: MetaConverter<T>,
descriptorBuilder: PropertyDescriptor.() -> Unit = {}, descriptorBuilder: PropertyDescriptor.() -> Unit = {},
@ -110,12 +124,6 @@ public abstract class DeviceSpec<D : Device> {
} }
} }
public fun <I, O> registerAction(deviceAction: DeviceActionSpec<D, I, O>): DeviceActionSpec<D, I, O> {
_actions[deviceAction.name] = deviceAction
return deviceAction
}
public fun <I, O> action( public fun <I, O> action(
inputConverter: MetaConverter<I>, inputConverter: MetaConverter<I>,
outputConverter: MetaConverter<O>, outputConverter: MetaConverter<O>,
@ -156,6 +164,24 @@ public abstract class DeviceSpec<D : Device> {
deviceAction deviceAction
} }
} }
public open fun createDevice(context: Context, meta: Meta): D {
// Since DeviceSpec<D> doesn't know how to create an instance of D,
// you need to override this method in subclasses.
throw NotImplementedError("createDevice must be implemented in subclasses")
}
public fun <ND : Device> device(
deviceSpec: DeviceSpec<ND>,
name: String? = null
): PropertyDelegateProvider<DeviceSpec<D>, ReadOnlyProperty<DeviceSpec<D>, DeviceSpec<ND>>> =
PropertyDelegateProvider { _, property ->
val deviceName = name ?: property.name
// Register the nested device spec
_nestedDeviceSpecs[deviceName] = deviceSpec
ReadOnlyProperty { _, _ -> deviceSpec }
}
} }
/** /**

View File

@ -6,6 +6,8 @@ import space.kscience.controls.api.metaDescriptor
import space.kscience.dataforge.meta.Meta import space.kscience.dataforge.meta.Meta
import space.kscience.dataforge.meta.MetaConverter import space.kscience.dataforge.meta.MetaConverter
import space.kscience.dataforge.meta.ValueType import space.kscience.dataforge.meta.ValueType
import space.kscience.dataforge.meta.descriptors.MetaDescriptor
import space.kscience.dataforge.meta.string
import kotlin.properties.PropertyDelegateProvider import kotlin.properties.PropertyDelegateProvider
import kotlin.properties.ReadOnlyProperty import kotlin.properties.ReadOnlyProperty
import kotlin.reflect.KMutableProperty1 import kotlin.reflect.KMutableProperty1
@ -192,3 +194,122 @@ public fun <D : Device> DeviceSpec<D>.metaProperty(
write: suspend D.(propertyName: String, value: Meta) -> Unit write: suspend D.(propertyName: String, value: Meta) -> Unit
): PropertyDelegateProvider<DeviceSpec<D>, ReadOnlyProperty<DeviceSpec<D>, MutableDevicePropertySpec<D, Meta>>> = ): PropertyDelegateProvider<DeviceSpec<D>, ReadOnlyProperty<DeviceSpec<D>, MutableDevicePropertySpec<D, Meta>>> =
mutableProperty(MetaConverter.meta, descriptorBuilder, name, read, write) mutableProperty(MetaConverter.meta, descriptorBuilder, name, read, write)
public fun <D : Device> DeviceSpec<D>.doubleProperty(
description: String? = null,
name: String? = null,
read: suspend D.(String) -> Double?,
write: (suspend D.(String, Double) -> Unit)? = null
): PropertyDelegateProvider<DeviceSpec<D>, ReadOnlyProperty<DeviceSpec<D>, DevicePropertySpec<D, Double>>> {
val converter = MetaConverter.double
val descriptorBuilder: PropertyDescriptor.() -> Unit = {
this.description = description
metaDescriptor {
valueType(ValueType.NUMBER)
}
}
return if (write != null) {
mutableProperty(converter, descriptorBuilder, name, read, write)
} else {
property(converter, descriptorBuilder, name, read)
}
}
public fun <D : Device> DeviceSpec<D>.booleanProperty(
description: String? = null,
name: String? = null,
read: suspend D.(String) -> Boolean?,
write: (suspend D.(String, Boolean) -> Unit)? = null
): PropertyDelegateProvider<DeviceSpec<D>, ReadOnlyProperty<DeviceSpec<D>, DevicePropertySpec<D, Boolean>>> {
val converter = MetaConverter.boolean
val descriptorBuilder: PropertyDescriptor.() -> Unit = {
this.description = description
metaDescriptor {
valueType(ValueType.BOOLEAN)
}
}
return if (write != null) {
mutableProperty(converter, descriptorBuilder, name, read, write)
} else {
property(converter, descriptorBuilder, name, read)
}
}
public fun <D : Device> DeviceSpec<D>.stringProperty(
description: String? = null,
name: String? = null,
read: suspend D.(String) -> String?,
write: (suspend D.(String, String) -> Unit)? = null
): PropertyDelegateProvider<DeviceSpec<D>, ReadOnlyProperty<DeviceSpec<D>, DevicePropertySpec<D, String>>> {
val converter = MetaConverter.string
val descriptorBuilder: PropertyDescriptor.() -> Unit = {
this.description = description
metaDescriptor {
valueType(ValueType.STRING)
}
}
return if (write != null) {
mutableProperty(converter, descriptorBuilder, name, read, write)
} else {
property(converter, descriptorBuilder, name, read)
}
}
public fun <D : Device> DeviceSpec<D>.intProperty(
description: String? = null,
name: String? = null,
read: suspend D.(propertyName: String) -> Int?,
write: (suspend D.(propertyName: String, value: Int) -> Unit)? = null
): PropertyDelegateProvider<DeviceSpec<D>, ReadOnlyProperty<DeviceSpec<D>, DevicePropertySpec<D, Int>>> {
val converter = MetaConverter.int
val descriptorBuilder: PropertyDescriptor.() -> Unit = {
this.description = description
metaDescriptor {
valueType(ValueType.NUMBER)
}
}
return if (write != null) {
mutableProperty(converter, descriptorBuilder, name, read, write)
} else {
property(converter, descriptorBuilder, name, read)
}
}
public fun <E : Enum<E>, D : Device> DeviceSpec<D>.enumProperty(
enumValues: Array<E>,
descriptorBuilder: PropertyDescriptor.() -> Unit = {},
name: String? = null,
read: suspend D.(propertyName: String) -> E?,
write: (suspend D.(propertyName: String, value: E) -> Unit)? = null
): PropertyDelegateProvider<DeviceSpec<D>, ReadOnlyProperty<DeviceSpec<D>, DevicePropertySpec<D, E>>> {
val converter = object : MetaConverter<E> {
override val descriptor: MetaDescriptor = MetaDescriptor {
valueType(ValueType.STRING)
allowedValues(enumValues.map { it.name })
}
override fun readOrNull(source: Meta): E? {
val value = source.string ?: return null
return enumValues.firstOrNull { it.name == value }
}
override fun convert(obj: E): Meta = Meta(obj.name)
}
return if (write != null) {
mutableProperty(
converter = converter,
descriptorBuilder = descriptorBuilder,
name = name,
read = read,
write = write
)
} else {
property(
converter = converter,
descriptorBuilder = descriptorBuilder,
name = name,
read = read
)
}
}