Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
invensense2.c
Go to the documentation of this file.
1/*
2 * Copyright (C) 2022 Freek van Tienen <freek.v.tienen@gmail.com>
3 *
4 * This file is part of paparazzi.
5 *
6 * paparazzi is free software; you can redistribute it and/or modify
7 * it under the terms of the GNU General Public License as published by
8 * the Free Software Foundation; either version 2, or (at your option)
9 * any later version.
10 *
11 * paparazzi is distributed in the hope that it will be useful,
12 * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 * GNU General Public License for more details.
15 *
16 * You should have received a copy of the GNU General Public License
17 * along with paparazzi; see the file COPYING. If not, write to
18 * the Free Software Foundation, 59 Temple Place - Suite 330,
19 * Boston, MA 02111-1307, USA.
20 */
21
31#include "math/pprz_isa.h"
33#include "modules/imu/imu.h"
34#include "modules/core/abi.h"
35#include "mcu_periph/gpio_arch.h"
36
37
38/* Local functions */
39static void invensense2_parse_data(struct invensense2_t *inv, volatile uint8_t *data, uint16_t len);
40static void invensense2_fix_config(struct invensense2_t *inv);
44static bool invensense2_config(struct invensense2_t *inv);
45
46/* Default gyro scalings */
47static const struct FloatRates invensense2_gyro_scale_f[5] = {
48 {0.545415, 0.545415, 0.545415}, // 250DPS: RATE_BFP_OF_REAL(radians(250)/(2**15))
49 {1.09083, 1.09083, 1.09083}, // 500DPS
50 {2.18166, 2.18166, 2.18166}, // 1000DPS
51 {4.36332, 4.36332, 4.36332}, // 2000DPS
52 {8.72664, 8.72664, 8.72664}, // 4000DPS
53};
54
55/* Default accel scalings */
56static const struct FloatVect3 invensense2_accel_scale_f[5] = {
57 {0.61312, 0.61312, 0.61312}, // 2G: ACCEL_BFP_OF_REAL(2G*9.81/(2**15))
58 {1.22583, 1.22583, 1.22583}, // 4G
59 {2.4525, 2.4525, 2.4525}, // 8G
60 {4.905, 4.905, 4.905}, // 16G
61 {9.196875, 9.196875, 9.196875}, // 30G
62};
63
70 /* General setup */
71 inv->status = INVENSENSE2_IDLE;
72 inv->device = INVENSENSE2_UNKOWN;
73 inv->register_bank = 0xFF;
74 inv->config_idx = 0;
75
76 /* SPI setup */
77 if(inv->bus == INVENSENSE2_SPI) {
78 inv->spi.trans.cpol = SPICpolIdleHigh;
79 inv->spi.trans.cpha = SPICphaEdge2;
80 inv->spi.trans.dss = SPIDss8bit;
81 inv->spi.trans.bitorder = SPIMSBFirst;
82 inv->spi.trans.cdiv = SPIDiv16;
83
84 inv->spi.trans.select = SPISelectUnselect;
85 inv->spi.trans.slave_idx = inv->spi.slave_idx;
86 inv->spi.trans.output_length = 0;
87 inv->spi.trans.input_length = 0;
88 inv->spi.trans.before_cb = NULL;
89 inv->spi.trans.after_cb = NULL;
90 inv->spi.trans.input_buf = inv->spi.rx_buf;
91 inv->spi.trans.output_buf = inv->spi.tx_buf;
92 inv->spi.trans.status = SPITransDone;
93 }
94 /* I2C setup */
95 else {
96 inv->i2c.trans.slave_addr = inv->i2c.slave_addr;
97 inv->i2c.trans.status = I2CTransDone;
98 }
99}
100
110 /* Idle */
111 if((inv->bus == INVENSENSE2_SPI && inv->spi.trans.status == SPITransDone) ||
112 (inv->bus == INVENSENSE2_I2C && inv->i2c.trans.status == I2CTransDone)) {
113
114 /* Depending on the status choose what to do */
115 switch(inv->status) {
116 case INVENSENSE2_IDLE:
117 /* Request WHO_AM_I */
119 break;
121 /* Start configuring */
123 inv->status = INVENSENSE2_RUNNING;
124 }
125 break;
127 /* Request a sensor reading */
129 break;
130 }
131 }
132}
133
143 volatile uint8_t *rx_buffer, *tx_buffer;
144 uint16_t rx_length = 0;
145
146 /* Set the buffers depending on the interface */
147 if(inv->bus == INVENSENSE2_SPI) {
148 rx_buffer = inv->spi.rx_buf;
149 tx_buffer = inv->spi.tx_buf;
150 rx_length = inv->spi.trans.input_length;
151 }
152 else {
153 rx_buffer = inv->i2c.trans.buf;
154 tx_buffer = inv->i2c.trans.buf;
155 rx_length = inv->i2c.trans.len_r;
156 }
157
158 /* Successful transfer */
159 if((inv->bus == INVENSENSE2_SPI && inv->spi.trans.status == SPITransSuccess) ||
160 (inv->bus == INVENSENSE2_I2C && inv->i2c.trans.status == I2CTransSuccess)) {
161
162 /* Update the register bank */
163 if(tx_buffer[0] == INV2REG_BANK_SEL)
164 inv->register_bank = inv->spi.tx_buf[1] >> 4;
165
166 /* Set the transaction as done and update register bank if needed */
167 if(inv->bus == INVENSENSE2_SPI)
168 inv->spi.trans.status = SPITransDone;
169 else
170 inv->i2c.trans.status = I2CTransDone;
171
172 /* Look at the results */
173 switch(inv->status) {
174 case INVENSENSE2_IDLE:
175 /* Check the response of the WHO_AM_I */
176 if(rx_buffer[1] == INV2_WHOAMI_ICM20648) {
177 inv->device = INVENSENSE2_ICM20648;
178 inv->status = INVENSENSE2_CONFIG;
179 } else if(rx_buffer[1] == INV2_WHOAMI_ICM20649) {
180 inv->device = INVENSENSE2_ICM20649;
181 inv->status = INVENSENSE2_CONFIG;
182 } else if(rx_buffer[1] == INV2_WHOAMI_ICM20948) {
183 inv->device = INVENSENSE2_ICM20948;
184 inv->status = INVENSENSE2_CONFIG;
185 }
186
187 /* Fix the configuration and set the scaling */
188 if(inv->status == INVENSENSE2_CONFIG)
190 break;
192 /* Apply the next configuration register */
194 inv->status = INVENSENSE2_RUNNING;
195 }
196 break;
197 case INVENSENSE2_RUNNING: {
198 /* Parse the results */
199 static const uint16_t max_bytes = sizeof(inv->spi.rx_buf) - 3;
200 uint16_t fifo_bytes = (uint16_t)rx_buffer[1] << 8 | rx_buffer[2];
201
202 // We read an incorrect length (try again)
203 if(fifo_bytes > 4096) {
205 return;
206 }
207
208 // Parse the data
209 if((rx_length - 3) > 0) {
210 uint16_t valid_bytes = ((rx_length - 3) < fifo_bytes)? (rx_length - 3) : fifo_bytes;
211 invensense2_parse_data(inv, &rx_buffer[3], valid_bytes);
212 inv->timer -= valid_bytes;
213 } else {
215 inv->timer = fifo_bytes;
216 }
217
218 // If we have more data request more
219 if(inv->timer > 0) {
220 uint16_t read_bytes = (inv->timer > max_bytes)? max_bytes : inv->timer;
222 }
223 break;
224 }
225 }
226 }
227 /* Failed transaction */
228 if((inv->bus == INVENSENSE2_SPI && inv->spi.trans.status == SPITransFailed) ||
229 (inv->bus == INVENSENSE2_I2C && inv->i2c.trans.status == I2CTransFailed)) {
230
231 /* Set the transaction as done and update register bank if needed */
232 if(inv->bus == INVENSENSE2_SPI) {
233 inv->spi.trans.status = SPITransDone;
234 }
235 else {
236 inv->i2c.trans.status = I2CTransDone;
237 }
238
239 /* Retry or ignore */
240 switch(inv->status) {
242 /* If was not a bus switch decrease the index */
243 if(inv->config_idx > 0 && ((inv->bus == INVENSENSE2_SPI && inv->spi.tx_buf[0] != INV2REG_BANK_SEL) ||
244 (inv->bus == INVENSENSE2_I2C && inv->i2c.trans.buf[0] != INV2REG_BANK_SEL))) {
245 inv->config_idx--;
246 }
247 /* Try again */
249 inv->status = INVENSENSE2_RUNNING;
250 }
251 break;
252 case INVENSENSE2_IDLE:
254 /* Ignore while idle/running */
255 break;
256 }
257 }
258}
259
267static void invensense2_parse_data(struct invensense2_t *inv, volatile uint8_t *data, uint16_t len) {
269 static struct Int32Vect3 accel[INVENSENSE2_SAMPLE_CNT] = {0};
270 static struct Int32Rates gyro[INVENSENSE2_SAMPLE_CNT] = {0};
271
274
275 uint16_t gyro_samplerate = 9000;
276 if(inv->gyro_dlpf != INVENSENSE2_GYRO_DLPF_OFF)
277 gyro_samplerate = 1125;
278
279 uint16_t accel_samplerate = 4500;
280 if(inv->accel_dlpf != INVENSENSE2_ACCEL_DLPF_OFF)
281 accel_samplerate = 1125;
282
283 // Go through the different samples
284 uint8_t j = 0;
285 uint8_t downsample = gyro_samplerate / accel_samplerate;
286 int32_t temp = 0;
287 for(uint8_t i = 0; i < samples; i++) {
288 if(i % downsample == 0) {
289 accel[j].x = (int16_t)((uint16_t)data[2] << 8 | data[3]);
290 accel[j].y = (int16_t)((uint16_t)data[0] << 8 | data[1]);
291 accel[j].z = -(int16_t)((uint16_t)data[4] << 8 | data[5]);
292 j++;
293 }
294
295 gyro[i].p = (int16_t)((uint16_t)data[8] << 8 | data[9]);
296 gyro[i].q = (int16_t)((uint16_t)data[6] << 8 | data[7]);
297 gyro[i].r = -(int16_t)((uint16_t)data[10] << 8 | data[11]);
298
299 temp += (int16_t)((uint16_t)data[12] << 8 | data[13]);
301 }
302
303 float temp_f = ((float)temp / samples) / 333.87f + 21.f;
304
305 // Send the scaled values over ABI
307 AbiSendMsgIMU_GYRO_RAW(inv->abi_id, now_ts, gyro, samples, gyro_samplerate*(1+inv->timebase_correction_pll/100.f), temp_f);
308 AbiSendMsgIMU_ACCEL_RAW(inv->abi_id, now_ts, accel, j, accel_samplerate*(1+inv->timebase_correction_pll/100.f), temp_f);
309}
310
317 /* Fix wrong configuration settings (prevent user error) */
318 if(inv->device == INVENSENSE2_ICM20649) {
319 if(inv->gyro_range == INVENSENSE2_GYRO_RANGE_250DPS)
321 if(inv->accel_range == INVENSENSE2_ACCEL_RANGE_2G)
322 inv->accel_range = INVENSENSE2_ACCEL_RANGE_4G;
323 }
324 else {
325 if(inv->gyro_range == INVENSENSE2_GYRO_RANGE_4000DPS)
327 if(inv->accel_range == INVENSENSE2_ACCEL_RANGE_30G)
328 inv->accel_range = INVENSENSE2_ACCEL_RANGE_16G;
329 }
330
331 /* Set the default values */
334}
335
346 /* Split the register and bank */
347 uint8_t bank = bank_reg >> 8;
348 uint8_t reg = bank_reg & 0xFF;
349
350 /* Switch the register bank if needed */
352 return false;
353 }
354
355 /* SPI transaction */
356 if(inv->bus == INVENSENSE2_SPI) {
357 inv->spi.trans.output_length = 2;
358 inv->spi.trans.input_length = 0;
359 inv->spi.tx_buf[0] = reg;
360 inv->spi.tx_buf[1] = value;
361 spi_submit(inv->spi.p, &(inv->spi.trans));
362 }
363 /* I2C transaction */
364 else {
365 inv->i2c.trans.buf[0] = reg;
366 inv->i2c.trans.buf[1] = value;
367 i2c_transmit(inv->i2c.p, &(inv->i2c.trans), inv->i2c.slave_addr, 2);
368 }
369
370 return true;
371}
372
383 /* Split the register and bank */
384 uint8_t bank = bank_reg >> 8;
385 uint8_t reg = bank_reg & 0xFF;
386
387 /* Switch the register bank if needed */
389 return false;
390 }
391
392 /* SPI transaction */
393 if(inv->bus == INVENSENSE2_SPI) {
394 inv->spi.trans.output_length = 2;
395 inv->spi.trans.input_length = 1 + size;
396 inv->spi.tx_buf[0] = reg | INV2_READ_FLAG;
397 inv->spi.tx_buf[1] = 0;
398 spi_submit(inv->spi.p, &(inv->spi.trans));
399 }
400 /* I2C transaction */
401 else {
402 inv->i2c.trans.buf[0] = reg | INV2_READ_FLAG;
403 i2c_transceive(inv->i2c.p, &(inv->i2c.trans), inv->i2c.slave_addr, 1, (1 + size));
404 }
405
406 return true;
407}
408
418 /* If we already selected the correct bank continue */
419 if(inv->register_bank == bank)
420 return false;
421
422 /* SPI transaction */
423 if(inv->bus == INVENSENSE2_SPI) {
424 inv->spi.trans.output_length = 2;
425 inv->spi.trans.input_length = 0;
426 inv->spi.tx_buf[0] = INV2REG_BANK_SEL;
427 inv->spi.tx_buf[1] = bank << 4;
428 spi_submit(inv->spi.p, &(inv->spi.trans));
429 }
430 /* I2C transaction */
431 else {
432 inv->i2c.trans.buf[0] = INV2REG_BANK_SEL;
433 inv->i2c.trans.buf[1] = bank << 4;
434 i2c_transmit(inv->i2c.p, &(inv->i2c.trans), inv->i2c.slave_addr, 2);
435 }
436
437 return true;
438}
439
448 switch(inv->config_idx) {
449 case 0:
450 /* Reset the device */
452 inv->config_idx++;
453 inv->timer = get_sys_time_usec();
454 break;
455 case 1: {
456 /* Reset I2C and FIFO SRAM, disable I2C if using SPI */
458 if(inv->bus == INVENSENSE2_SPI)
460
461 /* Because reset takes time wait ~100ms */
462 if((get_sys_time_usec() - inv->timer) < 100000)
463 break;
464
466 inv->config_idx++;
467 break;
468 }
469 case 2:
470 /* Wakeup the device in auto clock mode */
472 inv->config_idx++;
473 inv->timer = get_sys_time_usec();
474 break;
475 case 3: {
476 /* Configure gyro */
478 if(inv->gyro_dlpf != INVENSENSE2_GYRO_DLPF_OFF)
479 gyro_config |= BIT_GYRO_DLPF_ENABLE | ((inv->gyro_dlpf - 1) << GYRO_DLPF_CFG_SHIFT);
480 if((inv->device == INVENSENSE2_ICM20649 && inv->gyro_range > 0) || inv->gyro_range > 3)
481 gyro_config |= (inv->gyro_range - 1) << GYRO_FS_SEL_SHIFT;
482 else
483 gyro_config |= inv->gyro_range << GYRO_FS_SEL_SHIFT;
484
485 /* Because reset takes time wait ~100ms */
486 if((get_sys_time_usec() - inv->timer) < 100000)
487 break;
488
490 inv->config_idx++;
491 break;
492 }
493 case 4: {
494 /* Configure accelerometer */
496 if(inv->accel_dlpf != INVENSENSE2_ACCEL_DLPF_OFF)
498 if((inv->device == INVENSENSE2_ICM20649 && inv->accel_range > 0) || inv->accel_range > 3)
499 accel_config |= (inv->accel_range - 1) << ACCEL_FS_SEL_SHIFT;
500 else
501 accel_config |= inv->accel_range << ACCEL_FS_SEL_SHIFT;
503 inv->config_idx++;
504 break;
505 }
506 case 5:
507 /* Request TIMEBASE_CORRECTION_PLL */
509 inv->config_idx++;
510 break;
511 case 6:
512 /* Read the TIMEBASE_CORRECTION_PLL */
513 if(inv->bus == INVENSENSE2_SPI) {
514 inv->timebase_correction_pll = ((int8_t)inv->spi.rx_buf[1]) * 0.079f;
515 }
516 else {
517 inv->timebase_correction_pll = ((int8_t)inv->i2c.trans.buf[1]) * 0.079f;
518 }
519
520 /* Set the FIFO mode */
522 inv->config_idx++;
523 break;
524 case 7:
525 /* Set the GYRO sample rate divider */
527 inv->config_idx++;
528 break;
529 case 8:
530 /* FIFO reset 1 */
532 inv->config_idx++;
533 break;
534 case 9:
535 /* FIFO reset 2 */
537 inv->config_idx++;
538 break;
539 case 10: {
540 /* Enable FIFO */
542 if(inv->bus == INVENSENSE2_SPI)
545 inv->config_idx++;
546 break;
547 }
548 case 11:
549 /* Cofigure FIFO enable */
552 inv->config_idx++;
553 break;
554 case 12:
555 /* Enable interrupt pin/status */
557 inv->config_idx++;
558 break;
559 default:
560 inv->timer = 0;
561 return true;
562 }
563 return false;
564}
Main include for ABI (AirBorneInterface).
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
bool i2c_transmit(struct i2c_periph *p, struct i2c_transaction *t, uint8_t s_addr, uint8_t len)
Submit a write only transaction.
Definition i2c.c:202
bool i2c_transceive(struct i2c_periph *p, struct i2c_transaction *t, uint8_t s_addr, uint8_t len_w, uint16_t len_r)
Submit a write/read transaction.
Definition i2c.c:222
@ I2CTransSuccess
transaction successfully finished by I2C driver
Definition i2c.h:58
@ I2CTransFailed
transaction failed
Definition i2c.h:59
@ I2CTransDone
transaction set to done by user level
Definition i2c.h:60
angular rates
int32_t p
in rad/s with INT32_RATE_FRAC
int32_t r
in rad/s with INT32_RATE_FRAC
int32_t q
in rad/s with INT32_RATE_FRAC
angular rates
bool spi_submit(struct spi_periph *p, struct spi_transaction *t)
Submit SPI transaction.
Definition spi_arch.c:534
@ SPICphaEdge2
CPHA = 1.
Definition spi.h:71
@ SPITransFailed
Definition spi.h:96
@ SPITransSuccess
Definition spi.h:95
@ SPITransDone
Definition spi.h:97
@ SPICpolIdleHigh
CPOL = 1.
Definition spi.h:80
@ SPISelectUnselect
slave is selected before transaction and unselected after
Definition spi.h:59
@ SPIMSBFirst
Definition spi.h:108
@ SPIDiv16
Definition spi.h:119
@ SPIDss8bit
Definition spi.h:86
void imu_set_defaults_gyro(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Rates *neutral, const struct FloatRates *scale_f)
Set the defaults for a gyro sensor WARNING: Should be called before sensor is publishing messages to ...
Definition imu.c:612
void imu_set_defaults_accel(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct FloatVect3 *scale_f)
Set the defaults for a accel sensor WARNING: Should be called before sensor is publishing messages to...
Definition imu.c:641
Inertial Measurement Unit interface.
static const struct FloatVect3 invensense2_accel_scale_f[5]
Definition invensense2.c:56
static bool invensense2_select_bank(struct invensense2_t *inv, uint8_t bank)
Select the correct register bank.
static bool invensense2_register_write(struct invensense2_t *inv, uint16_t bank_reg, uint8_t value)
Write a register based on a combined bank/regsiter value.
void invensense2_event(struct invensense2_t *inv)
Should be called in the event thread.
static void invensense2_parse_data(struct invensense2_t *inv, volatile uint8_t *data, uint16_t len)
Parse the FIFO buffer data.
void invensense2_periodic(struct invensense2_t *inv)
Should be called periodically to request sensor readings.
static const struct FloatRates invensense2_gyro_scale_f[5]
Definition invensense2.c:47
static bool invensense2_config(struct invensense2_t *inv)
Configure the Invensense 2 device register by register.
static void invensense2_fix_config(struct invensense2_t *inv)
This fixes the configuration errors and sets the correct scalings.
static bool invensense2_register_read(struct invensense2_t *inv, uint16_t bank_reg, uint16_t size)
Read a register based on a combined bank/regsiter value.
void invensense2_init(struct invensense2_t *inv)
Initialize the invensense v2 sensor instance.
Definition invensense2.c:69
Driver for the Invensense V2 IMUs ICM20948, ICM20648 and ICM20649.
@ INVENSENSE2_GYRO_DLPF_OFF
Definition invensense2.h:81
@ INVENSENSE2_RUNNING
Definition invensense2.h:68
@ INVENSENSE2_IDLE
Definition invensense2.h:66
@ INVENSENSE2_CONFIG
Definition invensense2.h:67
@ INVENSENSE2_GYRO_RANGE_4000DPS
Only possible for ICM20649.
Definition invensense2.h:98
@ INVENSENSE2_GYRO_RANGE_500DPS
Definition invensense2.h:95
@ INVENSENSE2_GYRO_RANGE_2000DPS
Definition invensense2.h:97
@ INVENSENSE2_GYRO_RANGE_250DPS
Not possible for ICM20649.
Definition invensense2.h:94
@ INVENSENSE2_ACCEL_RANGE_2G
Not possible for ICM20649.
@ INVENSENSE2_ACCEL_RANGE_16G
@ INVENSENSE2_ACCEL_RANGE_4G
@ INVENSENSE2_ACCEL_RANGE_30G
Only possible for ICM20649.
@ INVENSENSE2_ACCEL_DLPF_OFF
@ INVENSENSE2_ICM20648
Definition invensense2.h:74
@ INVENSENSE2_ICM20649
Definition invensense2.h:75
@ INVENSENSE2_UNKOWN
Definition invensense2.h:73
@ INVENSENSE2_ICM20948
Definition invensense2.h:76
#define INVENSENSE2_SAMPLE_CNT
Definition invensense2.h:37
#define INVENSENSE2_SAMPLE_SIZE
Definition invensense2.h:38
@ INVENSENSE2_I2C
Definition invensense2.h:61
@ INVENSENSE2_SPI
Definition invensense2.h:60
Register and address definitions for the Invensense V2 from ardupilot.
#define GYRO_FS_SEL_SHIFT
#define BIT_USER_CTRL_FIFO_EN
#define INV2REG_INT_ENABLE_1
#define BIT_ZG_FIFO_EN
#define INV2REG_FIFO_COUNTH
#define BIT_PWR_MGMT_1_CLK_AUTO
#define BIT_YG_FIFO_EN
#define INV2_WHOAMI_ICM20948
#define BIT_ACCEL_DLPF_ENABLE
#define INV2_WHOAMI_ICM20648
#define ACCEL_DLPF_CFG_SHIFT
#define INV2REG_ACCEL_CONFIG
#define BIT_USER_CTRL_I2C_IF_DIS
#define INV2REG_PWR_MGMT_1
#define BIT_USER_CTRL_I2C_MST_RESET
#define INV2REG_GYRO_CONFIG_1
#define INV2REG_TIMEBASE_CORRECTIO
#define INV2REG_WHO_AM_I
#define INV2REG_FIFO_MODE
#define INV2REG_FIFO_EN_2
#define BIT_XG_FIFO_EN
#define INV2REG_USER_CTRL
#define ACCEL_FS_SEL_SHIFT
#define GYRO_DLPF_CFG_SHIFT
#define BIT_USER_CTRL_SRAM_RESET
#define BIT_ACCEL_FIFO_EN
#define INV2REG_BANK_SEL
#define INV2REG_GYRO_SMPLRT_DIV
#define BIT_TEMP_FIFO_EN
#define INV2REG_FIFO_RST
#define BIT_GYRO_DLPF_ENABLE
#define INV2_READ_FLAG
#define BIT_PWR_MGMT_1_DEVICE_RESET
#define INV2_WHOAMI_ICM20649
uint16_t foo
Definition main_demo5.c:58
Paparazzi fixed point algebra.
Paparazzi atmospheric pressure conversion utilities.
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
int int32_t
Typedef defining 32 bit int type.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
short int16_t
Typedef defining 16 bit short type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
signed char int8_t
Typedef defining 8 bit char type.