Skyward boardcore
Loading...
Searching...
No Matches
Boardcore Namespace Reference

This file includes all the types the logdecoder script will decode. More...

Namespaces

namespace  ADS131M04Defs
 
namespace  ADS131M08Defs
 
namespace  Aeroutils
 
namespace  BMX160Defs
 Various BMX160 register/enums definitions.
 
namespace  Canbus
 
namespace  ClockUtils
 
namespace  Constants
 
namespace  CpuMeter
 
namespace  CRCUtils
 
namespace  DependencyManagerDetails
 
namespace  DMADefs
 
namespace  H3LIS331DLDefs
 
namespace  Kernel
 
namespace  LogTypes
 
namespace  LPS22DFDefs
 
namespace  LPS28DFWDefs
 Various LPS28DFW register/enums definitions.
 
namespace  LSM6DSRXDefs
 
namespace  SkyQuaternion
 Functions for managing quaternions.
 
namespace  SPI
 Driver for STM32 low level SPI peripheral.
 
namespace  SX1278
 
namespace  TimerUtils
 Timer utilities.
 
namespace  TimestampTimer
 Utility for microsecond timestamp values.
 
namespace  Units
 
namespace  VN100SpiDefs
 
namespace  VN300Defs
 
namespace  Wiz
 
namespace  Xbee
 

Classes

class  AbstractSensor
 Base abstract class for sensor drivers. More...
 
struct  AccelerometerData
 Structure to handle accelerometer data. More...
 
struct  AccelerometerSimulatorData
 
class  ActiveObject
 
class  AD5204
 
class  ADA
 
struct  ADAState
 
struct  ADCData
 Structure to handle ADC data. More...
 
class  ADS1118
 Driver for ADS1118 adc. More...
 
struct  ADS1118Data
 
class  ADS131M04
 Driver for ADS131M04 4 simultaneous channels adc. More...
 
struct  ADS131M04Data
 
class  ADS131M08
 Driver for ADS131M08 8 simultaneous channels adc. More...
 
struct  ADS131M08Data
 
class  AirBrakesInterp
 
struct  AirBrakesInterpConfig
 
class  AirBrakesPI
 
struct  AirBrakesPIConfig
 
class  Algorithm
 
class  AnalogLoadCell
 
struct  AnalogLoadCellData
 
class  AnalogPressureSensor
 Common class for all analog pressure sensors. More...
 
struct  AntennaAngles
 A structure for storing angles relative to the NED frame. More...
 
struct  AntennaAnglesLog
 A structure for storing angles relative to the NED frame and the number of propagations that produce such angle, 0 if no propagation step has been used. Used for logging. More...
 
struct  AxisAngleOrientation
 This struct uses the three angles yaw, pitch and roll to define a transformation. More...
 
struct  AxisOrientation
 This struct represents in the most general way any kind of transformation of the reference frame (axis X, Y and Z). More...
 
struct  AxisOrthoOrientation
 This struct represents orthogonal rotations. More...
 
struct  AxisRelativeOrientation
 This struct represents axis orientation relative to a reference system. More...
 
struct  BarometerSimulatorData
 
class  BasicTimer
 Driver for STM32 basic timers. More...
 
class  BatteryVoltageSensor
 Common class for battery voltage sensors. More...
 
struct  BatteryVoltageSensorData
 Structure to handle battery voltage data. More...
 
class  BiasCalibration
 This is the dumbest type of calibration possible: an offset. More...
 
class  BiasCorrector
 Bias correction removes a bias from a measurement. More...
 
class  BME280
 
struct  BME280Data
 
class  BME280I2C
 
class  BMP280
 
struct  BMP280Data
 
class  BMP280I2C
 
class  BMX160
 BMX160 Driver. More...
 
struct  BMX160Config
 BMX160 Configuration. More...
 
struct  BMX160Data
 
struct  BMX160FifoStats
 BMX160 fifo statistics. More...
 
struct  BMX160GyroscopeCalibrationBiases
 
struct  BMX160Temperature
 
class  BMX160WithCorrection
 Applies calibration to a BMX160. More...
 
struct  BMX160WithCorrectionData
 
struct  Bounds
 
class  ButtonHandler
 Utility to detects if buttons are pressed, long pressed or long-long pressed and calls a callback in each case. More...
 
class  Buzzer
 This driver does not provide a square wave signal but instead is a simple utility that provides long PWM signals to make the buzzer beep on and off. More...
 
struct  CanBatteryVoltageSensorData
 
struct  CanCurrentData
 
struct  CanDeviceStatus
 
struct  CanEvent
 
struct  CanPitotData
 
struct  CanPressureData
 
struct  CanServoCommand
 
struct  CanServoData
 
struct  CanServoFeedback
 
struct  CanTemperatureData
 
struct  CanVoltageData
 
struct  checkIfProduces
 Check that a given type has a method called getData() and that the return type of this method is a subclass of the expected data type. More...
 
class  CircularBuffer
 
class  ConsoleTransceiver
 
class  ContiguousQueue
 
struct  Coordinates
 Coordinates struct with latitude [degree], longitude [degree]. More...
 
class  CountedPWM
 This class generates a PWM signal for a chosen number of pulses. More...
 
struct  CpuMeterData
 
class  CSVIterator
 Iterable CSV data. More...
 
class  CSVParser
 Iterable parser of CSV files. More...
 
struct  CurrentData
 Structure to handle current data. More...
 
class  CurrentSensor
 Common class for current sensors. More...
 
struct  DataAsciiRequest
 Structure that contains all the parameters for the request to be sent. More...
 
struct  DataModT
 Structure of the output of the load cell in [continuous mode -> ModT]. More...
 
struct  DataModTd
 Structure of the output of the load cell in [continuous mode -> ModTd]. More...
 
class  DependencyInjector
 Proxy class used to obtain dependencies. More...
 
class  DependencyManager
 Main DependencyManager class. More...
 
class  Deserializer
 Class used to deserialize the binary logs created using fedetft's logger into csv files. More...
 
struct  DeviceStatus
 
class  DipSwitch
 Dip switch driver to read the current status of the switch. More...
 
class  DMADriver
 This class is responsible for streams acquisition, streams release and interrupt handling. More...
 
class  DMAStream
 This class represents the actual DMA stream. It can be used to setup, start and stop DMA transactions. More...
 
class  DMAStreamGuard
 Simple RAII class to handle DMA streams. More...
 
struct  DMATransaction
 This is the configuration struct for a DMA transaction. More...
 
class  DummyBackend
 Dummy no-op backend. More...
 
class  EbyteFrontend
 
struct  EntryStructsUnion
 Union data struct to be stored in the map. It does contain the enumeration index and the value of such configuration entry. More...
 
struct  ErrataRegistersValues
 
class  EventBroker
 
class  EventCounter
 Helper class to count how many events are sent to the topic(s) it is registered to. More...
 
