-
Notifications
You must be signed in to change notification settings - Fork 3
Developing Sensor Drivers
A large portion of the CU InSpace code base is sensor drivers. Every sensor needs to provided a set of functions to initialize the sensor for which it is responsable and to read and interpret data from it. Our sensor drivers all follow roughly the same structure. This document will use the driver for the MS5611/MS5607 barometric altimeter as an example to demonstrate how drivers can be written.
This document describes how to structure a driver such that it will be compatible with the rest of the CU InSpace avionics code. It cannot however provide details on how to interface with any given sensor: every part is different.
The datasheets for all of the parts we are using are listed on the Datasheets page. When implementing a driver, you will need to reference the datasheet constantly. Everything you need to know about the sensor's capabilities, serial interfaces, register layouts, commands, data formats and any processing required to derive a final value from the sensor's output will almost always be included in the datasheet.
Before starting work on the driver for a part, read its datasheet. From cover to cover. Read the important parts (serial interfaces, register descriptions, maximum ratings, etc.) more than once. Trust me, it's better to read the datasheet first and write the driver once, rather than writing the driver, reading the datasheet, then re-writing the driver.
In this document is, for the most part, written in such a way that it is general enough to apply to any sensor we might be working with. The MS5611 driver is used as an example, but keep in mind that not all sensors have the same interface as the MS5611. The MS5611 is a particularly simple sensor, most will be much more complex. Your millage may vary: once again, read the datasheet!
The sensors we use are connected to the microcontroller over a serial interface (usually I2C or SPI). The majority of the sensor's interfaces consist of reading from and writing to a number of registers and/or sending short commands to the sensors over the serial interface. The details of using the serial interfaces to send and receive bytes from external peripherals are described in Serial Interfaces.
The MS5611 is a fairly simple device. It has 5 commands:
| Command | Bytes Sent | Bytes Received |
|---|---|---|
| Reset | 1 | 0 |
| Read PROM | 1 | 2 |
| Start Pressure Conversion | 1 | 0 |
| Start Temperature Conversion | 1 | 0 |
| Read Result | 0 | 3 |
The Read PROM command is able to read any of eight 16 bit PROM values, which are constants stored on the chip during manufacturing. The 3 bit address of the desired value is encoded in the command byte. The Start Pressure Conversion and Start Temperature Conversion commands also have some additional information encoded in the command.
To read all the data required to calculate the altitude from the barometer, the following sequence of commands is used:
- Read PROM (C1 through C6, 6 separate commands)
- Start Pressure Conversion
- Read Result
- Start Temperature Conversion
- Read Result
Many sensors do not have explicit commands, instead they are controlled and read by accessing registers. Interacting with these devices consists of sending an address to the sensor (usually one or two bytes) along with a bit that indicates whether you plan to either send data to be written to that address or read the data that is stored at that address.
The address map and register descriptions and/or list of commands will be provided in the sensor's datasheet.
Most sensor drivers should consist of three files.
-
<part number>-registers.hor<part number>-commands.h <part number>.h<part number>.c
The registers or commands header contains preprocessor macros for all of the commands and/or register addresses as well as all of the fields in the commands. It should also have the I2C address for sensors connected to the I2C bus. You may also want to write structures to represent the register formats if there are many registers which are divided into subfields. In the repository, ms5611-commands.h is a good example of a header file with defines a list of commands and some values to help encode arguments in them as well as an I2C address (note that the address is exactly 7 bits long). mcp23s17-registers.h is an example of a header file that describes all of the registers for a part (ignore the register map structure at the end though, for most parts it is unnecessary).
The other header file contains the declaration for the driver instance descriptor, the declarations of any subtypes within the instance descriptor such as enums and the declarations for all of the drivers functions.
The c file contains the actual code of the driver, as described later on in this document. It needs to #include the two header files.
We want to write most of our drivers in such a way that they could, in theory, be used with multiple instances of the sensor connected at once. For example, the MS5611 driver needs to be able to work with two pressure sensors, one is used to calculate altitude and the other can be used for a pitot tube. In order to accomplish this, we use a structure which contains all of the information associated with a certain physical sensor. A pointer to an instance of this structure is passed as part of every call to a function in the driver so that the same functions can be used with multiple instances.
The instance descriptor structure should contain the following data:
- The serial driver instance (SERCOM SPI, I2C or UART descriptor) used to communicate with the peripheral and a place to store a transaction ID
- Any other information required to communicate with the correct peripheral such as the I2C address or SPI chip select pin
- Buffers for data read from the sensor
- The last system time at which the sensor was read (copied from the global
millisvariable) - Any intermediate values used in calculations or other state which needs to be preserved between calls to the drivers service function
- The current state of the driver finite state machine and any other data or flags used by the state machine
- Any settings related to a specific driver instance
The MS5611 descriptor, defined in ms5611.h looks like this:
struct ms5611_desc_t {
// I2C Information
struct sercom_I2C_desc_t *I2C_instance;
uint8_t address;
uint8_t I2C_transaction_id;
// Data read from sensor
uint32_t last_reading_time;
int32_t pressure;
int32_t temperature;
float altitude;
uint16_t prom_values[6];
// Intermediate values used in calculations and other state
float p0;
uint32_t d1;
uint32_t d2;
uint32_t conv_start_time;
// Settings
uint32_t period;
bool calc_altitude;
// Current FSM state
enum ms5611_state state;
bool I2C_in_progress;
bool p0_set;
};Note that the code in the above code snippet has been re-arranged to better illustrate the type of information which should be stored in a driver's descriptor structure. It is not properly documented and its fields are not in an efficient order. To see how it should be laid out to avoid padding within the structure take a look at ms5611.h in the repository.
Each driver provides two main functions as well as a set of functions for retrieving data. Sensor drivers may also have additional functions to expose functionality specific to a certain sensor. The functions defined in ms5611.h look like this:
extern void init_ms5611 (struct ms5611_desc_t *inst,
struct sercom_I2C_desc_t *I2C_inst, uint8_t csb,
uint32_t period, uint8_t calculate_altitude);
extern void ms5611_service (struct ms5611_desc_t *inst);
extern int32_t ms5611_get_pressure (struct ms5611_desc_t *inst);
extern int32_t ms5611_get_temperature (struct ms5611_desc_t *inst);
extern float ms5611_get_altitude (struct ms5611_desc_t *inst);
extern uint32_t ms5611_get_last_reading_time (struct ms5611_desc_t *inst);
extern void ms5611_set_period (struct ms5611_desc_t *inst, uint32_t period);
extern void ms5611_tare_now (struct ms5611_desc_t *inst);
extern void ms5611_tare_next (struct ms5611_desc_t *inst);This code snippet has been simplified by making all of the functions external. In the actual driver many of the smaller functions (but not init or service) are implemented as static inline functions directly in the header file to avoid the overhead of calling them. To see how the the code can be optimized in this way look at ms5611.h in the repository.
All drivers should have an init function (even if it doesn't do anything, though that would be an exceptional case). This function is responsible for beginning the process of initializing the sensor. Due to the asynchronicity of the serial drivers (see Serial Interfaces), in most cases it will not be possible to complete the initialization process in the init function. The init function should do any work necessary to initialize the instance descriptor (without making any assumptions about its state, ie. all values for which the initial values matter should be initialized), set the current state appropriately and then call the service function to start the process of writing to or reading from the sensor in order to initialize it.
In addition to a pointer to an instance descriptor, the initialization function should take arguments to specify the serial interface used to communicate with the sensor and the sensor's address or chip select pin. The init function may also take additional arguments to specify other options for the driver instance.
Here is the init function for the MS5611 driver from ms5611.c:
void init_ms5611 (struct ms5611_desc_t *inst,
struct sercom_I2C_desc_t *I2C_inst, uint8_t csb,
uint32_t period, uint8_t calculate_altitude)
{
inst->address = MS5611_ADDR | ((csb) << MS5611_ADDR_CSB_Pos);
inst->period = period;
inst->calc_altitude = !!calculate_altitude;
inst->I2C_inst = I2C_inst;
inst->p0_set = 0;
// Start by reading the factory calibration data
inst->state = MS5611_READ_C1;
ms5611_service(inst);
}The init function for the MS5611 driver stores the I2C instance descriptor and I2C address for the sensor, which it calculates based on the base address (which is provided in the datasheet) and the csb value. The csb value passed to the init function reflects the value connected to the physical csb pin of the sensor. It is common for I2C sensors to have physical pins which change one or more bits of their address in order to allow for more than one of the same model of sensor to be connected to the same I2C bus. MS5611_ADDR and MS5611_ADDR_CSB_Pos are defined in ms5611-commands.h.
The MS5611 driver's initializer also takes the period of time between sensor reads as an argument. Most sensors need to be polled periodically and should take the polling period as an argument to the initializer so that it can be configured at compile time on a per instance basis. The final argument to the init function is calculate_altitude which is a boolean value indicating whether the driver should calculate an altitude value each time it polls the sensor. The code to calculate the altitude consists of CPU intensive floating point math, so it is better to avoid executing it if only the pressure value is needed (like for the pressure sensor connected to the pitot tube).
After setting all of the other necessary values in the descriptor structure, the MS5611 initialization function sets the instance's state to the first state in the drivers initialization process and runs the service function so that initialization can start immediately.
The service function is called regularly by the main loop in main.c. There is no guarantee as to how often the service function will be called, but it is generally safe to assume that it will be called at a rate of at least one kilohertz, and sometimes more often than that. In theory, it is also possible that it could be called less often if another driver or task is performing an operation which takes a lot of CPU time but this is unlikely.
It is important that we do not block within the service function, any time spend busy waiting is wasting cycles that could have been given to another module's service function. No blocking means that we cannot call any type of sleep or wait function or any blocking IO function. It also means that we cannot use use loops unless the loop condition will be made false by code inside of the loop. Unfortunately, these constraints conflict with the realities of how serial interfaces and sensors work. Serial interfaces are much slower than the CPU and a driver will spend a lot of time waiting for bytes to be read or written from the peripheral. Additionally many sensors have timing constraints. For example with the MS5611, after starting an analog to digital conversion it is necessary to wait before before reading back the result as reading the result while a conversion is in progress will corrupt the conversion.
In order to satisfy these two sets of design constraints we use a finite state machine model. What this means is that we look at everything that the driver needs to do and split it into a number of states, the boundaries between states being blocking operations. We keep track of which state the driver is in so that when the service function is called it knows exactly where to resume execution. If the driver is able to complete whatever task it needs to do in its current state it moves into the next state before returning from the service function.
As a simplified example we will imagine that, as a safety feature, we want to integrate a sensor which will measure how phlogisticated the air around the rocket is before launch. Our hypothetical phlogistication sensor has two registers, a 16 bit control register that we write to in order to change settings and a 16 bit result register from which we can read the output of the sensor's analog to digital converter. The following flow chart shows the logic that our sensor driver needs to implement in order to get data from the sensor.
For the "Waiting for Data to be Ready" state we could be waiting for specific amount of time or for an interrupt from the sensor (as described later in this document), but for the purposes of this example we will just assume that there is a magic variable called data_ready that becomes non-zero when data is ready. Here is some pseudocode for a very basic implementation of the above flowchart:
serial_interface_write_blocking(address = CONFIG, data = CONFIGURATION_DATA);
for (;;) {
while (!data_ready);
relative_phlogiston_level = serial_interface_read_blocking(address = RESULT);
}This is easy enough: the driver only has to write the configuration data to the configuration register then endlessly wait for new data to be ready and read it. The problem is that each of the tasks in our state machine is blocking. Writing the configuration data to the sensor over a serial interface is going to take quite a long time, but will be handled by the serial interface hardware; the CPU could work on something else while the transfer is going on. Waiting for the data to be ready will probably also take a long time; the sensor is probably a lot slower than our microcontroller, and if something goes wrong the data could never become ready leaving us stuck waiting forever. Finally, reading the data back is another serial interface transaction that will take a long time but could be done asynchronously.
To implement this logic in an asynchronous fashion, we can create a finite state machine that splits the above process into multiple states. That way we can write a service function to check the current state and perform an operation based on it. That FSM would look something like this:
Now we have five states. Each state has a condition that is required to leave the state or action that must be completed. Here is a summary of the states for our phlogistication sensor driver:
| State | Action | Exit Condition | Next State |
|---|---|---|---|
| Configure | Start a serial transaction to write configuration data to sensor | Move immediately to next state | First Wait for IO |
| First Wait for IO | None | Serial transaction is complete | Wait for Data |
| Wait for Data (idle) | None | The sensor has data ready to be read | Read Result |
| Read Result | Start a serial transaction to read phlogistication data from sensor | Move immediately to next state | Second Wait for IO |
| Second Wait for IO | None | Serial transaction is complete | Wait for Data |
Splitting the driver into these states lets us write a service function that returns between each state. This means that the driver does not have to take up any CPU time while blocking operations are ongoing. Here is some pseudocode for a basic service function based on the above FSM:
enum phlogistication_sensor_state {
CONFIGURE,
CONFIGURE_WAIT,
IDLE,
READ_RESULT,
READ_RESULT_WAIT
};
void service (struct phlogistication_sensor_instance *inst)
{
switch (inst->state) {
case CONFIGURE:
// Start writing configuration data
serial_start_write(address = CONFIG, data = CONFIGURATION_DATA);
// Go to the next state
inst->state = CONFIGURE_WAIT;
/* fall through */
case CONFIGURE_WAIT:
if (serial_transaction_done()) {
// Clean up transaction
serial_transaction_clear();
// Go to the next state
inst->state = IDLE;
/* fall through */
} else {
// Transaction is not yet done
// Break for now and check again next time the service is run
break;
}
case IDLE:
if (data_ready) {
// Go to the next state
inst->state = READ_RESULT;
/* fall through */
} else {
// Data is not ready yet
// Break for now and check again next time the service is run
break;
}
case READ_RESULT:
// Start reading
serial_start_read(address = RESULT);
// Go to the next state
inst->state = READ_RESULT_WAIT;
/* fall through */
case READ_RESULT_WAIT:
if (serial_transaction_done()) {
// Clean up transaction
serial_transaction_clear();
// Go to the next state
inst->state = IDLE;
} else {
// Transaction is not yet done
// Break for now and check again next time the service is run
}
break;
}
}Notice that in the above code everywhere where we would have had to block we instead return from the service function. Every time the service function is called we check if whatever we are currently waiting for is finished.
Service functions get called a lot, but the vast majority of the time they have nothing to do. This can make it worth while to try and make sure that the service function returns as soon as possible if it is not going to be able to do anything. A simple optimization which can help make sure that the service wastes as little time as possible before returning is to have a separate flag outside of the current state enum which indicates whether there is a transaction currently in progress on the serial interface. If there is, the service function can check whether the transaction is complete before doing anything else and return if it is not. The MS5611 driver makes use of this technique, which also lets it combine the transaction start and transaction wait states for reads and writes. Additionally, the MS5611 driver uses separate functions which handle read and write states in order to avoid code reuse. See ms5611.c for an example of a fairly detailed sensor driver state machine. rn2483.c is also a good service function state machine example.
Sensor drivers should generally also provide functions for getting the final values from the sensor. They may have other functions which change settings or perform other operations specific to a certain sensor. In general, nothing outside of the sensor driver should have to touch the instance descriptor structure, so there should be functions to facilitate access to any members which may need to be accessed externally. Often these functions are one or two line wrappers that just return a value from the descriptor structure that they are passed as an argument. Since they are so simple these short functions are good candidates for inlining, to facilitate this they should be defined as static inline functions directly in the header file. Functions that do anything more than retrieving values from the descriptor or setting values in the descriptor should be declared in the header as extern and defined normally in the c file.
Many sensors have interrupt pins which they can use to indicate certain events or states to the microcontroller without having to be polled. Commonly, the interrupt pin can be configured to indicate when new data is available to be read. When available, this is much better than repeatedly polling the sensor or waiting a fixed amount of time.
When writing a sensor driver that makes use of an interrupt, the GPIO driver should be used. The GPIO driver provides the gpio_enable_interrupt function which can be used to configure and interrupt on any pin and provide a callback function when the interrupt occurs. The callback function will be called when the appropriate edge (as specified in the arguments togpio_enable_interrupt ) happens. This callback function should not perform any work. Instead, it should set a flag which can be used by the service function to progress to a new FSM state. The interrupt can also change the driver FSM state directly, but care should be taken to make sure that the FSM is in the correct state before the state is changed so that interrupt does not cause the driver to skip states or to be resurrected from a failed state.