mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_Param: cleanup the eeprom parsing tools and fixed sentinal detection
This commit is contained in:
parent
eac027b5c5
commit
62e0a89036
@ -1,82 +0,0 @@
|
||||
/*
|
||||
* Simple tool to dump the AP_Var contents from an EEPROM dump
|
||||
*/
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdint.h>
|
||||
|
||||
uint8_t eeprom[0x1000];
|
||||
|
||||
struct PACKED EEPROM_header {
|
||||
uint16_t magic;
|
||||
uint8_t revision;
|
||||
uint8_t spare;
|
||||
};
|
||||
|
||||
static const uint16_t k_EEPROM_magic = 0x5041;
|
||||
static const uint16_t k_EEPROM_revision = 2;
|
||||
|
||||
struct PACKED Var_header {
|
||||
uint8_t size : 6;
|
||||
uint8_t spare : 2;
|
||||
uint8_t key;
|
||||
};
|
||||
|
||||
static const uint8_t k_key_sentinel = 0xff;
|
||||
|
||||
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 Var_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 != k_EEPROM_magic) {
|
||||
fail("bad magic in EEPROM file");
|
||||
}
|
||||
if (header->revision != 2) {
|
||||
fail("unsupported EEPROM format revision");
|
||||
}
|
||||
printf("Header OK\n");
|
||||
|
||||
index = sizeof(*header);
|
||||
for (;; ) {
|
||||
var = (struct Var_header *)&eeprom[index];
|
||||
if (var->key == k_key_sentinel) {
|
||||
printf("end sentinel at %u\n", index);
|
||||
break;
|
||||
}
|
||||
printf("%04x: key %u size %d\n ", index, var->key, var->size + 1);
|
||||
index += sizeof(*var);
|
||||
for (i = 0; i <= var->size; i++) {
|
||||
printf(" %02x", eeprom[index + i]);
|
||||
}
|
||||
printf("\n");
|
||||
index += var->size + 1;
|
||||
if (index >= sizeof(eeprom)) {
|
||||
fflush(stdout);
|
||||
fail("missing end sentinel");
|
||||
}
|
||||
}
|
||||
}
|
@ -1,47 +0,0 @@
|
||||
#!/usr/bin/perl
|
||||
|
||||
|
||||
$file = $ARGV[0];
|
||||
|
||||
|
||||
open(IN,$file) || die print "Failed to open file: $file : $!";
|
||||
|
||||
read(IN,$buffer,1);
|
||||
read(IN,$buffer2,1);
|
||||
if (ord($buffer) != 0x41 && ord($buffer2) != 0x50) {
|
||||
print "bad header ". $buffer ." ".$buffer2. "\n";
|
||||
exit;
|
||||
}
|
||||
read(IN,$buffer,1);
|
||||
if (ord($buffer) != 2) {
|
||||
print "bad version";
|
||||
exit;
|
||||
}
|
||||
|
||||
# spare
|
||||
read(IN,$buffer,1);
|
||||
|
||||
$a = 0;
|
||||
|
||||
while (read(IN,$buffer,1)) {
|
||||
$pos = (tell(IN) - 1);
|
||||
|
||||
$size = ((ord($buffer) & 63));
|
||||
|
||||
read(IN,$buffer,1);
|
||||
|
||||
if (ord($buffer) == 0xff) {
|
||||
printf("end sentinel at %u\n", $pos);
|
||||
last;
|
||||
}
|
||||
|
||||
printf("%04x: key %u size %d\n ", $pos, ord($buffer), $size + 1);
|
||||
|
||||
for ($i = 0; $i <= ($size); $i++) {
|
||||
read(IN,$buffer,1);
|
||||
printf(" %02x", ord($buffer));
|
||||
}
|
||||
print "\n";
|
||||
}
|
||||
|
||||
close IN;
|
@ -112,7 +112,6 @@ main(int argc, char *argv[])
|
||||
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;
|
||||
|
@ -1,84 +0,0 @@
|
||||
#!/usr/bin/perl
|
||||
|
||||
|
||||
$file = $ARGV[0];
|
||||
|
||||
|
||||
open(IN,$file) || die print "Failed to open file: $file : $!";
|
||||
|
||||
read(IN,$buffer,1);
|
||||
read(IN,$buffer2,1);
|
||||
if (ord($buffer2) != 0x41 && ord($buffer) != 0x50) {
|
||||
print "bad header ". $buffer ." ".$buffer2. "\n";
|
||||
exit;
|
||||
}
|
||||
read(IN,$buffer,1);
|
||||
if (ord($buffer) != 6) {
|
||||
print "bad version";
|
||||
exit;
|
||||
}
|
||||
|
||||
# spare
|
||||
read(IN,$buffer,1);
|
||||
|
||||
$a = 0;
|
||||
|
||||
while (read(IN,$buffer,1)) {
|
||||
$pos = (tell(IN) - 1);
|
||||
|
||||
my $key = ord($buffer);
|
||||
|
||||
if ($key == 0xff) {
|
||||
printf("end sentinel at %u\n", $pos);
|
||||
last;
|
||||
}
|
||||
|
||||
read(IN,$buffer2,1);
|
||||
read(IN,$buffer3,1);
|
||||
read(IN,$buffer4,1);
|
||||
|
||||
my $itype = ord($buffer2)&0x3F;
|
||||
my $group_element = (ord($buffer2)>>6) | (ord($buffer3)<<8) | (ord($buffer4)<<16);
|
||||
|
||||
if ($itype == 0) { #none
|
||||
$size = 0;
|
||||
$type = "NONE";
|
||||
} elsif ($itype == 1) { #int8
|
||||
$size = 1;
|
||||
$type = "INT8";
|
||||
} elsif ($itype == 2) { #int16
|
||||
$size = 2;
|
||||
$type = "INT16";
|
||||
} elsif ($itype == 3) { #int32
|
||||
$size = 4;
|
||||
$type = "INT32";
|
||||
} elsif ($itype == 4) { #float
|
||||
$size = 4;
|
||||
$type = "FLOAT";
|
||||
} elsif ($itype == 5) { #vector 3
|
||||
$size = 3*4;
|
||||
$type = "VECTOR3F";
|
||||
} elsif ($itype == 6) { #vector6
|
||||
$size = 6*4;
|
||||
$type = "VECTOR6F";
|
||||
} elsif ($itype == 7) { #matrix
|
||||
$size = 3*3*4;
|
||||
$type = "MATRIX6F";
|
||||
} elsif ($itype == 8) { #group
|
||||
$size = 0;
|
||||
$type = "GROUP";
|
||||
} else {
|
||||
print "Unknown type\n";
|
||||
$size = 0;
|
||||
}
|
||||
|
||||
printf("%04x: type %u ($type) key %u group_element %u size %d\n ", $pos, $itype, $key, $group_element, $size);
|
||||
|
||||
for ($i = 0; $i < ($size); $i++) {
|
||||
read(IN,$buffer,1);
|
||||
printf(" %02x", ord($buffer));
|
||||
}
|
||||
print "\n";
|
||||
}
|
||||
|
||||
close IN;
|
Loading…
Reference in New Issue
Block a user