struct  EventData
 Loggable struct for each event posted. More...
 
class  EventHandler
 
class  EventHandlerBase
 
class  EventInjector
 Utility class to manually post events to specific topics. More...
 
class  EventSniffer
 
class  FileBackend
 
class  FileLogSink
 
class  FileLogSinkBuffered
 
class  Follower
 Follower class to output the yaw ad pitch necessary to track from the GPS origin the rocket. Computes the angle to follow the rocket using its NAS origin, NED position and velocity. More...
 
struct  FollowerState
 State of the Follower algorithm, with the angles and speeds. More...
 
class  FSM
 
class  Gamma868
 
struct  GammaConf
 
union  GammaMessage
 
class  GeneralPurposeTimer
 Driver for STM32 general purpose timers. More...
 
struct  GpioPinCompare
 Comparison operator between GpioPins used for std::map. More...
 
struct  GPSData
 Structure to handle GPS data. More...
 
struct  GPSSimulatorData
 
class  GridLayout
 Displays childs in a numRows*numCols grid. More...
 
struct  GyroscopeData
 Structure to handle gyroscope data. More...
 
struct  GyroscopeSimulatorData
 
class  H3LIS331DL
 
struct  H3LIS331DLData
 
class  HBridge
 Driver to operate an H-bridge. More...
 
class  HIL
 Single interface to the hardware-in-the-loop framework. More...
 
class  HILPhasesManager
 Singleton object that manages all the phases of the simulation. After his instantiation we need to set the source of the current position in order to be able to save the outcomes for each event. More...
 
class  HILPhasesManagerBase
 
class  HILSensor
 Class that wraps a real sensor to perform HIL simulations. More...
 
class  HILTransceiver
 HILTransceiver is a Singleton and provides an easy interface for the control algorithms to send and receive data during a simulation. More...
 
class  HILTransceiverBase
 
class  HoneywellPressureSensor
 Driver for Honeywell's pressure sensors (absolute and differential) More...
 
class  HSCMAND015PA
 Absolute pressure sensor with a 0-103kPa range (0-15psi) More...
 
struct  HSCMAND015PAData
 
class  HSCMRNN015PA
 Absolute pressure sensor with a 0-103kPa range (0-15psi) More...
 
struct  HSCMRNN015PAData
 
class  HSCMRNN030PA
 Absolute pressure sensor with a 0-206kPa range (0-30psi) More...
 
struct  HSCMRNN030PAData
 
class  HSCMRNN160KA
 Absolute pressure sensor with a 0-160kPa range. More...
 
struct  HSCMRNN160KAData
 
class  HSM
 
struct  HumidityData
 Structure to handle humidity data. More...
 
class  HX711
 Load cell transducer. More...
 
struct  HX711Data
 
class  I2C
 High level driver for the I2C peripherals. More...
 
class  I2CDriver
 Low level driver for I2C peripherals. More...
 
class  ImageView
 Simple view that displays an image. More...
 
struct  IMUData
 
class  Injectable
 Interface for an injectable dependency. More...
 
struct  InjectableBase
 
class  InjectableWithDeps
 Base class for an Injectable with dependencies. More...
 
class  InjectableWithDeps< InjectableBase< Base >, Types... >
 Base class for an Injectable with dependencies and an Injectable superclass. More...
 
class  InternalADC
 Driver for stm32 internal ADC. More...
 
struct  InternalADCData
 
class  IRQCircularBuffer
 
class  Kalman
 Implementation of a generic Kalman filter using the Eigen library. More...
 
class  L3GD20
 
struct  L3GD20Data
 
class  LIS2MDL
 Driver for LIS2MDL, a three-axis magnetic sensor. More...
 
struct  LIS2MDLData
 
class  LIS331HH
 
struct  LIS331HHData
 
class  LIS3DSH
 
struct  LIS3DSHData
 
class  LIS3MDL
 Driver for LIS3MDL, a three-axis magnetic sensor. More...
 
struct  LIS3MDLData
 
struct  LoadCellData
 
struct  LogAntennasCoordinates
 A structure for logging the ARP system coordinates set in the Follower. More...
 
class  Logger
 Buffered logger. Needs to be started before it can be used. More...
 
struct  LoggerStats
 Statistics for the logger. More...
 
class  Logging
 
struct  LoggingString
 
struct  LogRecord
 
struct  LogRocketCoordinates
 A structure for logging the Rocket coordinates set in the Follower. More...
 
class  LogSink
 
class  LPS22DF
 Driver for LPS22DF, Low-power and high-precision MEMS pressure sensor. More...
 
struct  LPS22DFData
 
class  LPS28DFW
 Driver for LPS28DFW STMicroelectronics digital pressure sensor working in I2C. More...
 
struct  LPS28DFWData
 Struct for the LPS28DFW barometer data. Pressures stored in Pa and Temperature in °C. More...
 
class  LPS331AP
 
struct  LPS331APData
 
class  LSM6DSRX
 LSM6DSRX Driver. More...
 
struct  LSM6DSRXConfig
 
struct  LSM6DSRXData
 
struct  MagnetometerData
 Structure to handle magnetometer data. More...
 
struct  MagnetometerSimulatorData
 
class  MavlinkDriver
 The MavlinkDriver object offers an interface to send and receive from a Transceiver object using an implementation of the Mavlink protocol. More...
 
struct  MavlinkStatus
 
class  MAX31855
 MAX31855 thermocouple sensor driver. More...
 
class  MAX31856
 MAX31855 thermocouple sensor driver. More...
 
struct  MAX31856Data
 
class  MAX6675
 MAX6675 thermocouple sensor driver. More...
 
class  MBLoadCell
 Driver to communicate with a TLB digital-analog weight transmitter attached to a loadcell. More...
 
struct  MBLoadCellData
 Structure that stores a data value, with his timestamp and his validity. More...
 
struct  MBLoadCellSettings
 Structure of the output of the load cell in [continuous mode -> ModT]. More...
 
class  MEA
 
struct  MEAState
 
class  Module
 
class  ModuleManager
 The module manager is a singleton object, so it can be instantiated only once. It contains all the active software modules which can be accessed in a centralized way. More...
 
class  MovingAverage
 
class  MPU9250
 Driver class for MPU9250. More...
 
struct  MPU9250Data
 
class  MPX5010
 Driver for NXP's MPX5010 pressure sensor. More...
 
struct  MPX5010Data
 
class  MPXH6115A
 Driver for NXP's MPXH6115A pressure sensor. More...
 
struct  MPXH6115AData
 
class  MPXH6250A
 Driver for NXP's MPXHZ6130A pressure sensor. More...
 
struct  MPXH6250AData
 
class  MPXH6400A
 Driver for NXP's MPXHZ6130A pressure sensor. More...
 
struct  MPXH6400AData
 
