#[cfg(feature = "serde")]
use serde::{Deserialize, Serialize};
use crate::protocol::{Description, Units, Value};
use crate::utils::{Buildable, Builder};
#[derive(Debug, Clone, Default)]
#[cfg_attr(feature = "specta", derive(specta::Type))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct EnumEntryMavCmdParam {
index: u8,
description: Description,
label: Option<String>,
units: Option<Units>,
r#enum: Option<String>,
decimal_places: Option<u8>,
increment: Option<Value>,
min_value: Option<Value>,
max_value: Option<Value>,
reserved: bool,
default: Option<Value>,
}
impl Buildable for EnumEntryMavCmdParam {
type Builder = EnumEntryMavCmdParamBuilder;
fn to_builder(&self) -> EnumEntryMavCmdParamBuilder {
EnumEntryMavCmdParamBuilder(self.clone())
}
}
impl EnumEntryMavCmdParam {
pub fn builder() -> EnumEntryMavCmdParamBuilder {
EnumEntryMavCmdParamBuilder::new()
}
pub fn index(&self) -> u8 {
self.index
}
pub fn description(&self) -> &str {
self.description.as_str()
}
pub fn label(&self) -> Option<&str> {
self.label.as_deref()
}
pub fn units(&self) -> Option<&Units> {
self.units.as_ref()
}
pub fn r#enum(&self) -> Option<&str> {
self.r#enum.as_deref()
}
pub fn decimal_places(&self) -> Option<u8> {
self.decimal_places
}
pub fn increment(&self) -> Option<&Value> {
self.increment.as_ref()
}
pub fn min_value(&self) -> Option<&Value> {
self.min_value.as_ref()
}
pub fn max_value(&self) -> Option<&Value> {
self.max_value.as_ref()
}
pub fn reserved(&self) -> bool {
self.reserved
}
pub fn default(&self) -> Option<&Value> {
self.default.as_ref()
}
}
#[derive(Debug, Clone, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct EnumEntryMavCmdParamBuilder(EnumEntryMavCmdParam);
impl Builder for EnumEntryMavCmdParamBuilder {
type Buildable = EnumEntryMavCmdParam;
fn build(&self) -> EnumEntryMavCmdParam {
#[allow(clippy::match_single_binding)]
match self.0.clone() {
EnumEntryMavCmdParam {
index,
description,
label,
units,
r#enum,
decimal_places,
increment,
min_value,
max_value,
reserved,
default,
} => EnumEntryMavCmdParam {
index,
description,
label,
units,
r#enum,
decimal_places,
increment,
min_value,
max_value,
reserved,
default,
},
}
}
}
impl EnumEntryMavCmdParamBuilder {
pub fn new() -> Self {
Self::default()
}
pub fn set_index(&mut self, index: u8) -> &mut Self {
self.0.index = index;
self
}
pub fn set_description(&mut self, description: impl AsRef<str>) -> &mut Self {
self.0.description = Description::new(description);
self
}
pub fn set_label(&mut self, label: Option<impl AsRef<str>>) -> &mut Self {
self.0.label = label.map(|s| s.as_ref().to_string());
self
}
pub fn set_units(&mut self, units: Option<Units>) -> &mut Self {
self.0.units = units;
self
}
pub fn set_enum(&mut self, r#enum: Option<impl AsRef<str>>) -> &mut Self {
self.0.r#enum = r#enum.map(|s| s.as_ref().to_string());
self
}
pub fn set_decimal_places(&mut self, decimal_places: Option<u8>) -> &mut Self {
self.0.decimal_places = decimal_places;
self
}
pub fn set_increment(&mut self, increment: Option<Value>) -> &mut Self {
self.0.increment = increment;
self
}
pub fn set_min_value(&mut self, min_value: Option<Value>) -> &mut Self {
self.0.min_value = min_value;
self
}
pub fn set_max_value(&mut self, max_value: Option<Value>) -> &mut Self {
self.0.max_value = max_value;
self
}
pub fn set_reserved(&mut self, reserved: bool) -> &mut Self {
self.0.reserved = reserved;
self
}
pub fn set_default(&mut self, default: Option<Value>) -> &mut Self {
self.0.default = default;
self
}
}
#[cfg(test)]
mod tests {
use super::*;
#[test]
fn enum_entry_builder() {
let param = EnumEntryMavCmdParam::builder()
.set_index(3)
.set_description("description")
.set_label(Some("label".to_string()))
.set_units(Some(Units::Ampere))
.set_enum(Some("enum".to_string()))
.set_decimal_places(Some(5))
.set_increment(Some(Value::UInt16(10)))
.set_min_value(Some(Value::UInt16(100)))
.set_max_value(Some(Value::UInt16(u16::MAX)))
.set_reserved(true)
.set_default(Some(Value::UInt16(1000)))
.build();
assert!(matches!(param, EnumEntryMavCmdParam { .. }));
assert_eq!(param.index(), 3);
assert_eq!(param.description(), "description");
assert_eq!(param.label().unwrap(), "label");
assert!(matches!(param.units(), Some(Units::Ampere)));
assert_eq!(param.r#enum().unwrap(), "enum");
assert!(matches!(param.decimal_places(), Some(5)));
assert!(matches!(param.increment(), Some(Value::UInt16(10))));
assert!(matches!(param.min_value(), Some(Value::UInt16(100))));
assert!(matches!(param.max_value(), Some(Value::UInt16(u16::MAX))));
assert!(param.reserved());
assert!(matches!(param.default(), Some(Value::UInt16(1000))));
}
}