ardupilot/libraries/AP_Common/tools/eedump_apparam.c

138 lines
2.9 KiB
C

/*
* Simple tool to dump the AP_Param contents from an EEPROM dump
* Andrew Tridgell February 2012
*/
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
uint8_t eeprom[0x1000];
#pragma pack(1)
struct EEPROM_header {
uint8_t magic[2];
uint8_t revision;
uint8_t spare;
};
static const uint16_t k_EEPROM_magic0 = 0x50;
static const uint16_t k_EEPROM_magic1 = 0x41;
static const uint16_t k_EEPROM_revision = 5;
enum ap_var_type {
AP_PARAM_NONE = 0,
AP_PARAM_INT8,
AP_PARAM_INT16,
AP_PARAM_INT32,
AP_PARAM_FLOAT,
AP_PARAM_VECTOR3F,
AP_PARAM_VECTOR6F,
AP_PARAM_MATRIX3F,
AP_PARAM_GROUP
};
static const char *type_names[8] = {
"NONE", "INT8", "INT16", "INT32", "FLOAT", "VECTOR3F", "MATRIX6F", "GROUP"
};
struct Param_header {
uint8_t key;
uint8_t group_element;
uint8_t type;
};
static const uint8_t _sentinal_key = 0xFF;
static const uint8_t _sentinal_type = 0xFF;
static const uint8_t _sentinal_group = 0xFF;
static uint8_t type_size(enum ap_var_type type)
{
switch (type) {
case AP_PARAM_NONE:
case AP_PARAM_GROUP:
return 0;
case AP_PARAM_INT8:
return 1;
case AP_PARAM_INT16:
return 2;
case AP_PARAM_INT32:
return 4;
case AP_PARAM_FLOAT:
return 4;
case AP_PARAM_VECTOR3F:
return 3*4;
case AP_PARAM_VECTOR6F:
return 6*4;
case AP_PARAM_MATRIX3F:
return 3*3*4;
}
printf("unknown type %u\n", type);
return 0;
}
static void
fail(const char *why)
{
fprintf(stderr, "ERROR: %s\n", why);
exit(1);
}
int
main(int argc, char *argv[])
{
FILE *fp;
struct EEPROM_header *header;
struct Param_header *var;
unsigned index;
unsigned i;
if (argc != 2) {
fail("missing EEPROM file name");
}
if (NULL == (fp = fopen(argv[1], "rb"))) {
fail("can't open EEPROM file");
}
if (1 != fread(eeprom, sizeof(eeprom), 1, fp)) {
fail("can't read EEPROM file");
}
fclose(fp);
header = (struct EEPROM_header *)&eeprom[0];
if (header->magic[0] != k_EEPROM_magic0 ||
header->magic[1] != k_EEPROM_magic1) {
fail("bad magic in EEPROM file");
}
if (header->revision != k_EEPROM_revision) {
fail("unsupported EEPROM format revision");
}
printf("Header OK\n");
index = sizeof(*header);
for (;;) {
uint8_t size;
var = (struct Param_header *)&eeprom[index];
if (var->key == _sentinal_key ||
var->group_element == _sentinal_group ||
var->type == _sentinal_type) {
printf("end sentinel at %u\n", index);
break;
}
size = type_size(var->type);
printf("%04x: type %u (%s) key %u size %d\n ",
index, var->type, type_names[var->type], var->key, size);
index += sizeof(*var);
for (i = 0; i <= size; i++) {
printf(" %02x", eeprom[index + i]);
}
printf("\n");
index += size;
if (index >= sizeof(eeprom)) {
fflush(stdout);
fail("missing end sentinel");
}
}
return 0;
}