class  MPXHZ6130A
 Driver for NXP's MPXHZ6130A pressure sensor. More...
 
struct  MPXHZ6130AData
 
class  MS5803
 
struct  MS5803CalibrationData
 MS5803 calibration data. See page 13 of datasheet for more details. More...
 
struct  MS5803Data
 
class  MS5803I2C
 
class  NAS
 
struct  NASConfig
 
struct  NASState
 
class  NavController
 UI navigation controller: listens for button clicks and dispatches the interactions to the view tree. More...
 
class  ND015A
 
class  ND015D
 
struct  ND015XData
 
struct  NEDCoords
 
class  OptionView
 View used to display an option list, so the user can select one by clicking on it. More...
 
struct  Outcomes
 
class  Packet
 The Packet class is used for packing together messages with variable lengths into a fixed size packet. Useful for telemetry. More...
 
class  PIController
 Proportional and integral controller with saturation. More...
 
struct  PinData
 Pin informations. More...
 
class  PinObserver
 
class  Pitot
 
struct  PitotData
 
struct  PitotSimulatorData
 
struct  Position
 
struct  PressureData
 
class  PrintLogger
 
class  Propagator
 Predictor class that linearly propagates the last available rocket position by means of the rocket NAS velocity. More...
 
struct  PropagatorState
 State of the propagator, taking into account the prediction steps (0 if true NAS state) and the propagated NAS. More...
 
class  PWM
 Driver for easy access to the PWM capabilities of the general purpose timers. More...
 
struct  QuaternionData
 Structure to handle quaternion data. More...
 
class  RA01Frontend
 
struct  ReferenceValues
 Reference values for the Apogee Detection Algorithm. More...
 
class  RegistryBackend
 Registry Backend class used to save and load data to the designated storage/memory. More...
 
struct  RegistryFooter
 Registry Footer, with checksum of the configuration data (not whole data). Placed at the end of the actually serialized data. More...
 
class  RegistryFrontend
 This is the front-end for the registry to store and load the configuration. Its methods are type unsafe since the type is determined by the entry setted. It does check the data types but its job is mainly the one of get and set for the given ConfigurationId, the value of the entry. It also exposes methods for go into a "safe" state during armed state / flight. Finally there are methods to visit the entire configuration (forEach). More...
 
struct  RegistryHeader
 Serialization header, with useful information about the serialized data. Header to the actually serialized data. More...
 
class  RegistrySerializer
 Serialization and de-serialization class for the registry. It does serialize and deserialize the configuration to the specified vector. More...
 
class  RotatedIMU
 A software IMU sensor that allows applying transformations to the data after sampling via a callback. Defaults to identity transformations. More...
 
class  Runcam
 Class for controlling the Runcam via uart. More...
 
class  ScreenManager
 UI Thread: Manages multiple view trees ("Screen") and draws the active one at the provided refresh rate. More...
 
class  Sensor
 Base sensor class with has to be extended by any sensor driver. More...
 
class  SensorFIFO
 Interface for sensor that implement a FIFO. More...
 
struct  SensorInfo
 Sensors information struct needed by the SensorManager. More...
 
class  SensorManager
 The SensorManager handles sensors initialization and sampling. More...
 
class  SensorSampler
 Virtual sensor sampler class. More...
 
class  SerialTransceiver
 
class  Servo
 Driver to operate a PWM controlled servo motor. More...
 
struct  ServoCommand
 
struct  ServoData
 
struct  ServoFeedback
 
class  SignaledDeadlineTask
 A task that executes a user-defined function at specific time points, or when signaled. More...
 
class  SimpleSensorSampler
 Sampler for simple sensors, those that are simply sampled by calling the sample() method. More...
 
class  Singleton
 
class  SixParameterCalibration
 
class  SixParametersCorrector
 Six-parameter correction uses, for each axis, a coefficient to be multiplied and a constant to be added, so that is verified the formula: More...
 
struct  Size
 
class  Skyward433Frontend
 
class  SoftAndHardIronCalibration
 Soft and hard iron calibration utility. More...
 
class  SoftwareDifferentialPressureSensor
 Class used to simulate a differential pressure sensor in software. More...
 
class  SPIAcquireLock
 RAII Interface for SPI bus acquisition. More...
 
class  SPIBus
 Driver for STM32 low level SPI peripheral. More...
 
struct  SPIBusConfig
 SPI Bus configuration for a specific slave. More...
 
class  SPIBusInterface
 Interface for low level access of a SPI bus as a master. More...
 
class  SPISelectLock
 RAII Interface for SPI chip selection. More...
 
struct  SPISlave
 Contains information about a single SPI slave device. More...
 
class  SPITransaction
 Provides high-level access to the SPI Bus for a single transaction. More...
 
class  SSCDANN030PAA
 Absolute pressure sensor with a 0-206kPa range (0-30psi) More...
 
struct  SSCDANN030PAAData
 
class  SSCDRRN015PDA
 Differential pressure sensor with a ±103kPa range (±15psi) More...
 
struct  SSCDRRN015PDAData
 
class  SSCMRNN030PA
 Absolute pressure sensor with a 0-206kPa range (0-30psi) More...
 
struct  SSCMRNN030PAData
 
struct  StackData
 
class  StackLogger
 
class  StateInitializer
 Utility used to initialize the extended kalman filter's state. More...
 
class  Stats
 Computes on-line statistics of a dataset. More...
 
struct  StatsResult
 Statistics computed by the Stats class. More...
 
class  Stepper
 
struct  StepperData
 
class  StepperPWM
 
class  STM32SerialWrapper
 Wrapper for the STM32Serial driver in miosix. More...
 
class  SX1278Fsk
 Various SX1278 register/enums definitions. More...
 
class  SX1278Lora
 
class  SyncCircularBuffer
 
class  SyncedI2C
 Thread safe version of the I2C high-level driver. More...
 
class  SyncedSPIBus
 Extension of SPIBus to sync access to the bus between multiple threads. More...
 
class  SynchronizedQueue
 
class  SyncPacketQueue
 A SyncPacketQueue is a SyncCircularBuffer of Packets. More...
 
class  TaskScheduler
 The Task Scheduler allow to manage simple tasks with a single thread. All the task added must not take more than 1ms to execute and should take less time as possible to ensure other tasks are executed as they are supposed to. More...
 
struct  TaskStatsResult
 Statistics over a single task. More...
 
struct  TemperatureData
 
struct  TemperatureSimulatorData
 
class  TextView
 Simple view to display text on screen. More...
 
class  TimedTrajectoryPoint
 Trajectory point with timestamp and velocity module. More...
 
struct  TimestampData
 
class  TrafagPressureSensor
 Sensor class for a Trafag pressure sensor. More...
 
class  Trajectory
 
class  TrajectoryPoint
 
class  TrajectorySet
 
class  Transceiver
 
