Fixed camera lockup errors

added si446x-feeder timeout exception
Removed UART5 from mcuconf
pull/1/head
Sven Steudte 2018-02-12 09:35:33 +01:00
rodzic 75cc0a6df2
commit 6c73548999
9 zmienionych plików z 74 dodań i 73 usunięć

Wyświetl plik

@ -60,13 +60,13 @@ endif
# Stack size to be allocated to the Cortex-M process stack. This stack is
# the stack used by the main() thread.
ifeq ($(USE_PROCESS_STACKSIZE),)
USE_PROCESS_STACKSIZE = 0x1000
USE_PROCESS_STACKSIZE = 0x4000
endif
# Stack size to the allocated to the Cortex-M main/exceptions stack. This
# stack is used for processing interrupts and exceptions.
ifeq ($(USE_EXCEPTIONS_STACKSIZE),)
USE_EXCEPTIONS_STACKSIZE = 0x1500
USE_EXCEPTIONS_STACKSIZE = 0x4000
endif
# Enables the use of FPU (no, softfp, hard).

Wyświetl plik

@ -7,7 +7,7 @@ conf_t config = {
// Primary position transmission thread
.pos_pri = {
.thread_conf = {
.active = true,
.active = false,
.cycle = TIME_S2I(120)
},
.radio_conf = {
@ -17,9 +17,9 @@ conf_t config = {
.preamble = 200
},
.call = "DO7EN-8",
.call = "DL7AD-12",
.path = "WIDE1-1",
.symbol = SYM_SHIP,
.symbol = SYM_DIGIPEATER,
.tel_enc_cycle = TIME_S2I(10800),
},
@ -37,7 +37,7 @@ conf_t config = {
.preamble = 200
},
.call = "DL7AD-12",
.call = "DL7AD-14",
.path = "WIDE1-1",
.symbol = SYM_BALLOON,
@ -50,7 +50,7 @@ conf_t config = {
.active = true,
.cycle = CYCLE_CONTINUOUSLY,
.init_delay = TIME_S2I(5),
.packet_spacing = TIME_S2I(20)
//.packet_spacing = TIME_S2I(30)
},
.radio_conf = {
.pwr = 0x7F,
@ -60,10 +60,10 @@ conf_t config = {
.redundantTx = true
},
.call = "DO7EN-8",
.path = "WIDE1-1",
.call = "DL7AD-12",
.path = "DB0BLO",
.res = RES_QVGA,
.res = RES_VGA,
.quality = 4,
.buf_size = 64*1024
},
@ -116,9 +116,9 @@ conf_t config = {
.preamble = 200
},
.call = "DO7EN-8",
.call = "DL7AD-12",
.path = "WIDE1-1",
.symbol = SYM_SHIP
.symbol = SYM_DIGIPEATER
},
.rssi = 0x3F,
@ -127,8 +127,8 @@ conf_t config = {
.keep_cam_switched_on = false,
.gps_on_vbat = 1000,
.gps_off_vbat = 1000,
.gps_onper_vbat = 1000
.gps_on_vbat = 5000,
.gps_off_vbat = 5000,
.gps_onper_vbat = 5000
};

Wyświetl plik

@ -10,6 +10,7 @@
#include "board.h"
#include "debug.h"
#include "padc.h"
#include "si446x.h"
#include <string.h>
static uint32_t lightIntensity;
@ -70,8 +71,8 @@ static const struct regval_list OV5640YUV_Sensor_Dvp_Init[] =
{ 0x3c0a, 0x9c },
{ 0x3c0b, 0x40 },
{ 0x3820, 0x41 },
{ 0x3821, 0x01 }, //07
{ 0x3820, 0x47 },
{ 0x3821, 0x00 }, //07
//windows setup
{ 0x3800, 0x00 },
@ -327,8 +328,8 @@ static const struct regval_list OV5640YUV_Sensor_Dvp_Init[] =
//2592x1944 QSXGA
static const struct regval_list OV5640_JPEG_QSXGA[] =
{
{0x3820 ,0x40},
{0x3821 ,0x26},
{0x3820 ,0x47},
{0x3821 ,0x20},
{0x3814 ,0x11},
{0x3815 ,0x11},
{0x3803 ,0x00},
@ -729,14 +730,6 @@ uint32_t OV5640_Snapshot2RAM(uint8_t* buffer, uint32_t size, resolution_t res)
while(!buffer[size_sampled] && size_sampled > 0)
size_sampled--;
for(uint32_t i=0; i<(size_sampled+31)/32; i++) {
TRACE_DEBUG("0x%04x > %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x %02x",
i*32, buffer[i*32+0 ], buffer[i*32+1 ], buffer[i*32+2 ], buffer[i*32+3 ], buffer[i*32+4 ], buffer[i*32+5 ], buffer[i*32+6 ], buffer[i*32+7 ],
buffer[i*32+8 ], buffer[i*32+9 ], buffer[i*32+10], buffer[i*32+11], buffer[i*32+12], buffer[i*32+13], buffer[i*32+14], buffer[i*32+15],
buffer[i*32+16], buffer[i*32+17], buffer[i*32+18], buffer[i*32+19], buffer[i*32+20], buffer[i*32+21], buffer[i*32+22], buffer[i*32+23],
buffer[i*32+24], buffer[i*32+25], buffer[i*32+26], buffer[i*32+27], buffer[i*32+28], buffer[i*32+29], buffer[i*32+30], buffer[i*32+31]);
}
TRACE_INFO("CAM > Image size: %d bytes", size_sampled);
} while(!status && cntr--);
@ -748,7 +741,7 @@ const stm32_dma_stream_t *dmastp;
#if OV5640_USE_DMA_DBM == TRUE
uint16_t dma_index;
uint16_t dma_buffers;
#define DMA_SEGMENT_SIZE 65535
#define DMA_SEGMENT_SIZE 1024
#define DMA_FIFO_BURST_ALIGN 32
@ -847,7 +840,8 @@ static void dma_interrupt(void *p, uint32_t flags) {
* DMA will use new address at h/w DBM switch.
*/
if(dmaStreamGetCurrentTarget(dmastp) == 1) {
if (dmaStreamGetCurrentTarget(dmastp) == 1) {
dmaStreamSetMemory0(dmastp, &dma_buffer[++dma_index * DMA_SEGMENT_SIZE]);
} else {
dmaStreamSetMemory1(dmastp, &dma_buffer[++dma_index * DMA_SEGMENT_SIZE]);
@ -939,7 +933,7 @@ void vsync_cb(void *arg) {
bool OV5640_Capture(uint8_t* buffer, uint32_t size)
{
OV5640_setLightIntensity();
TRACE_DEBUG("A buffer_addr=%08x", buffer);chThdSleep(TIME_MS2I(10));
/*
* Note:
* If there are no Chibios devices enabled that use DMA then...
@ -947,13 +941,13 @@ TRACE_DEBUG("A buffer_addr=%08x", buffer);chThdSleep(TIME_MS2I(10));
* UDEFS = -DSTM32_DMA_REQUIRED
*/
TRACE_DEBUG("E");chThdSleep(TIME_MS2I(10));
I2C_Lock(); // Lock I2C because it uses the same DMA
lockRadioByCamera(); // Lock the radio because it uses the DMA too
/* Setup DMA for transfer on TIM8_CH1 - DMA2 stream 2, channel 7 */
dmastp = STM32_DMA_STREAM(STM32_DMA_STREAM_ID(2, 2));
uint32_t dmamode = STM32_DMA_CR_CHSEL(7) |
STM32_DMA_CR_PL(0) |
STM32_DMA_CR_PL(3) |
STM32_DMA_CR_DIR_P2M |
STM32_DMA_CR_MSIZE_WORD |
STM32_DMA_CR_MBURST_INCR4 |
@ -967,13 +961,13 @@ TRACE_DEBUG("E");chThdSleep(TIME_MS2I(10));
#endif
STM32_DMA_CR_TCIE;
dmaStreamAllocate(dmastp, 1, (stm32_dmaisr_t)dma_interrupt, NULL);
dmaStreamAllocate(dmastp, 3, (stm32_dmaisr_t)dma_interrupt, NULL);
dmaStreamSetPeripheral(dmastp, &GPIOA->IDR); // We want to read the data from here
#if OV5640_USE_DMA_DBM == TRUE
dma_buffer = buffer;
TRACE_DEBUG("B");chThdSleep(TIME_MS2I(10));
/*
* Buffer address must be word aligned.
* Also note requirement for burst transfers from FIFO.
@ -995,7 +989,7 @@ TRACE_DEBUG("B");chThdSleep(TIME_MS2I(10));
dmaStreamSetMemory0(dmastp, &buffer[0]);
dmaStreamSetMemory1(dmastp, &buffer[DMA_SEGMENT_SIZE]);
dmaStreamSetTransactionSize(dmastp, DMA_SEGMENT_SIZE);
TRACE_DEBUG("C");chThdSleep(TIME_MS2I(10));
/*
* Calculate the number of whole buffers.
* TODO: Make this include remainder memory as partial buffer?
@ -1018,7 +1012,7 @@ TRACE_DEBUG("C");chThdSleep(TIME_MS2I(10));
dma_error = false;
dma_flags = 0;
TRACE_DEBUG("D");chThdSleep(TIME_MS2I(10));
/*
* Setup timer for PCLK
* Setup timer to trigger DMA in capture mode. On rising edge, we will
@ -1036,23 +1030,28 @@ TRACE_DEBUG("D");chThdSleep(TIME_MS2I(10));
capture_finished = false;
vsync_cntr = 0;
TRACE_DEBUG("G");chThdSleep(TIME_MS2I(10));
// Enable VSYNC interrupt
palSetLineCallback(LINE_CAM_VSYNC, (palcallback_t)vsync_cb, NULL);
palEnableLineEvent(LINE_CAM_VSYNC, PAL_EVENT_MODE_RISING_EDGE);
TRACE_DEBUG("H");chThdSleep(TIME_MS2I(10));
// Wait for capture to be finished
uint8_t timout = 100; // 1000ms max
do {
TRACE_DEBUG("I");chThdSleep(TIME_MS2I(10));
chThdSleep(TIME_MS2I(10));
TRACE_DEBUG("dma_error=%08x dma_flags=%08x", dma_error, dma_flags);
} while(!capture_finished && !dma_error);
TRACE_DEBUG("J");chThdSleep(TIME_MS2I(10));
// Capture done, unlock I2C
} while(!capture_finished && !dma_error && --timout);
if(!timout) {
TRACE_ERROR("CAM > Image sampling timeout");
dma_stop();
TIM8->DIER &= ~TIM_DIER_CC1DE;
palDisableLineEventI(LINE_CAM_VSYNC);
}
// Capture done, unlock I2C and the radio
unlockRadio();
I2C_Unlock();
TRACE_DEBUG("K");chThdSleep(TIME_MS2I(10));
if(dma_error)
{
if(dma_flags & STM32_DMA_ISR_HTIF) {

Wyświetl plik

@ -180,7 +180,7 @@ void pac1720_init(void)
sendConfig();
TRACE_INFO("PAC > Init PAC1720 continuous measurement");
chThdCreateFromHeap(NULL, THD_WORKING_AREA_SIZE(512), "PAC1720", LOWPRIO, pac1720_thd, NULL);
//chThdCreateFromHeap(NULL, THD_WORKING_AREA_SIZE(512), "PAC1720", LOWPRIO, pac1720_thd, NULL);
chThdSleep(TIME_MS2I(10));
}

Wyświetl plik

@ -665,7 +665,6 @@ static void Si446x_shutdown(void)
static void lockRadio(void)
{
TRACE_DEBUG("LOCK");
// Initialize mutex
if(!radio_mtx_init)
chMtxObjectInit(&radio_mtx);
@ -673,19 +672,16 @@ static void lockRadio(void)
chMtxLock(&radio_mtx);
nextTransmissionWaiting = true;
TRACE_DEBUG("LOCKED1");
// Wait for old feeder thread to terminate
if(feeder_thd != NULL) // No waiting on first use
chThdWait(feeder_thd);
TRACE_DEBUG("LOCKED2");
}
void unlockRadio(void)
{
TRACE_DEBUG("UNLOCK");
nextTransmissionWaiting = false;
chMtxUnlock(&radio_mtx);
TRACE_DEBUG("UNLOCKED");
}
void lockRadioByCamera(void)
@ -807,7 +803,7 @@ static bool Si4464_restoreRX(void)
bool ret = Si446x_receive_noLock(rx_frequency, rx_rssi, rx_mod);
if(packetHandler) {
TRACE_DEBUG("Start packet handler")
TRACE_DEBUG("SI > Start packet handler")
pktStartDataReception(packetHandler); // Start packet handler again
}
@ -979,7 +975,7 @@ THD_FUNCTION(si_fifo_feeder_afsk, arg)
// Start transmission
Si446x_transmit(radio_freq, radio_pwr, all, 0x4F, TIME_S2I(10));
while(c < all) { // Do while bytes not written into FIFO completely
while(c < all && Si446x_getState() == Si446x_STATE_TX) { // Do while bytes not written into FIFO completely
// Determine free memory in Si446x-FIFO
uint8_t more = Si446x_freeFIFO();
if(more > all-c) {
@ -995,6 +991,10 @@ THD_FUNCTION(si_fifo_feeder_afsk, arg)
chThdSleep(TIME_MS2I(15));
}
if(c < all) {
TRACE_ERROR("SI > Packet was not sent completly");
}
/*
* Shutdown radio if receiption has been interrupted. If receiption was interrupted rx_frequency is set.
* If receiption has not been interrupted rx_frequency is set 0.
@ -1008,8 +1008,6 @@ THD_FUNCTION(si_fifo_feeder_afsk, arg)
// Free packet object memory
ax25_delete(pp);
TRACE_DEBUG("FIFO Feeder finished");
chThdExit(MSG_OK);
}
@ -1018,7 +1016,7 @@ void Si446x_sendAFSK(/*uint8_t *frame, uint32_t len*/packet_t pp, uint32_t freq,
// Stop packet handler (if started)
if(packetHandler) {
TRACE_DEBUG("Stop packet handler")
TRACE_DEBUG("SI > Stop packet handler")
pktStopDataReception(packetHandler);
}

Wyświetl plik

@ -9,6 +9,8 @@
#define I2C_DRIVER (&I2CD1)
static uint8_t error;
static mutex_t mtx;
static bool mtx_init;
const I2CConfig _i2cfg = {
OPMODE_I2C,
@ -38,12 +40,17 @@ static bool I2C_transmit(uint8_t addr, uint8_t *txbuf, uint32_t txbytes, uint8_t
void I2C_Lock(void)
{
i2cAcquireBus(I2C_DRIVER);
// Initialize mutex
if(!mtx_init)
chMtxObjectInit(&mtx);
mtx_init = true;
chMtxLock(&mtx);
}
void I2C_Unlock(void)
{
i2cReleaseBus(I2C_DRIVER);
chMtxUnlock(&mtx);
}
void pi2cInit(void)

Wyświetl plik

@ -185,7 +185,7 @@
#define STM32_SERIAL_USE_USART1 FALSE
#define STM32_SERIAL_USE_USART2 FALSE
#define STM32_SERIAL_USE_USART3 TRUE
#define STM32_SERIAL_USE_UART5 TRUE
#define STM32_SERIAL_USE_UART5 FALSE
#define STM32_SERIAL_USE_USART6 FALSE
#define STM32_SERIAL_USART1_PRIORITY 12
#define STM32_SERIAL_USART2_PRIORITY 12

Wyświetl plik

@ -286,7 +286,7 @@ static void encode_ssdv(const uint8_t *image, uint32_t image_len, thd_img_conf_t
ssdv_t ssdv;
uint8_t pkt[SSDV_PKT_SIZE];
uint8_t pkt_base91[256];
uint8_t pkt_base91[256] = {0};
const uint8_t *b;
uint32_t bi = 0;
uint8_t c = SSDV_OK;
@ -299,6 +299,15 @@ static void encode_ssdv(const uint8_t *image, uint32_t image_len, thd_img_conf_t
while(true)
{
// Proccess redundant transmission from last cycle
if(strlen((char*)pkt_base91) && conf->radio_conf.redundantTx) {
packet_t packet = aprs_encode_data_packet(conf->call, conf->path, 'I', pkt_base91);
transmitOnRadio(packet, conf->radio_conf.freq, conf->radio_conf.pwr, conf->radio_conf.mod);
}
// Encode packet
TRACE_INFO("IMG > Encode APRS/SSDV packet");
while((c = ssdv_enc_get_packet(&ssdv)) == SSDV_FEED_ME)
{
b = &image[bi];
@ -322,9 +331,6 @@ static void encode_ssdv(const uint8_t *image, uint32_t image_len, thd_img_conf_t
return;
}
// Encode packet
TRACE_INFO("IMG > Encode APRS/SSDV packet");
// Sync byte, CRC and FEC of SSDV not transmitted (because its not neccessary inside an APRS packet)
base91_encode(&pkt[6], pkt_base91, 174);
@ -415,9 +421,6 @@ uint32_t takePicture(uint8_t* buffer, uint32_t size, resolution_t res, bool enab
TRACE_INFO("IMG > OV5640 found");
// Lock Radio (The radio uses the same DMA for SPI as the camera)
lockRadioByCamera(); // Lock radio
uint8_t cntr = 5;
bool jpegValid;
do {
@ -447,9 +450,6 @@ uint32_t takePicture(uint8_t* buffer, uint32_t size, resolution_t res, bool enab
}
} while(!jpegValid && cntr--);
// Unlock radio
unlockRadio();
} else { // Camera not found
camInitialized = false;
@ -512,7 +512,7 @@ THD_FUNCTION(imgThread, arg)
void start_image_thread(thd_img_conf_t *conf)
{
thread_t *th = chThdCreateFromHeap(NULL, THD_WORKING_AREA_SIZE((conf->thread_conf.packet_spacing ? 6:12) * 1024 + conf->buf_size), "IMG", NORMALPRIO, imgThread, conf);
thread_t *th = chThdCreateFromHeap(NULL, THD_WORKING_AREA_SIZE((conf->thread_conf.packet_spacing ? 70:70) * 1024 + conf->buf_size), "IMG", NORMALPRIO, imgThread, conf);
if(!th) {
// Print startup error, do not start watchdog for this thread
TRACE_ERROR("IMG > Could not startup thread (not enough memory available)");

Wyświetl plik

@ -45,7 +45,6 @@ void start_rx_thread(uint32_t freq, uint8_t rssi) {
bool transmitOnRadio(packet_t pp, uint32_t freq, uint8_t pwr, mod_t mod)
{
TRACE_DEBUG("A -------------------------------------------------");
if(freq == FREQ_APRS_DYNAMIC)
freq = getAPRSRegionFrequency(); // Get transmission frequency by geofencing
@ -81,8 +80,6 @@ bool transmitOnRadio(packet_t pp, uint32_t freq, uint8_t pwr, mod_t mod)
}
TRACE_DEBUG("B -------------------------------------------------");
return true;
}