mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: allow JEDEC/RAMTRON to be compiled out
SITL: add and use AP_SIM_RAMTRON_ENABLED SITL: add an use AP_SIM_JEDEC_ENABLED
This commit is contained in:
parent
105fc36da5
commit
e6779e91e6
@ -1,5 +1,7 @@
|
||||
#include "SIM_JEDEC.h"
|
||||
|
||||
#if AP_SIM_JEDEC_ENABLED
|
||||
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
|
||||
@ -7,7 +9,7 @@
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
extern HAL_SITL& hal;
|
||||
extern const HAL_SITL& hal_sitl;
|
||||
|
||||
void JEDEC::open_storage_fd()
|
||||
{
|
||||
@ -15,7 +17,7 @@ void JEDEC::open_storage_fd()
|
||||
AP_HAL::panic("Should not have been called");
|
||||
}
|
||||
const char *filepath = filename();
|
||||
if (hal.get_wipe_storage()) {
|
||||
if (hal_sitl.get_wipe_storage()) {
|
||||
unlink(filepath);
|
||||
}
|
||||
storage_fd = open(filepath, O_RDWR|O_CREAT, 0644);
|
||||
@ -190,3 +192,5 @@ int JEDEC::rdwr(uint8_t count, SPI::spi_ioc_transfer *&tfrs)
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif // AP_SIM_JEDEC_ENABLED
|
||||
|
@ -1,5 +1,13 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_SIM_JEDEC_ENABLED
|
||||
#define AP_SIM_JEDEC_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if AP_SIM_JEDEC_ENABLED
|
||||
|
||||
#include "SIM_SPIDevice.h"
|
||||
|
||||
namespace SITL {
|
||||
@ -46,3 +54,5 @@ private:
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // AP_SIM_JEDEC_ENABLED
|
||||
|
@ -1,5 +1,7 @@
|
||||
#include "SIM_JEDEC_MX25L3206E.h"
|
||||
|
||||
#if AP_SIM_JEDEC_MX25L3206E_ENABLED
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
void JEDEC_MX25L3206E::fill_rdid(uint8_t *buffer, uint8_t len)
|
||||
@ -15,3 +17,5 @@ void JEDEC_MX25L3206E::fill_rdsr(uint8_t *buffer, uint8_t len)
|
||||
// hence we can never be busy while reading the status register
|
||||
buffer[0] = 0x00;
|
||||
}
|
||||
|
||||
#endif // AP_SIM_JEDEC_MX25L3206E_ENABLED
|
||||
|
@ -2,6 +2,12 @@
|
||||
|
||||
#include "SIM_JEDEC.h"
|
||||
|
||||
#ifndef AP_SIM_JEDEC_MX25L3206E_ENABLED
|
||||
#define AP_SIM_JEDEC_MX25L3206E_ENABLED AP_SIM_JEDEC_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_SIM_JEDEC_MX25L3206E_ENABLED
|
||||
|
||||
namespace SITL {
|
||||
|
||||
class JEDEC_MX25L3206E : public JEDEC
|
||||
@ -24,3 +30,5 @@ private:
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // AP_SIM_JEDEC_MX25L3206E_ENABLED
|
||||
|
@ -1,5 +1,7 @@
|
||||
#include "SIM_RAMTRON.h"
|
||||
|
||||
#if AP_SIM_RAMTRON_ENABLED
|
||||
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
|
||||
@ -7,7 +9,7 @@
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
extern HAL_SITL& hal;
|
||||
extern const HAL_SITL& hal_sitl;
|
||||
|
||||
void RAMTRON::open_storage_fd()
|
||||
{
|
||||
@ -16,7 +18,7 @@ void RAMTRON::open_storage_fd()
|
||||
}
|
||||
const char *filepath = filename();
|
||||
uint32_t flags = O_RDWR|O_CREAT;
|
||||
if (hal.get_wipe_storage()) {
|
||||
if (hal_sitl.get_wipe_storage()) {
|
||||
flags |= O_TRUNC;
|
||||
}
|
||||
storage_fd = open(filepath, flags, 0644);
|
||||
@ -109,3 +111,5 @@ int RAMTRON::rdwr(uint8_t count, SPI::spi_ioc_transfer *&tfrs)
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif // AP_SIM_RAMTRON_ENABLED
|
||||
|
@ -1,5 +1,13 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_SIM_RAMTRON_ENABLED
|
||||
#define AP_SIM_RAMTRON_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if AP_SIM_RAMTRON_ENABLED
|
||||
|
||||
#include "SIM_SPIDevice.h"
|
||||
|
||||
namespace SITL {
|
||||
@ -33,3 +41,5 @@ private:
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // AP_SIM_RAMTRON_ENABLED
|
||||
|
@ -1,5 +1,7 @@
|
||||
#include "SIM_RAMTRON_FM25V02.h"
|
||||
|
||||
#if AP_SIM_RAMTRON_FM25V02_ENABLED
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
void RAMTRON_FM25V02::fill_rdid(uint8_t *buffer, uint8_t len)
|
||||
@ -8,3 +10,5 @@ void RAMTRON_FM25V02::fill_rdid(uint8_t *buffer, uint8_t len)
|
||||
buffer[7] = id1();
|
||||
buffer[8] = id2();
|
||||
}
|
||||
|
||||
#endif // AP_SIM_RAMTRON_FM25V02_ENABLED
|
||||
|
@ -2,6 +2,12 @@
|
||||
|
||||
#include "SIM_RAMTRON.h"
|
||||
|
||||
#ifndef AP_SIM_RAMTRON_FM25V02_ENABLED
|
||||
#define AP_SIM_RAMTRON_FM25V02_ENABLED AP_SIM_RAMTRON_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_SIM_RAMTRON_FM25V02_ENABLED
|
||||
|
||||
namespace SITL {
|
||||
|
||||
class RAMTRON_FM25V02 : public RAMTRON
|
||||
@ -31,3 +37,5 @@ private:
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // AP_SIM_RAMTRON_FM25V02_ENABLED
|
||||
|
@ -21,6 +21,8 @@
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
#include "SIM_SPI.h"
|
||||
#include "SIM_SPIDevice.h"
|
||||
|
||||
#include "SIM_RAMTRON_FM25V02.h"
|
||||
#include "SIM_JEDEC_MX25L3206E.h"
|
||||
|
||||
@ -28,16 +30,24 @@
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
#if AP_SIM_RAMTRON_FM25V02_ENABLED
|
||||
static RAMTRON_FM25V02 ramtron_FM25V02; // 32kB 2-byte-addressing
|
||||
#endif
|
||||
#if AP_SIM_JEDEC_MX25L3206E_ENABLED
|
||||
static JEDEC_MX25L3206E jedec_MX25L3206E;
|
||||
#endif
|
||||
|
||||
struct spi_device_at_cs_pin {
|
||||
uint8_t bus;
|
||||
uint8_t cs_pin;
|
||||
SPIDevice &device;
|
||||
} spi_devices[] {
|
||||
#if AP_SIM_RAMTRON_FM25V02_ENABLED
|
||||
{ 0, 0, ramtron_FM25V02 },
|
||||
#endif
|
||||
#if AP_SIM_JEDEC_MX25L3206E_ENABLED
|
||||
{ 1, 0, jedec_MX25L3206E },
|
||||
#endif
|
||||
};
|
||||
|
||||
void SPI::init()
|
||||
|
Loading…
Reference in New Issue
Block a user