class  TwoPointAnalogLoadCell
 Sensor class for a two point calibrated load cell. More...
 
union  TypeUnion
 Union type used for the underlying saving mechanism for the configuration values. More...
 
struct  UBXAckFrame
 UBX frames UBX-ACK-ACK and UBX-ACK-NAK. More...
 
struct  UBXDateTime
 Structure to handle UBX UTC time. Nanoseconds range from -5000000 (5 ms) to 994999999 (~995 ms) and when negative the other fields have been rounded to the nearest hundredth of a second. Because of leap seconds, minutes can be a second longer or shorter, so seconds range from 0 to 60. More...
 
struct  UBXFrame
 Generic UBX frame. More...
 
struct  UBXGPSData
 
class  UBXGPSSerial
 Driver for Ublox GPSs. More...
 
class  UBXGPSSpi
 Sensor for UBlox GPS. More...
 
struct  UBXPvtFrame
 UBX frame UBX-NAV-PVT. More...
 
class  UdpTransceiver
 
class  USART
 Driver for STM32F4 low level USART/UART peripheral. More...
 
class  USARTInterface
 Abstract class that implements the interface for the USART/UART serial communication. More...
 
class  VerticalLayout
 Positions the childs in a vertical grid. The height of each child is dictated by its weight parameter. More...
 
class  View
 Base class for anything that can be drawn on the screen and interacted with. More...
 
class  VN100Serial
 Driver class for VN100 IMU. More...
 
struct  VN100SerialData
 data type class More...
 
class  VN100Spi
 Driver class for VN100 Spi IMU. More...
 
struct  VN100SpiData
 Data type class for VN100 Spi. More...
 
class  VN300
 Driver class for VN300 IMU. More...
 
struct  VN300Data
 Data class for VN300. More...
 
class  VNCommonSerial
 
struct  VoltageData
 Structure to handle voltage data. More...
 
class  Wiz5500
 Driver for the WizNet W5500 ethernet. More...
 
struct  WizIp
 Class representing an IPv4 ip. More...
 
struct  WizMac
 Class representing an ethernet MAC address. More...
 

Typedefs

using GP16bitTimer = GeneralPurposeTimer<uint16_t>
 General purpose 16bit timer.
 
using GP32bitTimer = GeneralPurposeTimer<uint32_t>
 General purpose 32bit timer.
 
typedef uint8_t Event
 
typedef std::numeric_limits< float > flt
 
typedef std::map< const LoadCellValuesEnum, std::string > LoadCellValues
 Type that maps the different requests to their keyword.
 
using RegistryConfiguration
 
using ConfigurationId = uint32_t
 

Enumerations

enum  LogLevel : uint8_t {
  LOGL_NOTSET = 0 , LOGL_DEBUG = 10 , LOGL_INFO = 20 , LOGL_WARNING = 30 ,
  LOGL_ERROR = 40 , LOGL_CRITICAL = 50
}
 
enum  ThreadId : uint8_t {
  THID_MAV_RECEIVER , THID_MAV_SENDER , THID_XBEE , THID_GPS ,
  THID_EVT_BROKER , THID_LOGGER_PACK , THID_LOGGER_WRITE , THID_CPU_METER ,
  THID_CPU_WD , THID_PIN_OBS , THID_FIRST_AVAILABLE_ID
}
 
enum  BasicEvent : Event {
  EV_ENTRY = 0 , EV_EXIT = 1 , EV_EMPTY = 2 , EV_INIT = 3 ,
  EV_FIRST_CUSTOM = 4
}
 
enum  State {
  HANDLED = 0 , UNHANDLED , IGNORED , TRAN ,
  SUPER
}
 
enum class  LoggerResult { Queued , Dropped , Ignored , TooLarge }
 Possible outcomes of Logger::log(). More...
 
enum  GammaBaudrate : uint8_t {
  B_9600 = 0 , B_192000 = 1 , B_28800 = 2 , B_38400 = 3 ,
  B_57600 = 4 , LAST_BAUDRATE
}
 
enum  GammaSF : uint8_t {
  SF6 = 0 , SF7 = 1 , SF8 = 2 , SF9 = 3 ,
  SF10 = 4 , SF11 = 5 , SF12 = 6 , LAST_SF
}
 
enum  GammaPower : uint8_t {
  dbm5 = 0 , dbm6 , dbm7 , dbm8 ,
  dbm9 , dbm10 , dbm11 , dbm12 ,
  dbm13 , dbm14 , dbm15 , dbm16 ,
  dbm17 , dbm18 , dbm19 , dbm20 ,
  LAST_POWER
}
 
enum class  Direction : uint8_t {
  POSITIVE_X = 0 , NEGATIVE_X , POSITIVE_Y , NEGATIVE_Y ,
  POSITIVE_Z , NEGATIVE_Z
}
 
enum  LoadCellModes : uint8_t { ASCII_MOD_TD , CONT_MOD_T , CONT_MOD_TD }
 Enumeration of all the modes supported by the driver. More...
 
enum  LoadCellValuesEnum {
  SET_SETPOINT_1 , SET_SETPOINT_2 , SET_SETPOINT_3 , GET_SETPOINT_1 ,
  GET_SETPOINT_2 , GET_SETPOINT_3 , GROSS_WEIGHT , NET_WEIGHT ,
  PEAK_WEIGHT , RESET_TARE , COMMUTE_TO_NET , COMMUTE_TO_GROSS
}
 Enumeration of all the requests in ASCII mode. More...
 
enum  ReturnsStates { VALID_RETURN , RECEPTION_ERROR , EXECUTION_ERROR }
 Structure of the errors in the ASCII requests. More...
 
enum  SensorErrors : uint8_t {
  NO_ERRORS = 0 , INVALID_WHOAMI = 1 , INIT_FAIL = 2 , NOT_INIT = 3 ,
  ALREADY_INIT = 4 , SELF_TEST_FAIL = 5 , BUS_FAULT = 6 , NO_NEW_DATA = 7 ,
  INVALID_FIFO_INDEX = 8 , DMA_ERROR = 9 , COMMAND_FAILED = 10 , END_OF_BASE_ERRORS = 11
}
 Generic error codes that a sensor can generate. More...
 
enum class  UBXMessage : uint16_t {
  UBX_NAV_PVT = 0x0701 , UBX_ACK_NAK = 0x0005 , UBX_ACK_ACK = 0x0105 , UBX_CFG_PRT = 0x0006 ,
  UBX_CFG_MSG = 0x0106 , UBX_CFG_RST = 0x0406 , UBX_CFG_RATE = 0x0806 , UBX_CFG_NAV5 = 0x2406
}
 UBX messages enumeration. More...
 
enum class  ButtonEvent { PRESSED , SHORT_PRESS , LONG_PRESS , VERY_LONG_PRESS }
 
enum class  VertAlignment { TOP , CENTER , BOTTOM }
 
