mirror of https://github.com/ArduPilot/ardupilot
AP_RAMTRON: added PB85RS128C and PB85RS2MC
This commit is contained in:
parent
6021e953c5
commit
011fdf6e2b
|
@ -40,6 +40,9 @@ const AP_RAMTRON::ramtron_id AP_RAMTRON::ramtron_ids[] = {
|
|||
{ 0x05, 0x09, 32, 2, RDID_type::Fujitsu }, // MB85RS256B
|
||||
{ 0x24, 0x03, 16, 2, RDID_type::Fujitsu }, // MB85RS128TY
|
||||
{ 0x25, 0x03, 32, 2, RDID_type::Fujitsu }, // MB85RS256TY
|
||||
|
||||
{ 0x22, 0x00, 16, 2, RDID_type::Petabytes }, // PB85RS128C
|
||||
{ 0x24, 0x00, 256, 3, RDID_type::Petabytes }, // PB85RS2MC
|
||||
};
|
||||
|
||||
// initialise the driver
|
||||
|
@ -62,6 +65,11 @@ bool AP_RAMTRON::init(void)
|
|||
uint8_t id1;
|
||||
uint8_t id2;
|
||||
};
|
||||
struct petabytes_rdid {
|
||||
uint8_t manufacturer[2];
|
||||
uint8_t id1;
|
||||
uint8_t id2;
|
||||
};
|
||||
|
||||
uint8_t rdid[sizeof(cypress_rdid)];
|
||||
|
||||
|
@ -86,6 +94,15 @@ bool AP_RAMTRON::init(void)
|
|||
ramtron_ids[i].id2 == fujitsu->id2) {
|
||||
id = i;
|
||||
break;
|
||||
}
|
||||
} else if (ramtron_ids[i].rdid_type == RDID_type::Petabytes) {
|
||||
const petabytes_rdid *petabytes = (const petabytes_rdid *)rdid;
|
||||
if (petabytes->manufacturer[0] == 0x62 &&
|
||||
petabytes->manufacturer[1] == 0x8C &&
|
||||
ramtron_ids[i].id1 == petabytes->id1 &&
|
||||
ramtron_ids[i].id2 == petabytes->id2) {
|
||||
id = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -28,6 +28,7 @@ private:
|
|||
enum class RDID_type :uint8_t {
|
||||
Cypress,
|
||||
Fujitsu,
|
||||
Petabytes
|
||||
};
|
||||
|
||||
struct ramtron_id {
|
||||
|
|
Loading…
Reference in New Issue