Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/scripts/decode_devid.py
Views: 1798
#!/usr/bin/env python1'''2decode a device ID, such as used for COMPASS_DEV_ID, INS_ACC_ID etc34To understand the devtype you should look at the backend headers for5the sensor library, such as libraries/AP_Compass/AP_Compass_Backend.h6'''78import sys9import optparse1011def num(s):12try:13return int(s)14except ValueError:15return int(s, 16)161718parser = optparse.OptionParser("decode_devid.py")19parser.add_option("-C", "--compass", action='store_true', help='decode compass IDs')20parser.add_option("-I", "--imu", action='store_true', help='decode IMU IDs')21parser.add_option("-B", "--baro", action='store_true', help='decode barometer IDs')22parser.add_option("-A", "--airspeed", action='store_true', help='decode airspeed IDs')2324opts, args = parser.parse_args()2526if len(args) == 0:27print("Please supply a device ID")28sys.exit(1)2930devid=num(args[0])3132bus_type=devid & 0x0733bus=(devid>>3) & 0x1F34address=(devid>>8)&0xFF35devtype=(devid>>16)3637bustypes = {381: "I2C",392: "SPI",403: "DRONECAN",414: "SITL",425: "MSP",436: "SERIAL",44}4546compass_types = {470x01 : "DEVTYPE_HMC5883_OLD",480x07 : "DEVTYPE_HMC5883",490x02 : "DEVTYPE_LSM303D",500x04 : "DEVTYPE_AK8963 ",510x05 : "DEVTYPE_BMM150 ",520x06 : "DEVTYPE_LSM9DS1",530x08 : "DEVTYPE_LIS3MDL",540x09 : "DEVTYPE_AK09916",550x0A : "DEVTYPE_IST8310",560x0B : "DEVTYPE_ICM20948",570x0C : "DEVTYPE_MMC3416",580x0D : "DEVTYPE_QMC5883L",590x0E : "DEVTYPE_MAG3110",600x0F : "DEVTYPE_SITL",610x10 : "DEVTYPE_IST8308",620x11 : "DEVTYPE_RM3100_OLD",630x12 : "DEVTYPE_RM3100",640x13 : "DEVTYPE_MMC5883",650x14 : "DEVTYPE_AK09918",660x15 : "DEVTYPE_AK09915",670x16 : "DEVTYPE_QMC5883P",680x17 : "DEVTYPE_BMM350",690x18 : "DEVTYPE_IIS2MDC",70}7172imu_types = {730x09 : "DEVTYPE_BMI160",740x10 : "DEVTYPE_L3G4200D",750x11 : "DEVTYPE_ACC_LSM303D",760x12 : "DEVTYPE_ACC_BMA180",770x13 : "DEVTYPE_ACC_MPU6000",780x16 : "DEVTYPE_ACC_MPU9250",790x17 : "DEVTYPE_ACC_IIS328DQ",800x21 : "DEVTYPE_GYR_MPU6000",810x22 : "DEVTYPE_GYR_L3GD20",820x24 : "DEVTYPE_GYR_MPU9250",830x25 : "DEVTYPE_GYR_I3G4250D",840x26 : "DEVTYPE_GYR_LSM9DS1",850x27 : "DEVTYPE_INS_ICM20789",860x28 : "DEVTYPE_INS_ICM20689",870x29 : "DEVTYPE_INS_BMI055",880x2A : "DEVTYPE_SITL",890x2B : "DEVTYPE_INS_BMI088",900x2C : "DEVTYPE_INS_ICM20948",910x2D : "DEVTYPE_INS_ICM20648",920x2E : "DEVTYPE_INS_ICM20649",930x2F : "DEVTYPE_INS_ICM20602",940x30 : "DEVTYPE_INS_ICM20601",950x31 : "DEVTYPE_INS_ADIS1647x",960x32 : "DEVTYPE_INS_SERIAL",970x33 : "DEVTYPE_INS_ICM40609",980x34 : "DEVTYPE_INS_ICM42688",990x35 : "DEVTYPE_INS_ICM42605",1000x36 : "DEVTYPE_INS_ICM40605",1010x37 : "DEVTYPE_INS_IIM42652",1020x38 : "DEVTYPE_INS_BMI270",1030x39 : "DEVTYPE_INS_BMI085",1040x3A : "DEVTYPE_INS_ICM42670",1050x3B : "DEVTYPE_INS_ICM45686",1060x3C : "DEVTYPE_INS_SCHA63T",1070x3D : "DEVTYPE_INS_IIM42653",108}109110baro_types = {1110x01 : "DEVTYPE_BARO_SITL",1120x02 : "DEVTYPE_BARO_BMP085",1130x03 : "DEVTYPE_BARO_BMP280",1140x04 : "DEVTYPE_BARO_BMP388",1150x05 : "DEVTYPE_BARO_DPS280",1160x06 : "DEVTYPE_BARO_DPS310",1170x07 : "DEVTYPE_BARO_FBM320",1180x08 : "DEVTYPE_BARO_ICM20789",1190x09 : "DEVTYPE_BARO_KELLERLD",1200x0A : "DEVTYPE_BARO_LPS2XH",1210x0B : "DEVTYPE_BARO_MS5611",1220x0C : "DEVTYPE_BARO_SPL06",1230x0D : "DEVTYPE_BARO_DRONECAN",1240x0E : "DEVTYPE_BARO_MSP",1250x0F : "DEVTYPE_BARO_ICP101XX",1260x10 : "DEVTYPE_BARO_ICP201XX",1270x11 : "DEVTYPE_BARO_MS5607",1280x12 : "DEVTYPE_BARO_MS5837",1290x13 : "DEVTYPE_BARO_MS5637",1300x14 : "DEVTYPE_BARO_BMP390",1310x15 : "DEVTYPE_BARO_BMP581",132}133134airspeed_types = {1350x01 : "DEVTYPE_AIRSPEED_SITL",1360x02 : "DEVTYPE_AIRSPEED_MS4525",1370x03 : "DEVTYPE_AIRSPEED_MS5525",1380x04 : "DEVTYPE_AIRSPEED_DLVR",1390x05 : "DEVTYPE_AIRSPEED_MSP",1400x06 : "DEVTYPE_AIRSPEED_SDP3X",1410x07 : "DEVTYPE_AIRSPEED_DRONECAN",1420x08 : "DEVTYPE_AIRSPEED_ANALOG",1430x09 : "DEVTYPE_AIRSPEED_NMEA",1440x0A : "DEVTYPE_AIRSPEED_ASP5033",145}146147decoded_devname = ""148149if opts.compass:150decoded_devname = compass_types.get(devtype, "UNKNOWN")151152if opts.imu:153decoded_devname = imu_types.get(devtype, "UNKNOWN")154155if opts.baro:156decoded_devname = baro_types.get(devtype, "UNKNOWN")157158if opts.airspeed:159decoded_devname = airspeed_types.get(devtype, "UNKNOWN")160161if bus_type == 3:162#dronecan devtype represents sensor_id163print("bus_type:%s(%u) bus:%u address:%u(0x%x) sensor_id:%u(0x%x) %s" % (164bustypes.get(bus_type,"UNKNOWN"), bus_type,165bus, address, address, devtype-1, devtype-1, decoded_devname))166else:167print("bus_type:%s(%u) bus:%u address:%u(0x%x) devtype:%u(0x%x) %s" % (168bustypes.get(bus_type,"UNKNOWN"), bus_type,169bus, address, address, devtype, devtype, decoded_devname))170171172