enum class  HorizAlignment { LEFT , CENTER , RIGHT }
 
enum class  Interaction { BTN_DOWN , BTN_UP , CLICK , LONG_CLICK }
 
enum class  PinTransition : uint8_t { FALLING_EDGE = 0 , RISING_EDGE }
 Pin transition. More...
 
enum class  TypesEnum { UINT32 , FLOAT , COORDINATES }
 
enum class  RegistryError {
  OK , MALFORMED_SERIALIZED_DATA , CHECKSUM_FAIL , INCORRECT_TYPE ,
  WRONG_WRITES_SIZE , NO_SPACE_FOR_HEADER , NO_SUCH_TYPE , ARMED ,
  ENTRY_NOT_FOUND , WRONG_ENDIANESS , BACKEND_START_FAIL , BACKEND_LOAD_FAIL ,
  BACKEND_SAVE_FAIL
}
 RegistryError enumeration as return type. More...
 

Functions

float minimizeRotation (float angle)
 Minimize rotation angle.
 
unsigned int skywardStack (unsigned int stack)
 
uint32_t floatToInt32 (float val)
 
float int32ToFloat (uint32_t val)
 
Canbus::CanMessage toCanMessage (const PitotData &data)
 
Canbus::CanMessage toCanMessage (const PressureData &data)
 
Canbus::CanMessage toCanMessage (const TemperatureData &data)
 
Canbus::CanMessage toCanMessage (const CurrentData &data)
 
Canbus::CanMessage toCanMessage (const ServoData &data)
 
Canbus::CanMessage toCanMessage (const BatteryVoltageSensorData &data)
 
Canbus::CanMessage toCanMessage (const VoltageData &data)
 
Canbus::CanMessage toCanMessage (const DeviceStatus &data)
 
Canbus::CanMessage toCanMessage (const ServoCommand &data)
 
Canbus::CanMessage toCanMessage (const ServoFeedback &data)
 
CanPitotData pitotDataFromCanMessage (const Canbus::CanMessage &msg)
 
CanPressureData pressureDataFromCanMessage (const Canbus::CanMessage &msg)
 
CanTemperatureData temperatureDataFromCanMessage (const Canbus::CanMessage &msg)
 
CanCurrentData currentDataFromCanMessage (const Canbus::CanMessage &msg)
 
CanServoData servoDataFromCanMessage (const Canbus::CanMessage &msg)
 
CanBatteryVoltageSensorData batteryVoltageDataFromCanMessage (const Canbus::CanMessage &msg)
 
CanVoltageData voltageDataFromCanMessage (const Canbus::CanMessage &msg)
 
CanDeviceStatus deviceStatusFromCanMessage (const Canbus::CanMessage &msg)
 
CanServoCommand servoCommandFromCanMessage (const Canbus::CanMessage &msg)
 
CanServoFeedback servoFeedbackFromCanMessage (const Canbus::CanMessage &msg)
 
bool operator== (const GammaConf &lhs, const GammaConf &rhs)
 
std::ostream & operator<< (std::ostream &o, const GammaConf &conf)
 
long long now ()
 
Eigen::Vector3f orientationToVector (Direction direction)
 
void operator<< (AccelerometerData &lhs, const Vector3f &rhs)
 
void operator<< (Eigen::Vector3f &lhs, const AccelerometerData &rhs)
 
void operator<< (GyroscopeData &lhs, const Vector3f &rhs)
 
void operator<< (Eigen::Vector3f &lhs, const GyroscopeData &rhs)
 
void operator<< (MagnetometerData &lhs, const Vector3f &rhs)
 
void operator<< (Eigen::Vector3f &lhs, const MagnetometerData &rhs)
 
void operator>> (const AccelerometerData &lhs, Eigen::Vector3f &rhs)
 
void operator>> (const Eigen::Vector3f &lhs, AccelerometerData &rhs)
 
void operator>> (const GyroscopeData &lhs, Eigen::Vector3f &rhs)
 
void operator>> (const Eigen::Vector3f &lhs, GyroscopeData &rhs)
 
void operator>> (const MagnetometerData &lhs, Eigen::Vector3f &rhs)
 
void operator>> (const Eigen::Vector3f &lhs, MagnetometerData &rhs)
 
void operator<< (AccelerometerData &lhs, const Eigen::Vector3f &rhs)
 
void operator<< (GyroscopeData &lhs, const Eigen::Vector3f &rhs)
 
void operator<< (MagnetometerData &lhs, const Eigen::Vector3f &rhs)
 
int32_t getNextDependencyId ()
 Returns the next available id.
 
template<typename T >
int32_t getDependencyId ()
 Get the ID associated with the given T type.
 
mxgui::Color color24to16 (uint32_t rgb)
 Converts a 24bit color to a 16bit color.
 
template<class T >
constexpr auto add_sat (T x, T y) noexcept -> typename std::enable_if_t< std::is_integral< T >::value, T >
 Computes the saturating addition x + y for integral types.
 
ostream & operator<< (ostream &os, const StatsResult &sr)
 
std::ostream & operator<< (std::ostream &os, const StatsResult &sr)
 Allows printing StatsResult to an ostream.
 
constexpr long long nsToUs (long long ns)
 Convert nanoseconds to microseconds.
 
constexpr long long nsToMs (long long ns)
 Convert nanoseconds to milliseconds.
 
constexpr long long msToNs (long long ms)
 Convert milliseconds to nanoseconds.
 
constexpr long long sToNs (long long s)
 Convert seconds to nanoseconds.
 

Variables

constexpr DioMapping DEFAULT_MAPPING = DioMapping(0, 0, 0, 1, 0, 0, false)
 
constexpr const char * humanFriendlyDirection []
 

Detailed Description

This file includes all the types the logdecoder script will decode.

Utility to parse a CSV file.

Driver for the VN100S IMU.

All logged classes inside Boardcore should be reported here.

This object includes only the protocol header (protocol.h). To use this driver, you should include YOUR OWN implementation of the messages definition (mavlink.h) before including this header.

The VN100 sensor is a calibrated IMU which includes accelerometer, magnetometer, gyroscope, barometer and temperature sensor. It also provides attitude data (yaw, pith, roll, quaternion). The device provides also a calibration matrix and an anti-drift matrix for the gyroscope values.

This driver samples IMU compensated data (accelerometer, gyroscope and magnetometer), quaternion data, temperature and pressure data. The sampling rate is 400Hz.

This driver only supports binary encoding for communication.

Driver for the VN100 SPI IMU.

The VN100 sensor is a calibrated IMU which includes accelerometer, magnetometer, gyroscope, barometer and temperature sensor. It also provides attitude data (yaw, pith, roll, quaternion). This driver samples imu compensated data (accelerometer, gyroscope and magnetometer) and quaternion data.

The sampling rate is 400Hz. The data ready interrupt can be set to a lower rate by changing the syncOutSkipFactor parameter.

