Commit e3b75b7f authored by Andrey Filippov's avatar Andrey Filippov

Synchronized with framepars branch

parents ee474cb0 bfdfc65a
...@@ -4,11 +4,11 @@ Debug ...@@ -4,11 +4,11 @@ Debug
Release Release
linux linux
sysroots sysroots
.project /.project
.cproject /.cproject
.externalToolBuilders /.externalToolBuilders
.settings /.settings
.pydevproject /.pydevproject
html html
*.directory *.directory
doxygen.tag doxygen.tag
...@@ -21,3 +21,5 @@ src/drivers/elphel/x393_types.h ...@@ -21,3 +21,5 @@ src/drivers/elphel/x393_types.h
all_sources.lst all_sources.lst
excluding.lst excluding.lst
attic attic
board_elphel393
scp
\ No newline at end of file
This source diff could not be displayed because it is too large. You can view the blob instead.
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<launchConfiguration type="org.eclipse.ant.AntBuilderLaunchConfigurationType">
<stringAttribute key="org.eclipse.jdt.launching.CLASSPATH_PROVIDER" value="org.eclipse.ant.ui.AntClasspathProvider"/>
<booleanAttribute key="org.eclipse.jdt.launching.DEFAULT_CLASSPATH" value="true"/>
<booleanAttribute key="org.eclipse.ui.externaltools.ATTR_BUILDER_ENABLED" value="false"/>
<stringAttribute key="org.eclipse.ui.externaltools.ATTR_DISABLED_BUILDER" value="org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder"/>
<mapAttribute key="org.eclipse.ui.externaltools.ATTR_TOOL_ARGUMENTS"/>
<booleanAttribute key="org.eclipse.ui.externaltools.ATTR_TRIGGERS_CONFIGURED" value="true"/>
</launchConfiguration>
...@@ -11,16 +11,6 @@ ...@@ -11,16 +11,6 @@
<arguments> <arguments>
</arguments> </arguments>
</buildCommand> </buildCommand>
<buildCommand>
<name>org.eclipse.ui.externaltools.ExternalToolBuilder</name>
<triggers>full,incremental,</triggers>
<arguments>
<dictionary>
<key>LaunchConfigHandle</key>
<value>&lt;project&gt;/.externalToolBuilders/org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder.launch</value>
</dictionary>
</arguments>
</buildCommand>
<buildCommand> <buildCommand>
<name>org.eclipse.ui.externaltools.ExternalToolBuilder</name> <name>org.eclipse.ui.externaltools.ExternalToolBuilder</name>
<triggers>clean,</triggers> <triggers>clean,</triggers>
......
This diff is collapsed.
/** @file ahci_elphel_ext.h
*
* @brief Elphel AHCI SATA platform driver for Elphel393 camera. This module provides
* additional functions which allows to use a part of a disk (or entire disk) as a
* raw circular buffer.
*
* @copyright Copyright (C) 2016 Elphel, Inc
*
* @par <b>License</b>
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <uapi/elphel/ahci_cmd.h>
#include "../elphel/circbuf.h"
#ifndef _AHCI_ELPHEL_EXT
#define _AHCI_ELPHEL_EXT
#define IRQ_SIMPLE (1 << 0) ///< Flag indicating that IRQ corresponds to internal command and should not be
///< processed in ahci_handle_port_interrupt
#define DISK_BUSY (1 << 1) ///< Flag indicating that disk is currently busy. Access to this flag should be protected by
///< spin locks to prevent race conditions
#define PROC_CMD (1 << 2) ///< Processing driver's internal command is in progress
#define LAST_BLOCK (1 << 3) ///< Flag indicating that the remaining chunk of data will be recorded
#define DELAYED_FINISH (1 << 4) ///< Flag indicating that recording should be stopped right after the last chunk of data is written
#define LOCK_TAIL (1 << 5) ///< Lock current command slot until all data buffers are assigned and the frame is aligned
#define CMD_FIS_LEN 5 ///< The length of a command FIS in double words
#define ADDR_MASK_28_BIT ((u64)0xfffffff)///< This is used to get 28-bit address from 64-bit value
#define MAX_PRDT_LEN 0x3fffff ///< A maximum of length of 4MB may exist for PRDT entry
#define MAX_DATA_CHUNKS 9 ///< An array or JPEG frame chunks contains pointers to JPEG leading marker,
///< JPEG header, Exif data if present, stuffing bytes chunk which aligns
///< the frame size to disk sector boundary, JPEG data which
///< can be split into two chunks, align buffers, JPEG
///< trailing marker, and pointer to a buffer containing the remainder of a
///< frame. Nine chunks of data in total.
#define DEFAULT_PORT_NUM 0 ///< Default port number
#define ALIGNMENT_SIZE 32 ///< Align buffers length to this amount of bytes
#define MAX_SGL_LEN 168 ///< Maximum number of entries in PRDT table. HW max is 64k.
///< Set this value the same as AHCI_MAX_SG in ahci.h
#define MAX_CMD_SLOTS 4 ///< Maximum number of frames which will be processed at the same time
#define MAX_LBA_COUNT 0xff ///< Maximum number of sectors for READ DMA or WRITE DMA commands
#define MAX_LBA_COUNT_EXT 0xffff ///< Maximum number of sectors for READ DMA EXT or WRITE_DMA EXT commands
#define PHY_BLOCK_SIZE 512 ///< Physical disk block size
#define JPEG_MARKER_LEN 2 ///< The size in bytes of JPEG marker
#define JPEG_SIZE_LEN 2 ///< The size in bytes of JPEG marker length field
#define INCLUDE_REM 1 ///< Include REM buffer to total size calculation
#define EXCLUDE_REM 0 ///< Exclude REM buffer from total size calculation
/** This structure holds raw device buffer pointers */
struct drv_pointers {
uint64_t lba_start; ///< raw buffer starting LBA
uint64_t lba_end; ///< raw buffer ending LBA
uint64_t lba_write; ///< current write pointer inside raw buffer
uint16_t wr_count; ///< the number of LBA to write next time
};
/** Container structure for frame buffers */
struct frame_buffers {
struct fvec exif_buff; ///< Exif buffer
struct fvec jpheader_buff; ///< JPEG header buffer
struct fvec trailer_buff; ///< buffer for trailing marker
struct fvec common_buff; ///< common buffer where other parts are combined
struct fvec rem_buff; ///< remainder from previous frame
};
/** Symbolic names for slots in buffer pointers. Buffer alignment function relies on the order of these names, so
* new names can be added but the overall order should not be changed */
enum {
CHUNK_LEADER, ///< pointer to JPEG leading marker
CHUNK_EXIF, ///< pointer to Exif buffer
CHUNK_HEADER, ///< pointer to JPEG header data excluding leading marker
CHUNK_COMMON, ///< pointer to common buffer
CHUNK_DATA_0, ///< pointer to JPEG data
CHUNK_DATA_1, ///< pointer to the second half of JPEG data if a frame crosses circbuf boundary
CHUNK_TRAILER, ///< pointer to JPEG trailing marker
CHUNK_ALIGN, ///< pointer to buffer where the second part of JPEG data should be aligned
CHUNK_REM ///< pointer to buffer containing the remainder of current frame. It will be recorded during next transaction
};
/** AHCI driver private structure */
struct elphel_ahci_priv {
u32 clb_offs; ///< CLB offset, received from device tree
u32 fb_offs; ///< FB offset, received from device tree
u32 base_addr; ///< controller base address
u32 flags; ///< flags indicating current state of the driver. Access to #DISK_BUSY flags is protected with
///< a spin lock
int curr_cmd; ///< current ATA command
size_t max_data_sz; ///< maximum data size (in bytes) which can be processed with current ATA command
struct drv_pointers lba_ptr; ///< disk buffer pointers
struct frame_buffers fbuffs[MAX_CMD_SLOTS]; ///< a set of buffers for each command
struct fvec data_chunks[MAX_CMD_SLOTS][MAX_DATA_CHUNKS];///< a set of vectors pointing to data buffers for each command
struct fvec sgl[MAX_SGL_LEN]; ///< an array of data buffers mapped for next transaction
int sg_elems; ///< the number of S/G vectors mapped for next transaction in @e sgl array
int curr_data_chunk; ///< index of a data chunk used during last transaction
size_t curr_data_offset; ///< offset of the last byte in a data chunk pointed to by @e curr_data_chunk
size_t head_ptr; ///< pointer to command slot which will be written next
size_t tail_ptr; ///< pointer to next free command slot
spinlock_t flags_lock; ///< controls access to #DISK_BUSY flag in @e flags variable.
///< This flag controls access to disk write operations either from
///< the the driver itself or from the system. Mutex is not used
///< because this flag is accessed from interrupt context
struct tasklet_struct bh; ///< command processing tasklet
struct device *dev; ///< pointer to parent device structure
};
#endif /* _AHCI_ELPHEL_EXT */
/*!*************************************************************************** /*!***************************************************************************
*! FILE NAME : si5338.c * @file si5338.c
*! DESCRIPTION: control of the Silicon Laboratories SI5338 clock generator * @brief control of the Silicon Laboratories SI5338 clock generator
*! Copyright (C) 2013 Elphel, Inc. * @copyright Copyright (C) 2013 Elphel, Inc.
*! -----------------------------------------------------------------------------**
*! *
*! This program is free software: you can redistribute it and/or modify * This program is free software: you can redistribute it and/or modify
*! it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
*! the Free Software Foundation, either version 3 of the License, or * the Free Software Foundation, either version 3 of the License, or
*! (at your option) any later version. * (at your option) any later version.
*! *
*! This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
*! but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
*! MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
*! GNU General Public License for more details. * GNU General Public License for more details.
*! *
*! You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
*! along with this program. If not, see <http://www.gnu.org/licenses/>. * along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*#define DEBUG // should be before linux/module.h - enables dev_dbg at boot in this file (needs "debug" in bootarg)*/ /*#define DEBUG // should be before linux/module.h - enables dev_dbg at boot in this file (needs "debug" in bootarg)*/
...@@ -4579,7 +4579,7 @@ static void si5338_init_of(struct i2c_client *client) ...@@ -4579,7 +4579,7 @@ static void si5338_init_of(struct i2c_client *client)
return; return;
} }
init_type=1; init_type=1;
/* falling to initialization */ // no break : falling to initialization */
case 1: case 1:
pre_init(client,1); // clear outputs and muxes - they will be programmed later pre_init(client,1); // clear outputs and muxes - they will be programmed later
break; break;
......
...@@ -23,3 +23,15 @@ obj-$(CONFIG_ELPHEL393) += quantization_tables.o ...@@ -23,3 +23,15 @@ obj-$(CONFIG_ELPHEL393) += quantization_tables.o
obj-$(CONFIG_ELPHEL393) += circbuf.o obj-$(CONFIG_ELPHEL393) += circbuf.o
obj-$(CONFIG_ELPHEL393) += jpeghead.o obj-$(CONFIG_ELPHEL393) += jpeghead.o
obj-$(CONFIG_ELPHEL393) += gamma_tables.o
obj-$(CONFIG_ELPHEL393) += histograms.o
obj-$(CONFIG_ELPHEL393) += pgm_functions.o
obj-$(CONFIG_ELPHEL393) += mt9x001.o
obj-$(CONFIG_ELPHEL393) += multi10359.o
obj-$(CONFIG_ELPHEL393) += imu_log393.o
obj-$(CONFIG_ELPHEL393) += cxi2c.o
obj-$(CONFIG_ELPHEL393) += x393_videomem.o
obj-$(CONFIG_ELPHEL393) += detect_sensors.o
obj-$(CONFIG_ELPHEL393) += x393_fpga_functions.o
obj-$(CONFIG_ELPHEL393) += klogger_393.o
\ No newline at end of file
/** @file x393_helpers.c /** @file cci2c.h
* *
* @brief Helper functions for various routines form x393.h which require several actions to get * @brief Pre-393 I2c driver for FPGA communicating to sensors, software implementation
* reliable result. * Porting to get GPS communication, sesnors in NC393 are handled by sensor_i2c.c driver
* *
* @copyright Copyright (C) 2016 Elphel, Inc * @copyright Copyright (C) 2002-2016 Elphel, Inc
* *
* @par <b>License</b> * @par <b>License</b>
* This program is free software: you can redistribute it and/or modify * This program is free software: you can redistribute it and/or modify
...@@ -18,32 +18,14 @@ ...@@ -18,32 +18,14 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>. * along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <stddef.h> int i2c_delays (unsigned long delays);
#include "x393_helpers.h" int i2c_writeData(int n, unsigned char theSlave, unsigned char *theData, int size, int stop);
int i2c_readData(int n, unsigned char theSlave, unsigned char *theData, int size, int start);
int i2c_ioctl(struct inode *inode, struct file *file, unsigned int cmd, unsigned long arg);
/** #ifdef NC353
* @brief Read RTC microsecond counter. void i2c_reset_wait(void);
* @return Current value of microsecond counter or 0 in case read sequence was void i2c_stop_wait(void);
* not successful. void i2c_run(void);
*/ int i2s_running(void);
u32 get_rtc_usec(void) #endif
{
x393_rtc_status_t stat;
x393_status_ctrl_t stat_ctrl;
x393_rtc_usec_t usec;
unsigned int i;
stat = x393_rtc_status();
stat_ctrl.d32 = 0;
stat_ctrl.mode = 1;
stat_ctrl.seq_num = stat.seq_num + 1;
set_x393_rtc_set_status(stat_ctrl);
for (i = 0; i < REPEAT_READ; i++) {
stat = x393_rtc_status();
if (stat.seq_num == stat_ctrl.seq_num) {
usec = x393_rtc_status_usec();
return usec.usec;
}
}
return 0;
}
This diff is collapsed.
...@@ -24,12 +24,21 @@ ...@@ -24,12 +24,21 @@
#include <linux/poll.h> #include <linux/poll.h>
struct fvec {
void *iov_base; ///< pointer to allocated buffer
size_t iov_len; ///< the size (in bytes) of allocated buffer; set after allocation and is not modified during buffer lifetime
dma_addr_t iov_dma; ///< buffer physical address
};
/** @brief Circular buffer private data */ /** @brief Circular buffer private data */
struct circbuf_priv_t { struct circbuf_priv_t {
int minor; ///< device file minor number int minor; ///< device file minor number
unsigned long *buf_ptr; ///< pointer to circular buffer memory region unsigned long *buf_ptr; ///< pointer to circular buffer memory region
unsigned long buf_size; ///< circular region size in bytes
unsigned long buf_size32; ///< circular region size in dwords
dma_addr_t phys_addr; ///< physical address of memory region reported by memory driver dma_addr_t phys_addr; ///< physical address of memory region reported by memory driver
}; };
struct circbuf_priv_t *get_circbuf(int chn); // alternative to use of extern struct circbuf_priv_ptr;
extern struct circbuf_priv_t *circbuf_priv_ptr; extern struct circbuf_priv_t *circbuf_priv_ptr;
extern wait_queue_head_t circbuf_wait_queue; extern wait_queue_head_t circbuf_wait_queue;
...@@ -48,11 +57,30 @@ ssize_t circbuf_read (struct file * file, char * buf, size_t count, loff_t ...@@ -48,11 +57,30 @@ ssize_t circbuf_read (struct file * file, char * buf, size_t count, loff_t
int circbuf_mmap (struct file *file, struct vm_area_struct *vma); int circbuf_mmap (struct file *file, struct vm_area_struct *vma);
unsigned int circbuf_poll (struct file *file, poll_table *wait); unsigned int circbuf_poll (struct file *file, poll_table *wait);
#ifdef USE_OLD_CODE
//int init_ccam_dma_buf_ptr(void);
/*!======================================================================================
* Wait queue for the processes waiting for a new frame to appear in the circular buffer
*======================================================================================*/
extern wait_queue_head_t circbuf_wait_queue;
// private data
struct circbuf_priv_t {
int minor;
unsigned long *buf_ptr;
dma_addr_t phys_addr;
};
extern struct circbuf_priv_t *circbuf_priv_ptr;
#endif
/* debug code follows */ /* debug code follows */
#ifdef PRE_FRAMEPARS
extern unsigned short circbuf_quality; extern unsigned short circbuf_quality;
extern unsigned short circbuf_height; extern unsigned short circbuf_height;
extern unsigned short circbuf_width; extern unsigned short circbuf_width;
extern unsigned char circbuf_byrshift; extern unsigned char circbuf_byrshift;
#endif
/* end of debug code */ /* end of debug code */
ssize_t circbuf_get_ptr(int sensor_port, size_t offset, size_t len, struct fvec *vect_0, struct fvec *vect_1);
#endif /* _CIRCBUF_H */ #endif /* _CIRCBUF_H */
/******************************************************************************* /***************************************************************************//**
* FILE NAME : clock10359.c * @file clock10359.c
* DESCRIPTION: Control of the CY22393 clock on the 10359 multiplexer connected * @brief Control of the CY22393 clock on the 10359 multiplexer connected
* to the sensor port * to the sensor port
* Copyright 2002-2016 (C) Elphel, Inc. * @copyright Copyright 2002-2016 (C) Elphel, Inc.
* -----------------------------------------------------------------------------* * @par <b>License</b>
*
* This program is free software: you can redistribute it and/or modify * This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 2 of the License, or * the Free Software Foundation, either version 2 of the License, or
* (at your option) any later version. * (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details. * GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>. * along with this program. If not, see <http://www.gnu.org/licenses/>.
*******************************************************************************/ *******************************************************************************/
/****************** INCLUDE FILES SECTION ***********************************/ /****************** INCLUDE FILES SECTION ***********************************/
#define DEBUG /* should be before linux/module.h - enables dev_dbg at boot in this file */ //#define DEBUG /* should be before linux/module.h - enables dev_dbg at boot in this file */
#include <linux/module.h> #include <linux/module.h>
#include <linux/sched.h> #include <linux/sched.h>
...@@ -78,7 +75,6 @@ typedef struct { ...@@ -78,7 +75,6 @@ typedef struct {
int calc_pll_params (unsigned int f, t_pll_params * pars); // f -in Hz int calc_pll_params (unsigned int f, t_pll_params * pars); // f -in Hz
int setCYField (int sensor_port, int addr, int mask, int value); /// bus==1 - FPGA (sensor bus through 10359), 0 - CPU bus int setCYField (int sensor_port, int addr, int mask, int value); /// bus==1 - FPGA (sensor bus through 10359), 0 - CPU bus
int setClockFreq(int nclock, int freq); // freq now in Hz
int calc_pll_params (unsigned int f, t_pll_params * pars) { // f -in Hz int calc_pll_params (unsigned int f, t_pll_params * pars) { // f -in Hz
// t_pll_params pars; // t_pll_params pars;
...@@ -179,6 +175,7 @@ int setCYField (int sensor_port, int reg_addr, int mask, int value) { ...@@ -179,6 +175,7 @@ int setCYField (int sensor_port, int reg_addr, int mask, int value) {
sensor_port, reg_addr, mask, value,reg_data); sensor_port, reg_addr, mask, value,reg_data);
return error; return error;
} }
return 0;
} }
int x393_getClockFreq(int sensor_port, int nclock) { int x393_getClockFreq(int sensor_port, int nclock) {
...@@ -190,7 +187,8 @@ int x393_getClockFreq(int sensor_port, int nclock) { ...@@ -190,7 +187,8 @@ int x393_getClockFreq(int sensor_port, int nclock) {
EXPORT_SYMBOL_GPL(x393_getClockFreq); EXPORT_SYMBOL_GPL(x393_getClockFreq);
int x393_setClockFreq(int sensor_port, int nclock, int freq) { // freq now in Hz int x393_setClockFreq(int sensor_port, int nclock, int freq)
{ // freq now in Hz
int err=0; int err=0;
sensor_port &= 3; sensor_port &= 3;
nclock &= 3; nclock &= 3;
......
/******************************************************************************* /***************************************************************************//**
* FILE NAME : clock10359.h * @file clock10359.h
* DESCRIPTION: Control of the CY22393 clock on the 10359 multiplexer connected * @brief Control of the CY22393 clock on the 10359 multiplexer connected
* to the sensor port * to the sensor port
* Copyright 2002-2016 (C) Elphel, Inc. * Copyright 2002-2016 (C) Elphel, Inc.
* -----------------------------------------------------------------------------* * @par <b>License</b>
*
* This program is free software: you can redistribute it and/or modify * This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 2 of the License, or * the Free Software Foundation, either version 2 of the License, or
......
/***************************************************************************//**
* @file command_sequencer.c
* @brief Interface to FPGA-based command sequencer sequencer
* @copyright Copyright 2016 (C) Elphel, Inc.
* @par <b>License</b>
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 2 of the License, or
* (at your option) any later version.
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*******************************************************************************/
#include <linux/errno.h>
#include <linux/spinlock.h>
#include <uapi/elphel/c313a.h> // PARS_FRAMES_MASK
#include "x393.h"
static DEFINE_SPINLOCK(lock);
/** Write command to the 16-frame sequencer, relative to the current frame */
int write_seq_rel (int chn, ///< sensor port
int frame, ///< relative frame number modulo 16 (0 - ASAP)
u32 addr, ///< command (register) address in bytes (2 LSBs are will be discarded)
u32 data) ///< command data.
///< @return 0 on success, negative error if table shadow is not initialized to data
{
if (unlikely(frame < 0)) frame = 0;
else if (unlikely(frame >= PARS_FRAMES_MASK)){
return -EINVAL; // too far in the future
}
spin_lock(&lock);
x393_cmdframeseq_rel(addr>>2, chn, frame);
x393_cmdframeseq_rel(data, chn, frame);
spin_unlock(&lock);
return 0;
}
EXPORT_SYMBOL_GPL(write_seq_rel);
/* Write command to the 16-frame sequencer, absolute frame */
int write_seq_abs (int chn, ///< sensor port
int frame, ///< absolute frame number modulo 16
u32 addr, ///< command (register) address in bytes (2 LSBs are will be discarded)
u32 * data) ///< data array. Length written is defined by the pre-configured table entry.
///< MSB (data is sent MSB first) of the first entry is index in the table.
///< @return 0 on success, negative error if table shadow is not initialized to data
{
frame &= PARS_FRAMES_MASK;
spin_lock(&lock);
x393_cmdframeseq_rel(addr>>2, chn, frame);
x393_cmdframeseq_rel(data, chn, frame);
spin_unlock(&lock);
return 0;
}
EXPORT_SYMBOL_GPL(write_seq_abs);
// TODO: Add other sequencer control here
/*
// Command sequencer control
// Controller is programmed through 32 locations. Each register but the control requires two writes:
// First write - register address (AXI_WR_ADDR_BITS bits), second - register data (32 bits)
// Writing to the contol register (0x1f) resets the first/second counter so the next write will be "first"
// 0x0..0xf write directly to the frame number [3:0] modulo 16, except if you write to the frame
// "just missed" - in that case data will go to the current frame.
// 0x10 - write seq commands to be sent ASAP
// 0x11 - write seq commands to be sent after the next frame starts
//
// 0x1e - write seq commands to be sent after the next 14 frame start pulses
// 0x1f - control register:
// [14] - reset all FIFO (takes 32 clock pulses), also - stops seq until run command
// [13:12] - 3 - run seq, 2 - stop seq , 1,0 - no change to run state
// [1:0] - 0: NOP, 1: clear IRQ, 2 - Clear IE, 3: set IE
void x393_cmdframeseq_ctrl (x393_cmdframeseq_mode_t d, int sens_chn){writel(d.d32, mmio_ptr + (0x1e7c + 0x80 * sens_chn));} // CMDFRAMESEQ control register
void x393_cmdframeseq_abs (u32 d, int sens_chn, int offset){writel(d, mmio_ptr + (0x1e00 + 0x80 * sens_chn + 0x4 * offset));} // CMDFRAMESEQ absolute frame address/command
void x393_cmdframeseq_rel (u32 d, int sens_chn, int offset){writel(d, mmio_ptr + (0x1e40 + 0x80 * sens_chn + 0x4 * offset));} // CMDFRAMESEQ relative frame address/command
// Command sequencer multiplexer, provides current frame number for each sensor channel and interrupt status/interrupt masks for them.
// Interrupts and interrupt masks are controlled through channel CMDFRAMESEQ module
void set_x393_cmdseqmux_status_ctrl (x393_status_ctrl_t d){writel(d.d32, mmio_ptr + 0x1c08);} // CMDSEQMUX status control mode (status provides current frame numbers)
x393_status_ctrl_t get_x393_cmdseqmux_status_ctrl (void) { x393_status_ctrl_t d; d.d32 = readl(mmio_ptr + 0x1c08); return d; }
x393_cmdseqmux_status_t x393_cmdseqmux_status (void) { x393_cmdseqmux_status_t d; d.d32 = readl(mmio_ptr + 0x20e0); return d; } // CMDSEQMUX status data (frame numbers and interrupts
*/
/***************************************************************************//**
* @file command_sequencer.h
* @brief Interface to FPGA-based command sequencer sequencer
* @copyright Copyright 2016 (C) Elphel, Inc.
* @par <b>License</b>
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 2 of the License, or
* (at your option) any later version.
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*******************************************************************************/
/* Write command to the 16-frame sequencer, relative to the current frame */
int write_seq_rel (int chn, int frame, u32 addr, u32 data);
/* Write command to the 16-frame sequencer, absolute frame */
int write_seq_abs (int chn, int frame, u32 addr, u32 * data);
This diff is collapsed.
/***************************************************************************//**
* @file debug393.h
* @brief Macros for low-overhad logging messages to a large memory buffer
* using klogger_393
* @copyright Copyright 2016 (C) Elphel, Inc.
* @par <b>License</b>
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 2 of the License, or
* (at your option) any later version.
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*******************************************************************************/
// Used debug bits:
// framepars.c
// 0
#define DBGB_FSFA 1 ///< setFrameParsAtomic (kthread)
#define DBGB_FASAP 2 ///< _processParsASAP (kthread, tasklet) (first N only)
#define DBGB_FSEQ 3 ///< _processParsSeq (kthread, tasklet) (first N only)
#define DBGB_FPPI 4 ///< _processPars (kthread, tasklet) (first N only)
#define DBGB_FPPT 5 ///< processPars (from tasklets) (first N only)
#define DBGB_FSFP 6 ///< setFramePar(), setFramePars() (tasklet)
#define DBGB_FSFV 7 ///< setFramePar(), setFramePars() - adiitional(verbose) (tasklet)
#define DBGB_FSCF 8 ///< schedule_pgm_func,schedule_this_pgm_func
#define DBGB_FFOP 9 ///< file operations
// pgm_functions.c
#define DBGB_PSFN 10 ///< start of each function
#define DBGB_PADD 11 ///< additional details
// x393_vidoemem.c
#define DBGB_VM 12 ///< vidoemem all debug
#define DBGB_SCRST 13 ///< vidoemem all debug
// 13
// 14
// 15
// 16
// 17
// 18
// 19
// 20
// 21
// 22
// 23
// 24
// 25
// 26
// 27
// 28
// 29
// 30
// 31
#define DBGB_SFA 1 ///< setFrameParsAtomic (kthread)
#include "klogger_393.h"
#include "framepars.h" // for aglobals
#include "sensor_common.h"// for int getHardFrameNumber(int sensor_port, int use_compressor);
#ifndef ELPHEL_DEBUG393
#define ELPHEL_DEBUG393 1
#if ELPHEL_DEBUG393
static int klog_mode = 0xff; ///< bits specify attributes to log
/// log unconditionally, for any channel
#define MDG(...) print_klog393(klog_mode, __FILE__, __FUNCTION__, __LINE__, __VA_ARGS__);
/// log only if specified bit in G_DEBUG global parameter for the specified sensor port is set
// #define MDP(bit,port,fmt,...) { if (GLOBALPARS(port,G_DEBUG) & (1 << bit)) print_klog393(klog_mode, __FILE__, __FUNCTION__, __LINE__,"%d: "fmt,port,__VA_ARGS__); }
#define MDP(bit,port,fmt,...) { if (GLOBALPARS(port,G_DEBUG) & (1 << bit)) print_klog393(klog_mode, __FILE__, __FUNCTION__, __LINE__,"%d:%d "fmt,port,getHardFrameNumber(port, 0),__VA_ARGS__); }
#else
#define MDF(x)
#define MDP(bit,port,fmt,...)
#endif
#endif
This diff is collapsed.
/***************************************************************************//**
* @file detect_sensors.h
* @brief Determine sensor boards attached to each of the ports. Use
* Device Tree, sysfs to set sensor types per port. Add autodetection
* (using pullup/pull downs) later
* @copyright Copyright 2016 (C) Elphel, Inc.
* @par <b>License</b>
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 2 of the License, or
* (at your option) any later version.
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*******************************************************************************/
#define DETECT_SENSOR 1 ///< Include sensors, May be OR-ed when looking for sensor/multiplexer code/name
#define DETECT_MUX 2 ///< Include multiplexers, May be OR-ed when looking for sensor/multiplexer code/name
typedef enum {NONE,PARALLEL12,HISPI4} sens_iface_t; ///< Sensor port interface type
int get_code_by_name(const char * name, int type);
const char * get_name_by_code(int code, int type);
sens_iface_t get_iface_by_code(int code, int type);
int get_detected_mux_code(int port);
int get_detected_sensor_code(int port, int sub_chn);
int get_subchannels(int port);
int set_detected_mux_code(int port, int mux_type);
int set_detected_sensor_code(int port, int sub_chn, int mux_type);
sens_iface_t get_port_interface(int port);
/*!*************************************************************************** /*!***************************************************************************
*! FILE NAME : elphel393-init.c * @file elphel393-init.c
*! DESCRIPTION: * Unlock rootfs NAND flash partition * @brief * Unlock rootfs NAND flash partition
*! * Read MAC and other useful info from NAND flash OTP area * * Read MAC and other useful info from NAND flash OTP area
*! and put to sysfs * and put to sysfs
*! *
*! E-mail: oleg@elphel.com, support-list@elphel.com * E-mail: oleg@elphel.com, support-list@elphel.com
*! *
*! Copyright (C) 2016 Elphel, Inc. * @copyright Copyright (C) 2016 Elphel, Inc.
*! -----------------------------------------------------------------------------**
*! *
*! This program is free software: you can redistribute it and/or modify * This program is free software: you can redistribute it and/or modify
*! it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
*! the Free Software Foundation, either version 2 of the License, or * the Free Software Foundation, either version 2 of the License, or
*! (at your option) any later version. * (at your option) any later version.
*! *
*! This program is distributed in the hope that it will be useful, * This program is distributed in the hope that it will be useful,
*! but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
*! MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
*! GNU General Public License for more details. * GNU General Public License for more details.
*! *
*! You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
*! along with this program. If not, see <http://www.gnu.org/licenses/>. * along with this program. If not, see <http://www.gnu.org/licenses/>.
*!****************************************************************************/ *****************************************************************************/
#define DRV_NAME "elphel393-init" #define DRV_NAME "elphel393-init"
#define pr_fmt(fmt) DRV_NAME": " fmt #define pr_fmt(fmt) DRV_NAME": " fmt
......
This diff is collapsed.
/*!*************************************************************************** /*!***********************************************************************//**
*! FILE NAME : elphel393-pwr.c * @file elphel393-pwr.c
*! DESCRIPTION: power supplies control on Elphel 10393 board * @brief power supplies control on Elphel 10393 board
*! Copyright (C) 2013-2016 Elphel, Inc. * @copyright Copyright (C) 2013-2016 Elphel, Inc.
*! -----------------------------------------------------------------------------** * @par <b>License</b>
*! * This program is free software: you can redistribute it and/or modify
*! This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by
*! it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 2 of the License, or
*! the Free Software Foundation, either version 2 of the License, or * (at your option) any later version.
*! (at your option) any later version. * This program is distributed in the hope that it will be useful,
*! * but WITHOUT ANY WARRANTY; without even the implied warranty of
*! This program is distributed in the hope that it will be useful, * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
*! but WITHOUT ANY WARRANTY; without even the implied warranty of * GNU General Public License for more details.
*! MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * You should have received a copy of the GNU General Public License
*! GNU General Public License for more details. * along with this program. If not, see <http://www.gnu.org/licenses/>.
*!
*! You should have received a copy of the GNU General Public License
*! along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#undef DEBUG /* should be before linux/module.h - enables dev_dbg at boot in this file */ #undef DEBUG /* should be before linux/module.h - enables dev_dbg at boot in this file */
#include <linux/i2c.h> #include <linux/i2c.h>
......
This diff is collapsed.
/* /*!****************************************************************************//**
exif353.h * @file exif393.h
* @brief Drivers for Exif manipulation
* @copyright Copyright (C) 2008-2016 Elphel, Inc.
* @par <b>License</b>
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#ifndef _EXIF_H #ifndef _EXIF_H
#define _EXIF_H #define _EXIF_H
...@@ -40,5 +53,6 @@ int putlong_meta(int sensor_port, unsigned long data, int * indx, unsigned long ...@@ -40,5 +53,6 @@ int putlong_meta(int sensor_port, unsigned long data, int * indx, unsigned long
char * encode_time(char buf[27], unsigned long sec, unsigned long usec); char * encode_time(char buf[27], unsigned long sec, unsigned long usec);
int store_meta(int sensor_port); //called from IRQ service - put current metadata to meta_buffer, return page index int store_meta(int sensor_port); //called from IRQ service - put current metadata to meta_buffer, return page index
size_t exif_get_data(int sensor_port, unsigned short meta_index, void * buff, size_t buff_sz);
#endif #endif
This diff is collapsed.
This diff is collapsed.
#ifndef _FRAMEPARS_H #ifndef _FRAMEPARS_H
#define _FRAMEPARS_H #define _FRAMEPARS_H
#ifndef SENSOR_PORTS #ifndef SENSOR_PORTS
#include <elphel/c313a.h> // to get SENSOR_PORTS #include <uapi/elphel/c313a.h> // to get SENSOR_PORTS
#endif #endif
//extern struct framepars_t (*framepars)[PARS_FRAMES]; //extern struct framepars_t (*framepars)[PARS_FRAMES];
extern struct framepars_t *aframepars[SENSOR_PORTS]; extern struct framepars_t *aframepars[SENSOR_PORTS];
...@@ -13,23 +13,28 @@ extern wait_queue_head_t aframepars_wait_queue[SENSOR_PORTS]; ...@@ -13,23 +13,28 @@ extern wait_queue_head_t aframepars_wait_queue[SENSOR_PORTS];
///TODO: init framepars (zero parameters) before initscripts (not when detecting the sensors) - then initscript will be able to overwrite some ///TODO: init framepars (zero parameters) before initscripts (not when detecting the sensors) - then initscript will be able to overwrite some
void init_framepars_ptr(int sensor_port); void init_framepars_ptr(int sensor_port);
void initSequencers (int sensor_port); ///Move to sensorcommon? currently it is used through frameparsall file (lseek) int initSequencers (int sensor_port); ///Move to sensorcommon? currently it is used through frameparsall file (lseek)
void initGlobalPars (int sensor_port); /// resets all global parameters but debug mask (if ELPHEL_DEBUG) void initGlobalPars (int sensor_port); /// resets all global parameters but debug mask (if ELPHEL_DEBUG)
int initMultiPars (int sensor_port); /// initialize structures for individual per-sensor parameters. Now only works for sensor registers using G_MULTI_REGSM. Should be called aftre/during sensor detection int initMultiPars (int sensor_port); /// initialize structures for individual per-sensor parameters. Now only works for sensor registers using G_MULTI_REGSM. Should be called aftre/during sensor detection
void initFramePars (int sensor_port); ///initialize all parameters, set thisFrameNumber to frame8 (read from hardware, usually 0 after resetting i2c and cmd_seq) void initFramePars (int sensor_port); ///initialize all parameters, set thisFrameNumber to frame8 (read from hardware, usually 0 after resetting i2c and cmd_seq)
void resetFrameNumber (int sensor_port); /// reset this frame number (called from initFramePars(), also can be used to avoid frame number integer overflow) void resetFrameNumber (int sensor_port, u32 aframe, int hreset); /// reset this frame number (called from initFramePars(), also can be used to avoid frame number integer overflow)
unsigned long get_imageParamsFrame(int sensor_port, int n, int frame);
unsigned long get_imageParamsThis (int sensor_port, int n); unsigned long get_imageParamsThis (int sensor_port, int n);
unsigned long get_imageParamsPrev (int sensor_port, int n); unsigned long get_imageParamsPrev (int sensor_port, int n);
unsigned long get_imageParamsPast(int sensor_port, int n, int frame);
unsigned long * get_imageParamsFramePtr(int sensor_port, int n, int frame);
unsigned long * get_imageParamsPastPtr (int sensor_port, int n, int frame);
void set_imageParamsThis (int sensor_port, int n, unsigned long d); void set_imageParamsThis (int sensor_port, int n, unsigned long d);
unsigned long get_globalParam (int sensor_port, int n); unsigned long get_globalParam (int sensor_port, int n);
void set_globalParam (int sensor_port, int n, unsigned long d); void set_globalParam (int sensor_port, int n, unsigned long d);
void set_imageParamsR_all(int sensor_port, int n, unsigned long d); void set_imageParamsR_all(int sensor_port, int n, unsigned long d);
void updateFramePars (int sensor_port, int frame8, struct interframe_params_t * frame_pars); /// called from ISR - advance thisFrameNumber to match hardware frame8, copy parameters as needed. //Next 2 called from ISR
/// frame8 usually is just next after thisFrameNumber void updateInterFrame(int sensor_port, u32 compressed_frame, struct interframe_params_t * interframe_pars);
/// frame_pars - pointer to structure (between frames in the frame buffer) to save a pointer to past parameters void updateFramePars (int sensor_port, int frame16);
int setFrameParsStatic (int sensor_port, int numPars, struct frameparspair_t * pars); int setFrameParsStatic (int sensor_port, int numPars, struct frameparspair_t * pars);
unsigned long getThisFrameNumber (int sensor_port); /// just return current thisFrameNumber unsigned long getThisFrameNumber (int sensor_port); /// just return current thisFrameNumber
...@@ -38,33 +43,33 @@ unsigned long getThisFrameNumber (int sensor_port); /// just return current thi ...@@ -38,33 +43,33 @@ unsigned long getThisFrameNumber (int sensor_port); /// just return current thi
/// Return - 0 if OK, -ERR_FRAMEPARS_TOOEARLY or -ERR_FRAMEPARS_TOOLATE if it is too early or too late to set parameters (numPars may be 0 to just test) /// Return - 0 if OK, -ERR_FRAMEPARS_TOOEARLY or -ERR_FRAMEPARS_TOOLATE if it is too early or too late to set parameters (numPars may be 0 to just test)
/// ///
/// NOTE: When writing parameter to P_SENSOR_RUN or P_COMPRESSOR_RUN "*_RUN_SINGLE", first write "*SENSOR_RUN_STOP" (it will propagate to all next frames) and then /// NOTE: When writing parameter to P_SENSOR_RUN or P_COMPRESSOR_RUN "*_RUN_SINGLE", first write "*SENSOR_RUN_STOP" (it will propagate to all next frames) and then
/// write "*_RUN_SINGLE", to (P_*_RUN | FRAMEPAIR_JUST_THIS) - then this *_RUN_SINGLE will not propagate to the next frames (they will stay stopped) // write "*_RUN_SINGLE", to (P_*_RUN | FRAMEPAIR_JUST_THIS) - then this *_RUN_SINGLE will not propagate to the next frames (they will stay stopped)
/// TODO: Make (an "unlimited") future commands que based on lists and a tree frame index // TODO: Make (an "unlimited") future commands que based on lists and a tree frame index
int setFrameParsAtomic (int sensor_port, unsigned long frameno, int maxLatency, int numPars, struct frameparspair_t * pars); int setFrameParsAtomic (int sensor_port, unsigned long frameno, int maxLatency, int numPars, struct frameparspair_t * pars);
/// set output/calculated parameter and propagate changes - will not trigger any actions // set output/calculated parameter and propagate changes - will not trigger any actions
int setFramePar (int sensor_port, struct framepars_t * this_framepars, unsigned long mindex, unsigned long val); int setFramePar (int sensor_port, struct framepars_t * this_framepars, unsigned long mindex, unsigned long val);
// Same, but adds lock to call from user thread
int setFrameParLocked (int sensor_port, struct framepars_t * this_framepars, unsigned long mindex, unsigned long val);
///same for several pars at once ///same for several pars at once
int setFramePars (int sensor_port, struct framepars_t * this_framepars, int numPars, struct frameparspair_t * pars); int setFramePars (int sensor_port, struct framepars_t * this_framepars, int numPars, struct frameparspair_t * pars);
/// schedule pgm_func to be executed for selected frame /// schedule pgm_func to be executed for selected frame
void schedule_pgm_func (int sensor_port, int frame8, int func_num); void schedule_pgm_func (int sensor_port, int frame8, int func_num);
/// schedule pgm_func to be executed for the current frame // schedule pgm_func to be executed for the current frame
void schedule_this_pgm_func (int sensor_port, struct framepars_t * this_framepars, int func_num); void schedule_this_pgm_func (int sensor_port, struct framepars_t * this_framepars, int func_num);
/// program acquisition, according to the parameters changed. // program acquisition, according to the parameters changed.
/// maxahead - how many frames ahead of time (start with most urgent, then 1 ahead, ...) // maxahead - how many frames ahead of time (start with most urgent, then 1 ahead, ...)
/// make maxahead - P_* parameter? // make maxahead - P_* parameter?
/* 393: See if sesnor port is needed here */ /* 393: See if sensor port is needed here */
inline void processParsASAP (int sensor_port, struct sensorproc_t * sensorproc, int frame8); /* NC393: Removed, should not be called from outside the lock-ed processPars() */
inline void processParsSeq (int sensor_port, struct sensorproc_t * sensorproc, int frame8, int maxahead); //inline void _processParsASAP (int sensor_port, struct sensorproc_t * sensorproc, int frame8);
//inline void _processParsSeq (int sensor_port, struct sensorproc_t * sensorproc, int frame8, int maxahead);
void processPars (int sensor_port, struct sensorproc_t * sensorproc, int frame8, int maxahead);
///*** TODO: Add option (flag?) to write "single" (like single compress, single sensor) so it will not make all the next frames "single"
int framepars_init (struct platform_device *pdev);
int framepars_remove (struct platform_device *pdev);
int processPars (int sensor_port, struct sensorproc_t * sensorproc, int frame8, int maxahead);
// *** TODO: Add option (flag?) to write "single" (like single compress, single sensor) so it will not make all the next frames "single"
#endif #endif
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
...@@ -14,6 +14,7 @@ int jpegheader_create(struct interframe_params_t * params, unsigned char * b ...@@ -14,6 +14,7 @@ int jpegheader_create(struct interframe_params_t * params, unsigned char * b
int jpeghead_open (struct inode *inode, struct file *filp); // set filesize int jpeghead_open (struct inode *inode, struct file *filp); // set filesize
loff_t jpeghead_lseek (struct file * file, loff_t offset, int orig, struct interframe_params_t *fp); loff_t jpeghead_lseek (struct file * file, loff_t offset, int orig, struct interframe_params_t *fp);
ssize_t jpeghead_read (struct file * file, char * buf, size_t count, loff_t *off); ssize_t jpeghead_read (struct file * file, char * buf, size_t count, loff_t *off);
ssize_t jpeghead_get_data(int sensor_port, void *buff, size_t buff_sz, size_t offset);
int huffman_open (struct inode *inode, struct file *filp); // set filesize int huffman_open (struct inode *inode, struct file *filp); // set filesize
int huffman_release(struct inode *inode, struct file *filp); int huffman_release(struct inode *inode, struct file *filp);
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment