use std::borrow::Cow;
use serde::{Deserialize, Serialize};
use super::geometry_msgs;
use super::std_msgs::Header;
#[derive(Debug, Serialize, Deserialize)]
pub struct Image<'a> {
pub header: Header,
pub height: u32,
pub width: u32,
pub encoding: String,
pub is_bigendian: u8,
pub step: u32,
#[serde(with = "serde_bytes")]
#[serde(borrow)]
pub data: Cow<'a, [u8]>,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct CompressedImage<'a> {
pub header: Header,
pub format: String,
#[serde(with = "serde_bytes")]
#[serde(borrow)]
pub data: Cow<'a, [u8]>,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct Imu {
pub header: Header,
pub orientation: geometry_msgs::Quaternion,
pub orientation_covariance: [f64; 9],
pub angular_velocity: geometry_msgs::Vector3,
pub angular_velocity_covariance: [f64; 9],
pub linear_acceleration: geometry_msgs::Vector3,
pub linear_acceleration_covariance: [f64; 9],
}
#[derive(Copy, Clone, Debug, Serialize, Deserialize)]
#[serde(try_from = "u8", into = "u8")]
#[repr(u8)]
pub enum PointFieldDatatype {
Int8 = 1,
UInt8 = 2,
Int16 = 3,
UInt16 = 4,
Int32 = 5,
UInt32 = 6,
Float32 = 7,
Float64 = 8,
}
#[derive(Debug, thiserror::Error)]
#[error("unknown point field datatype: {0}")]
pub struct UnknownPointFieldDatatype(u8);
impl TryFrom<u8> for PointFieldDatatype {
type Error = UnknownPointFieldDatatype;
fn try_from(value: u8) -> Result<Self, Self::Error> {
Ok(match value {
1 => Self::Int8,
2 => Self::UInt8,
3 => Self::Int16,
4 => Self::UInt16,
5 => Self::Int32,
6 => Self::UInt32,
7 => Self::Float32,
8 => Self::Float64,
other => Err(UnknownPointFieldDatatype(other))?,
})
}
}
impl From<PointFieldDatatype> for u8 {
fn from(datatype: PointFieldDatatype) -> Self {
datatype as Self
}
}
#[derive(Debug, Serialize, Deserialize)]
pub struct PointField {
pub name: String,
pub offset: u32,
pub datatype: PointFieldDatatype,
pub count: u32,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct PointCloud2 {
pub header: Header,
pub height: u32,
pub width: u32,
pub fields: Vec<PointField>,
pub is_bigendian: bool,
pub point_step: u32,
pub row_step: u32,
pub data: Vec<u8>,
pub is_dense: bool,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct RegionOfInterest {
pub x_offset: u32,
pub y_offset: u32,
pub height: u32,
pub width: u32,
pub do_rectify: bool,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct CameraInfo {
pub header: Header,
pub height: u32,
pub width: u32,
pub distortion_model: String,
pub d: Vec<f64>,
pub k: [f64; 9],
pub r: [f64; 9],
pub p: [f64; 12],
pub binning_x: u32,
pub binning_y: u32,
pub roi: RegionOfInterest,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct JointState {
pub header: Header,
pub name: Vec<String>,
pub position: Vec<f64>,
pub velocity: Vec<f64>,
pub effort: Vec<f64>,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct NavSatStatus {
pub status: NavSatFixStatus,
pub service: NavSatService,
}
#[derive(Copy, Clone, Debug, Serialize, Deserialize)]
#[serde(from = "i8", into = "i8")]
#[repr(i8)]
pub enum NavSatFixStatus {
Unknown = -2,
NoFix = -1,
Fix = 0,
SbasFix = 1,
GbasFix = 2,
}
impl From<i8> for NavSatFixStatus {
fn from(value: i8) -> Self {
match value {
-1 => Self::NoFix,
0 => Self::Fix,
1 => Self::SbasFix,
2 => Self::GbasFix,
_ => Self::Unknown,
}
}
}
impl From<NavSatFixStatus> for i8 {
fn from(status: NavSatFixStatus) -> Self {
status as Self
}
}
#[derive(Copy, Clone, Debug, Serialize, Deserialize)]
#[serde(from = "u16", into = "u16")]
#[repr(u16)]
pub enum NavSatService {
Unknown = 0,
Gps = 1,
Glonass = 2,
Compass = 4,
Galileo = 8,
}
impl From<u16> for NavSatService {
fn from(value: u16) -> Self {
match value {
1 => Self::Gps,
2 => Self::Glonass,
4 => Self::Compass,
8 => Self::Galileo,
_ => Self::Unknown,
}
}
}
impl From<NavSatService> for u16 {
fn from(service: NavSatService) -> Self {
service as Self
}
}
#[derive(Copy, Clone, Debug, Serialize, Deserialize)]
#[serde(from = "u8", into = "u8")]
#[repr(u8)]
pub enum CovarianceType {
Unknown = 0,
Approximated = 1,
DiagonalKnown = 2,
Known = 3,
}
impl From<u8> for CovarianceType {
fn from(value: u8) -> Self {
match value {
1 => Self::Approximated,
2 => Self::DiagonalKnown,
3 => Self::Known,
_ => Self::Unknown,
}
}
}
impl From<CovarianceType> for u8 {
fn from(cov_type: CovarianceType) -> Self {
cov_type as Self
}
}
#[derive(Debug, Serialize, Deserialize)]
pub struct NavSatFix {
pub header: Header,
pub status: NavSatStatus,
pub latitude: f64,
pub longitude: f64,
pub altitude: f64,
pub position_covariance: [f64; 9],
pub position_covariance_type: CovarianceType,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct Temperature {
pub header: Header,
pub temperature: f64,
pub variance: f64,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct FluidPressure {
pub header: Header,
pub fluid_pressure: f64,
pub variance: f64,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct RelativeHumidity {
pub header: Header,
pub humidity: f64,
pub variance: f64,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct Illuminance {
pub header: Header,
pub illuminance: f64,
pub variance: f64,
}
#[derive(Copy, Clone, Debug, Serialize, Deserialize)]
#[serde(from = "u8", into = "u8")]
#[repr(u8)]
pub enum RadiationType {
Ultrasound = 0,
Infrared = 1,
}
impl From<u8> for RadiationType {
fn from(value: u8) -> Self {
match value {
1 => Self::Infrared,
_ => Self::Ultrasound,
}
}
}
impl From<RadiationType> for u8 {
fn from(radiation_type: RadiationType) -> Self {
radiation_type as Self
}
}
#[derive(Debug, Serialize, Deserialize)]
pub struct Range {
pub header: Header,
pub radiation_type: RadiationType,
pub field_of_view: f32,
pub min_range: f32,
pub max_range: f32,
pub range: f32,
}
#[derive(Copy, Clone, Debug, Serialize, Deserialize)]
#[serde(from = "u8", into = "u8")]
#[repr(u8)]
pub enum PowerSupplyStatus {
Unknown = 0,
Charging = 1,
Discharging = 2,
NotCharging = 3,
Full = 4,
}
impl From<u8> for PowerSupplyStatus {
fn from(value: u8) -> Self {
match value {
1 => Self::Charging,
2 => Self::Discharging,
3 => Self::NotCharging,
4 => Self::Full,
_ => Self::Unknown,
}
}
}
impl From<PowerSupplyStatus> for u8 {
fn from(status: PowerSupplyStatus) -> Self {
status as Self
}
}
#[derive(Copy, Clone, Debug, Serialize, Deserialize)]
#[serde(from = "u8", into = "u8")]
#[repr(u8)]
pub enum PowerSupplyHealth {
Unknown = 0,
Good = 1,
Overheat = 2,
Dead = 3,
Overvoltage = 4,
UnspecFailure = 5,
Cold = 6,
WatchdogTimerExpire = 7,
SafetyTimerExpire = 8,
}
impl From<u8> for PowerSupplyHealth {
fn from(value: u8) -> Self {
match value {
1 => Self::Good,
2 => Self::Overheat,
3 => Self::Dead,
4 => Self::Overvoltage,
5 => Self::UnspecFailure,
6 => Self::Cold,
7 => Self::WatchdogTimerExpire,
8 => Self::SafetyTimerExpire,
_ => Self::Unknown,
}
}
}
impl From<PowerSupplyHealth> for u8 {
fn from(health: PowerSupplyHealth) -> Self {
health as Self
}
}
#[derive(Copy, Clone, Debug, Serialize, Deserialize)]
#[serde(from = "u8", into = "u8")]
#[repr(u8)]
pub enum PowerSupplyTechnology {
Unknown = 0,
Nimh = 1,
Lion = 2,
Lipo = 3,
Life = 4,
Nicd = 5,
Limn = 6,
Ternary = 7,
Vrla = 8,
}
impl From<u8> for PowerSupplyTechnology {
fn from(value: u8) -> Self {
match value {
1 => Self::Nimh,
2 => Self::Lion,
3 => Self::Lipo,
4 => Self::Life,
5 => Self::Nicd,
6 => Self::Limn,
7 => Self::Ternary,
8 => Self::Vrla,
_ => Self::Unknown,
}
}
}
impl From<PowerSupplyTechnology> for u8 {
fn from(tech: PowerSupplyTechnology) -> Self {
tech as Self
}
}
#[derive(Debug, Serialize, Deserialize)]
pub struct BatteryState {
pub header: Header,
pub voltage: f32,
pub temperature: f32,
pub current: f32,
pub charge: f32,
pub capacity: f32,
pub design_capacity: f32,
pub percentage: f32,
pub power_supply_status: PowerSupplyStatus,
pub power_supply_health: PowerSupplyHealth,
pub power_supply_technology: PowerSupplyTechnology,
pub present: bool,
pub cell_voltage: Vec<f32>,
pub cell_temperature: Vec<f32>,
pub location: String,
pub serial_number: String,
}
#[derive(Debug, Serialize, Deserialize)]
pub struct MagneticField {
pub header: Header,
pub magnetic_field: geometry_msgs::Vector3,
pub magnetic_field_covariance: [f64; 9],
}
#[derive(Debug, Serialize, Deserialize)]
pub struct Joy {
pub header: Header,
pub axes: Vec<f32>,
pub buttons: Vec<i32>,
}