ATTENTION: at least 100 microseconds has to pass between the read/write operations with the sensor.

Use CSVParser with the filename to iterate through all the CSV entries. You need to specify a type with the >> stream operator.

Here an example you can find in test-csvreader.cpp

struct TestData { uint64_t timestamp; int counter; };

std::istream& operator>>(std::istream& input, TestData& data) { input >> data.timestamp; input.ignore(1, ','); input >> data.counter;

return input; }

int main() { for (auto& data : CSVParser<TestData>("/sd/config.csv")) printf("%llu,%d\n", data.timestamp, data.counter); // linter off }

Reference: https://stackoverflow.com/questions/1120140/how-can-i-read-and-parse-csv-files-in-c

Typedef Documentation

◆ ConfigurationId

using Boardcore::ConfigurationId = uint32_t

Definition at line 38 of file RegistryTypes.h.

◆ Event

typedef uint8_t Boardcore::Event

Definition at line 30 of file Event.h.

◆ flt

typedef std::numeric_limits<float> Boardcore::flt

Definition at line 46 of file Deserializer.h.

◆ GP16bitTimer

General purpose 16bit timer.

If a timer is natively 32bit, it can be used as 16bit (or even as a basic timer).

Definition at line 216 of file GeneralPurposeTimer.h.

◆ GP32bitTimer

General purpose 32bit timer.

Definition at line 221 of file GeneralPurposeTimer.h.

◆ LoadCellValues

typedef std::map<const LoadCellValuesEnum, std::string> Boardcore::LoadCellValues

Type that maps the different requests to their keyword.

Definition at line 67 of file MBLoadCellData.h.

◆ RegistryConfiguration

Initial value:
std::unordered_map<ConfigurationId, EntryStructsUnion>

Definition at line 37 of file RegistrySerializer.h.

Enumeration Type Documentation

◆ BasicEvent

Enumerator
EV_ENTRY 
EV_EXIT 
EV_EMPTY 
EV_INIT 
EV_FIRST_CUSTOM 

Definition at line 32 of file Event.h.

◆ ButtonEvent

enum class Boardcore::ButtonEvent
strong
Enumerator
PRESSED 

The button is pressed.

SHORT_PRESS 

The button is released before LONG_PRESS_TICKS.

LONG_PRESS 

The button is released before VERY_LONG_PRESS_TICKS.

VERY_LONG_PRESS 

The button is released after VERY_LONG_PRESS_TICKS.

Definition at line 34 of file ButtonHandler.h.

◆ Direction

enum class Boardcore::Direction : uint8_t
strong

This enum is used to represent directions relative to X, Y and X.

Enumerator
POSITIVE_X 
NEGATIVE_X 
POSITIVE_Y 
NEGATIVE_Y 
POSITIVE_Z 
NEGATIVE_Z 

Definition at line 36 of file AxisOrientation.h.

◆ GammaBaudrate

enum Boardcore::GammaBaudrate : uint8_t
Enumerator
B_9600 
B_192000 
B_28800 
B_38400 
B_57600 
LAST_BAUDRATE 

Definition at line 31 of file GammaTypes.h.

◆ GammaPower

enum Boardcore::GammaPower : uint8_t
Enumerator
dbm5 
dbm6 
dbm7 
dbm8 
dbm9 
dbm10 
dbm11 
dbm12 
dbm13 
dbm14 
dbm15 
dbm16 
dbm17 
dbm18 
dbm19 
dbm20 
LAST_POWER 

Definition at line 53 of file GammaTypes.h.

◆ GammaSF

enum Boardcore::GammaSF : uint8_t
Enumerator
SF6 
SF7 
SF8 
SF9 
SF10 
SF11 
SF12 
LAST_SF 

Definition at line 41 of file GammaTypes.h.

◆ HorizAlignment

enum class Boardcore::HorizAlignment
strong
Enumerator
LEFT 
CENTER 
RIGHT 

Definition at line 106 of file View.h.

◆ Interaction

enum class Boardcore::Interaction
strong
Enumerator
BTN_DOWN 
BTN_UP 
CLICK 
LONG_CLICK 

Definition at line 113 of file View.h.

◆ LoadCellModes

enum Boardcore::LoadCellModes : uint8_t

Enumeration of all the modes supported by the driver.

Enumerator
ASCII_MOD_TD 
CONT_MOD_T 
CONT_MOD_TD 

Definition at line 38 of file MBLoadCellData.h.

◆ LoadCellValuesEnum

Enumeration of all the requests in ASCII mode.

Enumerator
SET_SETPOINT_1 
SET_SETPOINT_2 
SET_SETPOINT_3 
GET_SETPOINT_1 
GET_SETPOINT_2 
GET_SETPOINT_3 
GROSS_WEIGHT 
NET_WEIGHT 
PEAK_WEIGHT 
RESET_TARE 
COMMUTE_TO_NET 
COMMUTE_TO_GROSS 

Definition at line 48 of file MBLoadCellData.h.

◆ LoggerResult

enum class Boardcore::LoggerResult
strong

Possible outcomes of Logger::log().

Enumerator
Queued 

Data has been accepted by the logger and will be written.

Dropped 

Buffers are currently full, data will not be written. Sorry.

Ignored 

Logger is currently stopped, data will not be written.

TooLarge 

Data is too large to be logged. Increase maxRecordSize.

Definition at line 43 of file Logger.h.

◆ LogLevel

enum Boardcore::LogLevel : uint8_t
Enumerator
LOGL_NOTSET 
LOGL_DEBUG 
LOGL_INFO 
LOGL_WARNING 
LOGL_ERROR 
LOGL_CRITICAL 

Definition at line 43 of file PrintLoggerData.h.

◆ PinTransition

enum class Boardcore::PinTransition : uint8_t
strong

Pin transition.

Enumerator
FALLING_EDGE 

The pin goes from high to low.

RISING_EDGE 

The pin goes from low to high.

Definition at line 36 of file PinObserver.h.

◆ RegistryError

enum class Boardcore::RegistryError
strong

RegistryError enumeration as return type.

Enumerator
OK 

Correct condition.

MALFORMED_SERIALIZED_DATA 

Malformed data while deserializing.

CHECKSUM_FAIL 

The custom checksum check fails.

INCORRECT_TYPE 

The typeId and value type not correspond.

WRONG_WRITES_SIZE 

Cannot write due to wrong data size.

NO_SPACE_FOR_HEADER 

There is not enough space to write the header.

NO_SUCH_TYPE 

There is no such type in TypeEnum.

ARMED 

The registry is armed, the operation is not allowed.

ENTRY_NOT_FOUND 

Not found such entry.

WRONG_ENDIANESS 

The endianess not corresponds.

BACKEND_START_FAIL 
BACKEND_LOAD_FAIL 
BACKEND_SAVE_FAIL 

Definition at line 67 of file RegistryTypes.h.

◆ ReturnsStates

Structure of the errors in the ASCII requests.

Enumerator
VALID_RETURN 
RECEPTION_ERROR 
EXECUTION_ERROR 

Definition at line 79 of file MBLoadCellData.h.

◆ SensorErrors

enum Boardcore::SensorErrors : uint8_t

Generic error codes that a sensor can generate.

Sensors can extend this enum by defining a new set of errors, starting from END_OF_BASE_ERRORS.

Enumerator
NO_ERRORS 
INVALID_WHOAMI 
INIT_FAIL 
NOT_INIT 
ALREADY_INIT 
SELF_TEST_FAIL 
BUS_FAULT 
NO_NEW_DATA 
INVALID_FIFO_INDEX 
DMA_ERROR 
COMMAND_FAILED 
END_OF_BASE_ERRORS 

Definition at line 37 of file SensorData.h.

◆ State

Enumerator
HANDLED 

Event handled.

UNHANDLED 

Event unhandled.

IGNORED 
TRAN 

A transition to another state was taken.

SUPER 

A transition to a parent state was taken.

Definition at line 40 of file HSM.h.

◆ ThreadId

enum Boardcore::ThreadId : uint8_t
Enumerator
THID_MAV_RECEIVER 
THID_MAV_SENDER 
THID_XBEE 
THID_GPS 
THID_EVT_BROKER 
THID_LOGGER_PACK 
THID_LOGGER_WRITE 
THID_CPU_METER 
THID_CPU_WD 
THID_PIN_OBS 
THID_FIRST_AVAILABLE_ID 

Definition at line 33 of file StackData.h.

◆ TypesEnum

enum class Boardcore::TypesEnum
strong
Enumerator
UINT32 
FLOAT 
COORDINATES 

Definition at line 41 of file RegistryTypes.h.

◆ UBXMessage

enum class Boardcore::UBXMessage : uint16_t
strong

UBX messages enumeration.

Enumerator
UBX_NAV_PVT 
UBX_ACK_NAK 
UBX_ACK_ACK 
UBX_CFG_PRT 
UBX_CFG_MSG 
UBX_CFG_RST 
UBX_CFG_RATE 
UBX_CFG_NAV5 

Definition at line 36 of file UBXFrame.h.

◆ VertAlignment

enum class Boardcore::VertAlignment
strong
Enumerator
TOP 
CENTER 
BOTTOM 

Definition at line 99 of file View.h.

Function Documentation

◆ add_sat()

template<class T >
constexpr auto Boardcore::add_sat ( T x,
T y ) -> typename std::enable_if_t<std::is_integral<T>::value, T>
constexprnoexcept

Computes the saturating addition x + y for integral types.

Returns
x + y, if the result is representable as a value of type T. Otherwise, the largest or smallest value of type T, whichever is closer to the result.

Definition at line 43 of file Numeric.h.

◆ batteryVoltageDataFromCanMessage()

CanBatteryVoltageSensorData Boardcore::batteryVoltageDataFromCanMessage ( const Canbus::CanMessage & msg)
inline

Definition at line 499 of file CanProtocolTypes.h.

◆ color24to16()

mxgui::Color Boardcore::color24to16 ( uint32_t rgb)

Converts a 24bit color to a 16bit color.

Parameters
rgb24 bit color
Returns
Color Closest 16 bit color

Definition at line 35 of file Misc.h.

◆ currentDataFromCanMessage()

CanCurrentData Boardcore::currentDataFromCanMessage ( const Canbus::CanMessage & msg)
inline

Definition at line 473 of file CanProtocolTypes.h.

◆ deviceStatusFromCanMessage()

CanDeviceStatus Boardcore::deviceStatusFromCanMessage ( const Canbus::CanMessage & msg)
inline

Definition at line 524 of file CanProtocolTypes.h.

◆ floatToInt32()

uint32_t Boardcore::floatToInt32 ( float val)
inline

Definition at line 37 of file CanProtocolTypes.h.

◆ getDependencyId()

template<typename T >
int32_t Boardcore::getDependencyId ( )

Get the ID associated with the given T type.

Definition at line 49 of file DependencyManager.h.

◆ getNextDependencyId()

int32_t Boardcore::getNextDependencyId ( )

Returns the next available id.

Note
THIS IS ONLY USED INTERNALLY BY getDependencyId().

Definition at line 32 of file DependencyManager.cpp.

◆ int32ToFloat()

float Boardcore::int32ToFloat ( uint32_t val)
inline

Definition at line 44 of file CanProtocolTypes.h.

◆ minimizeRotation()

float Boardcore::minimizeRotation ( float angle)

Minimize rotation angle.

Parameters
angleAngle of movement [deg]
Returns
The minimized rotation angle [deg]

Definition at line 43 of file Follower.cpp.

◆ msToNs()

constexpr long long Boardcore::msToNs ( long long ms)
constexpr

Convert milliseconds to nanoseconds.

Parameters
msMilliseconds.
Returns
Nanoseconds.

Definition at line 56 of file TimeUtils.h.

◆ now()

long long Boardcore::now ( )

Definition at line 38 of file SX1278Fsk.cpp.

◆ nsToMs()

constexpr long long Boardcore::nsToMs ( long long ns)
constexpr

Convert nanoseconds to milliseconds.

Parameters
nsNanoseconds.
Returns
Milliseconds.

Definition at line 48 of file TimeUtils.h.

◆ nsToUs()

constexpr long long Boardcore::nsToUs ( long long ns)
constexpr

Convert nanoseconds to microseconds.

Parameters
nsNanoseconds.
Returns
Microseconds.

Definition at line 40 of file TimeUtils.h.

◆ operator<<() [1/12]

void Boardcore::operator<< ( AccelerometerData & lhs,
const Eigen::Vector3f & rhs )

◆ operator<<() [2/12]

void Boardcore::operator<< ( AccelerometerData & lhs,
const Vector3f & rhs )

Definition at line 30 of file SensorDataExtra.cpp.

◆ operator<<() [3/12]

void Boardcore::operator<< ( Eigen::Vector3f & lhs,
const AccelerometerData & rhs )

Definition at line 37 of file SensorDataExtra.cpp.

◆ operator<<() [4/12]

void Boardcore::operator<< ( Eigen::Vector3f & lhs,
const GyroscopeData & rhs )

Definition at line 51 of file SensorDataExtra.cpp.

◆ operator<<() [5/12]

void Boardcore::operator<< ( Eigen::Vector3f & lhs,
const MagnetometerData & rhs )

Definition at line 65 of file SensorDataExtra.cpp.

◆ operator<<() [6/12]

void Boardcore::operator<< ( GyroscopeData & lhs,
const Eigen::Vector3f & rhs )

◆ operator<<() [7/12]

void Boardcore::operator<< ( GyroscopeData & lhs,
const Vector3f & rhs )

Definition at line 44 of file SensorDataExtra.cpp.

◆ operator<<() [8/12]

void Boardcore::operator<< ( MagnetometerData & lhs,
const Eigen::Vector3f & rhs )

◆ operator<<() [9/12]

void Boardcore::operator<< ( MagnetometerData & lhs,
const Vector3f & rhs )

Definition at line 58 of file SensorDataExtra.cpp.

◆ operator<<() [10/12]

ostream & Boardcore::operator<< ( ostream & os,
const StatsResult & sr )

Definition at line 34 of file Stats.cpp.

◆ operator<<() [11/12]

std::ostream & Boardcore::operator<< ( std::ostream & o,
const GammaConf & conf )
inline

Definition at line 98 of file GammaTypes.h.

◆ operator<<() [12/12]

std::ostream & Boardcore::operator<< ( std::ostream & os,
const StatsResult & sr )

Allows printing StatsResult to an ostream.

◆ operator==()

bool Boardcore::operator== ( const GammaConf & lhs,
const GammaConf & rhs )
inline

Definition at line 88 of file GammaTypes.h.

◆ operator>>() [1/6]

void Boardcore::operator>> ( const AccelerometerData & lhs,
Eigen::Vector3f & rhs )

Definition at line 72 of file SensorDataExtra.cpp.

◆ operator>>() [2/6]

void Boardcore::operator>> ( const Eigen::Vector3f & lhs,
AccelerometerData & rhs )

Definition at line 77 of file SensorDataExtra.cpp.

◆ operator>>() [3/6]

void Boardcore::operator>> ( const Eigen::Vector3f & lhs,
GyroscopeData & rhs )

Definition at line 84 of file SensorDataExtra.cpp.

◆ operator>>() [4/6]

void Boardcore::operator>> ( const Eigen::Vector3f & lhs,
MagnetometerData & rhs )

Definition at line 91 of file SensorDataExtra.cpp.

◆ operator>>() [5/6]

void Boardcore::operator>> ( const GyroscopeData & lhs,
Eigen::Vector3f & rhs )

Definition at line 82 of file SensorDataExtra.cpp.

◆ operator>>() [6/6]

void Boardcore::operator>> ( const MagnetometerData & lhs,
Eigen::Vector3f & rhs )

Definition at line 86 of file SensorDataExtra.cpp.

◆ orientationToVector()

Eigen::Vector3f Boardcore::orientationToVector ( Direction direction)
inline

Definition at line 50 of file AxisOrientation.h.

◆ pitotDataFromCanMessage()

CanPitotData Boardcore::pitotDataFromCanMessage ( const Canbus::CanMessage & msg)
inline

Definition at line 435 of file CanProtocolTypes.h.

◆ pressureDataFromCanMessage()

CanPressureData Boardcore::pressureDataFromCanMessage ( const Canbus::CanMessage & msg)
inline

Definition at line 448 of file CanProtocolTypes.h.

◆ servoCommandFromCanMessage()

CanServoCommand Boardcore::servoCommandFromCanMessage ( const Canbus::CanMessage & msg)
inline

Definition at line 540 of file CanProtocolTypes.h.

◆ servoDataFromCanMessage()

CanServoData Boardcore::servoDataFromCanMessage ( const Canbus::CanMessage & msg)
inline

Definition at line 485 of file CanProtocolTypes.h.

◆ servoFeedbackFromCanMessage()

CanServoFeedback Boardcore::servoFeedbackFromCanMessage ( const Canbus::CanMessage & msg)
inline

Definition at line 552 of file CanProtocolTypes.h.

◆ skywardStack()

unsigned int Boardcore::skywardStack ( unsigned int stack)
inline

Definition at line 36 of file SkywardStack.h.

◆ sToNs()

constexpr long long Boardcore::sToNs ( long long s)
constexpr

Convert seconds to nanoseconds.

Parameters
sSeconds.
Returns
Nanoseconds.

Definition at line 64 of file TimeUtils.h.

◆ temperatureDataFromCanMessage()

CanTemperatureData Boardcore::temperatureDataFromCanMessage ( const Canbus::CanMessage & msg)
inline

Definition at line 460 of file CanProtocolTypes.h.

◆ toCanMessage() [1/10]

Canbus::CanMessage Boardcore::toCanMessage ( const BatteryVoltageSensorData & data)
inline

Definition at line 370 of file CanProtocolTypes.h.

◆ toCanMessage() [2/10]

Canbus::CanMessage Boardcore::toCanMessage ( const CurrentData & data)
inline

Definition at line 339 of file CanProtocolTypes.h.

◆ toCanMessage() [3/10]

Canbus::CanMessage Boardcore::toCanMessage ( const DeviceStatus & data)
inline

Definition at line 394 of file CanProtocolTypes.h.

◆ toCanMessage() [4/10]

Canbus::CanMessage Boardcore::toCanMessage ( const PitotData & data)
inline

Definition at line 303 of file CanProtocolTypes.h.

◆ toCanMessage() [5/10]

Canbus::CanMessage Boardcore::toCanMessage ( const PressureData & data)
inline

Definition at line 315 of file CanProtocolTypes.h.

◆ toCanMessage() [6/10]

Canbus::CanMessage Boardcore::toCanMessage ( const ServoCommand & data)
inline

Definition at line 410 of file CanProtocolTypes.h.

◆ toCanMessage() [7/10]

Canbus::CanMessage Boardcore::toCanMessage ( const ServoData & data)
inline

Definition at line 351 of file CanProtocolTypes.h.

◆ toCanMessage() [8/10]

Canbus::CanMessage Boardcore::toCanMessage ( const ServoFeedback & data)
inline

Definition at line 422 of file CanProtocolTypes.h.

◆ toCanMessage() [9/10]

Canbus::CanMessage Boardcore::toCanMessage ( const TemperatureData & data)
inline

Definition at line 327 of file CanProtocolTypes.h.

◆ toCanMessage() [10/10]

Canbus::CanMessage Boardcore::toCanMessage ( const VoltageData & data)
inline

Definition at line 382 of file CanProtocolTypes.h.

◆ voltageDataFromCanMessage()

CanVoltageData Boardcore::voltageDataFromCanMessage ( const Canbus::CanMessage & msg)
inline

Definition at line 512 of file CanProtocolTypes.h.

Variable Documentation

◆ DEFAULT_MAPPING

static constexpr DioMapping Boardcore::DEFAULT_MAPPING = DioMapping(0, 0, 0, 1, 0, 0, false)
constexpr

Definition at line 44 of file SX1278Fsk.cpp.

◆ humanFriendlyDirection

constexpr const char* Boardcore::humanFriendlyDirection[]
constexpr
Initial value:
{
"North", "South", "East", "West", "Down", "Up",
}

Definition at line 46 of file AxisOrientation.h.