Merge branch 'next' into next_novolk

This commit is contained in:
Ismael Gomez 2017-10-02 17:57:38 +01:00
commit 4375113efc
129 changed files with 4574 additions and 2214 deletions

View File

@ -72,6 +72,7 @@ Build Instructions
* Mandatory requirements:
* Common:
* cmake https://cmake.org/
* libfftw http://www.fftw.org/
* PolarSSL/mbedTLS https://tls.mbed.org
* srsUE:
@ -83,7 +84,7 @@ Build Instructions
For example, on Ubuntu 17.04, one can install the required libraries with:
```
sudo apt-get install libfftw3-dev libmbedtls-dev libboost-all-dev libconfig++-dev libsctp-dev
sudo apt-get install cmake libfftw3-dev libmbedtls-dev libboost-all-dev libconfig++-dev libsctp-dev
```
Note that depending on your flavor and version of Linux, the actual package names may be different.

View File

@ -335,10 +335,9 @@ int main(int argc, char **argv) {
fprintf(stderr, "Error decoding UE DL\n");fflush(stdout);
return -1;
} else if (n == 0) {
printf("CFO: %+6.4f kHz, SFO: %+6.4f kHz, NOI: %.2f, PDCCH-Det: %.3f\r",
printf("CFO: %+6.4f kHz, SFO: %+6.4f kHz, PDCCH-Det: %.3f\r",
srslte_ue_sync_get_cfo(&ue_sync)/1000, srslte_ue_sync_get_sfo(&ue_sync)/1000,
srslte_pdsch_average_noi(&ue_dl.pdsch),
(float) ue_dl.nof_detected/nof_trials);
(float) ue_dl.nof_detected/nof_trials);
nof_trials++;
} else {
printf("Decoded SIB1. Payload: ");

View File

@ -27,7 +27,9 @@
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <strings.h>
#include <unistd.h>
#include <sys/select.h>
#include <pthread.h>
#include <semaphore.h>
#include <signal.h>
@ -38,10 +40,11 @@
#define UE_CRNTI 0x1234
#define M_CRNTI 0xFFFD
#ifndef DISABLE_RF
#include "srslte/phy/rf/rf.h"
#include "srslte/phy/common/phy_common.h"
srslte_rf_t rf;
#else
#warning Compiling pdsch_ue with no RF support
@ -55,52 +58,67 @@ char *output_file_name = NULL;
#define DOWN_KEY 66
srslte_cell_t cell = {
25, // nof_prb
1, // nof_ports
0, // cell_id
SRSLTE_CP_NORM, // cyclic prefix
SRSLTE_PHICH_NORM, // PHICH length
SRSLTE_PHICH_R_1 // PHICH resources
25, // nof_prb
1, // nof_ports
0, // cell_id
SRSLTE_CP_NORM, // cyclic prefix
SRSLTE_PHICH_NORM, // PHICH length
SRSLTE_PHICH_R_1 // PHICH resources
};
uint16_t c = -1;
int net_port = -1; // -1 generates random dataThat means there is some problem sending samples to the device
uint32_t cfi = 1;
uint32_t cfi = 2;
uint32_t mcs_idx = 1, last_mcs_idx = 1;
int nof_frames = -1;
char mimo_type_str[32] = "single";
uint32_t nof_tb = 1;
uint32_t multiplex_pmi = 0;
uint32_t multiplex_nof_layers = 1;
int mbsfn_area_id = -1;
char *rf_args = "";
float rf_amp = 0.8, rf_gain = 70.0, rf_freq = 2400000000;
bool null_file_sink=false;
srslte_filesink_t fsink;
srslte_ofdm_t ifft;
srslte_ofdm_t ifft_mbsfn;
srslte_pbch_t pbch;
srslte_pcfich_t pcfich;
srslte_pdcch_t pdcch;
srslte_pdsch_t pdsch;
srslte_pdsch_cfg_t pdsch_cfg;
srslte_pdsch_cfg_t pdsch_cfg;
srslte_pmch_t pmch;
srslte_pdsch_cfg_t pmch_cfg;
srslte_softbuffer_tx_t *softbuffers[SRSLTE_MAX_CODEWORDS];
srslte_regs_t regs;
srslte_ra_dl_dci_t ra_dl;
srslte_ra_dl_dci_t ra_dl;
int rvidx[SRSLTE_MAX_CODEWORDS] = {0, 0};
cf_t *sf_buffer[SRSLTE_MAX_PORTS] = {NULL}, *output_buffer [SRSLTE_MAX_PORTS] = {NULL};
int sf_n_re, sf_n_samples;
pthread_t net_thread;
pthread_t net_thread;
void *net_thread_fnc(void *arg);
sem_t net_sem;
bool net_packet_ready = false;
srslte_netsource_t net_source;
srslte_netsink_t net_sink;
int prbset_num = 1, last_prbset_num = 1;
int prbset_orig = 0;
//#define DATA_BUFF_SZ 1024*128
//uint8_t data[8*DATA_BUFF_SZ], data2[DATA_BUFF_SZ];
//uint8_t data_tmp[DATA_BUFF_SZ];
#define DATA_BUFF_SZ 1024*1024
uint8_t *data[2], data2[DATA_BUFF_SZ];
@ -121,6 +139,7 @@ void usage(char *prog) {
printf("\t-n number of frames [Default %d]\n", nof_frames);
printf("\t-c cell id [Default %d]\n", cell.id);
printf("\t-p nof_prb [Default %d]\n", cell.nof_prb);
printf("\t-M MBSFN area id [Default %d]\n", mbsfn_area_id);
printf("\t-x Transmission mode[single|diversity|cdd|multiplex] [Default %s]\n", mimo_type_str);
printf("\t-b Precoding Matrix Index (multiplex mode only)* [Default %d]\n", multiplex_pmi);
printf("\t-w Number of codewords/layers (multiplex mode only)* [Default %d]\n", multiplex_nof_layers);
@ -132,7 +151,8 @@ void usage(char *prog) {
void parse_args(int argc, char **argv) {
int opt;
while ((opt = getopt(argc, argv, "aglfmoncpvutxbw")) != -1) {
while ((opt = getopt(argc, argv, "aglfmoncpvutxbwM")) != -1) {
switch (opt) {
case 'a':
rf_args = argv[optind];
@ -173,6 +193,9 @@ void parse_args(int argc, char **argv) {
case 'w':
multiplex_nof_layers = (uint32_t) atoi(argv[optind]);
break;
case 'M':
mbsfn_area_id = atoi(argv[optind]);
break;
case 'v':
srslte_verbose++;
break;
@ -188,7 +211,7 @@ void parse_args(int argc, char **argv) {
}
#endif
}
void base_init() {
int i;
@ -245,6 +268,7 @@ void base_init() {
bzero(output_buffer[i], sizeof(cf_t) * sf_n_samples);
}
/* open file or USRP */
if (output_file_name) {
if (strcmp(output_file_name, "NULL")) {
@ -291,7 +315,15 @@ void base_init() {
fprintf(stderr, "Error creating iFFT object\n");
exit(-1);
}
if (srslte_ofdm_tx_init_mbsfn(&ifft_mbsfn, SRSLTE_CP_EXT, cell.nof_prb)) {
fprintf(stderr, "Error creating iFFT object\n");
exit(-1);
}
srslte_ofdm_set_non_mbsfn_region(&ifft_mbsfn, 2);
srslte_ofdm_set_normalize(&ifft, true);
srslte_ofdm_set_normalize(&ifft_mbsfn, true);
if (srslte_pbch_init(&pbch)) {
fprintf(stderr, "Error creating PBCH object\n");
exit(-1);
@ -300,12 +332,14 @@ void base_init() {
fprintf(stderr, "Error creating PBCH object\n");
exit(-1);
}
if (srslte_regs_init(&regs, cell)) {
fprintf(stderr, "Error initiating regs\n");
exit(-1);
}
if (srslte_pcfich_init(&pcfich, 1)) {
fprintf(stderr, "Error creating PBCH object\n");
exit(-1);
@ -340,6 +374,14 @@ void base_init() {
srslte_pdsch_set_rnti(&pdsch, UE_CRNTI);
if(mbsfn_area_id > -1){
if (srslte_pmch_init(&pmch, cell.nof_prb)) {
fprintf(stderr, "Error creating PMCH object\n");
}
srslte_pmch_set_area_id(&pmch, mbsfn_area_id);
}
for (i = 0; i < SRSLTE_MAX_CODEWORDS; i++) {
softbuffers[i] = calloc(sizeof(srslte_softbuffer_tx_t), 1);
if (!softbuffers[i]) {
@ -354,6 +396,7 @@ void base_init() {
}
}
void base_free() {
int i;
for (i = 0; i < SRSLTE_MAX_CODEWORDS; i++) {
@ -366,8 +409,12 @@ void base_free() {
srslte_pdcch_free(&pdcch);
srslte_regs_free(&regs);
srslte_pbch_free(&pbch);
if(mbsfn_area_id > -1){
srslte_pmch_free(&pmch);
}
srslte_ofdm_tx_free(&ifft_mbsfn);
srslte_ofdm_tx_free(&ifft);
for (i = 0; i < SRSLTE_MAX_CODEWORDS; i++) {
if (data[i]) {
@ -481,7 +528,7 @@ int update_radl() {
srslte_ra_dl_dci_to_grant(&ra_dl, cell.nof_prb, UE_CRNTI, &dummy_grant);
srslte_ra_dl_grant_to_nbits(&dummy_grant, cfi, cell, 0, &dummy_nbits);
srslte_ra_dl_grant_fprint(stdout, &dummy_grant);
dummy_grant.sf_type = SRSLTE_SF_NORM;
if (pdsch_cfg.mimo_type != SRSLTE_MIMO_TYPE_SINGLE_ANTENNA) {
printf("\nTransmission mode key table:\n");
printf(" Mode | 1TB | 2TB |\n");
@ -596,6 +643,7 @@ int update_control() {
}
}
/** Function run in a separate thread to receive UDP data */
void *net_thread_fnc(void *arg) {
int n;
@ -633,6 +681,7 @@ void *net_thread_fnc(void *arg) {
return NULL;
}
int main(int argc, char **argv) {
int nf=0, sf_idx=0, N_id_2=0;
cf_t pss_signal[SRSLTE_PSS_LEN];
@ -645,7 +694,8 @@ int main(int argc, char **argv) {
srslte_dci_msg_t dci_msg;
srslte_dci_location_t locations[SRSLTE_NSUBFRAMES_X_FRAME][30];
uint32_t sfn;
srslte_chest_dl_t est;
srslte_refsignal_t csr_refs;
srslte_refsignal_t mbsfn_refs;
#ifdef DISABLE_RF
if (argc < 3) {
@ -674,21 +724,31 @@ int main(int argc, char **argv) {
srslte_pss_generate(pss_signal, N_id_2);
srslte_sss_generate(sss_signal0, sss_signal5, cell.id);
/* Generate CRS signals */
if (srslte_chest_dl_init(&est, cell.nof_prb)) {
fprintf(stderr, "Error initializing equalizer\n");
exit(-1);
}
if (srslte_chest_dl_set_cell(&est, cell)) {
fprintf(stderr, "Error initializing equalizer\n");
exit(-1);
}
/* Generate reference signals */
if(srslte_refsignal_cs_init(&csr_refs, cell.nof_prb)) {
fprintf(stderr, "Error initializing equalizer\n");
exit(-1);
}
if(mbsfn_area_id > -1) {
if(srslte_refsignal_mbsfn_init(&mbsfn_refs, cell, mbsfn_area_id)) {
fprintf(stderr, "Error initializing equalizer\n");
exit(-1);
}
}
if(srslte_refsignal_cs_set_cell(&csr_refs, cell)){
fprintf(stderr, "Error setting cell\n");
exit(-1);
}
for (i = 0; i < SRSLTE_MAX_PORTS; i++) {
sf_symbols[i] = sf_buffer[i%cell.nof_ports];
slot1_symbols[i] = &sf_buffer[i%cell.nof_ports][SRSLTE_SLOT_LEN_RE(cell.nof_prb, cell.cp)];
}
#ifndef DISABLE_RF
@ -737,48 +797,51 @@ int main(int argc, char **argv) {
/* Initiate valid DCI locations */
for (i=0;i<SRSLTE_NSUBFRAMES_X_FRAME;i++) {
srslte_pdcch_ue_locations(&pdcch, locations[i], 30, i, cfi, UE_CRNTI);
}
nf = 0;
bool send_data = false;
for (i = 0; i < SRSLTE_MAX_CODEWORDS; i++) {
for (i = 0; i < SRSLTE_MAX_CODEWORDS; i++) {
srslte_softbuffer_tx_reset(softbuffers[i]);
}
#ifndef DISABLE_RF
bool start_of_burst = true;
#endif
while ((nf < nof_frames || nof_frames == -1) && !go_exit) {
for (sf_idx = 0; sf_idx < SRSLTE_NSUBFRAMES_X_FRAME && (nf < nof_frames || nof_frames == -1); sf_idx++) {
/* Set Antenna port resource elements to zero */
bzero(sf_symbols[0], sizeof(cf_t) * sf_n_re);
/* Populate Synchronization signals if required */
if (sf_idx == 0 || sf_idx == 5) {
srslte_pss_put_slot(pss_signal, sf_symbols[0], cell.nof_prb, SRSLTE_CP_NORM);
srslte_sss_put_slot(sf_idx ? sss_signal5 : sss_signal0, sf_symbols[0], cell.nof_prb,
SRSLTE_CP_NORM);
}
/* Copy zeros, SSS, PSS into the rest of antenna ports */
for (i = 1; i < cell.nof_ports; i++) {
memcpy(sf_symbols[i], sf_symbols[0], sizeof(cf_t) * sf_n_re);
}
/* Put reference signals */
for (i = 0; i < cell.nof_ports; i++) {
srslte_refsignal_cs_put_sf(cell, (uint32_t) i, est.csr_signal.pilots[i / 2][sf_idx], sf_symbols[i]);
if(sf_idx == 1 && mbsfn_area_id > -1){
srslte_refsignal_mbsfn_put_sf(cell, 0,csr_refs.pilots[0][sf_idx], mbsfn_refs.pilots[0][sf_idx], sf_symbols[0]);
} else {
for (i = 0; i < cell.nof_ports; i++) {
srslte_refsignal_cs_put_sf(cell, (uint32_t) i, csr_refs.pilots[i / 2][sf_idx], sf_symbols[i]);
}
}
srslte_pbch_mib_pack(&cell, sfn, bch_payload);
if (sf_idx == 0) {
srslte_pbch_encode(&pbch, bch_payload, slot1_symbols, nf%4);
}
srslte_pcfich_encode(&pcfich, cfi, sf_symbols, sf_idx);
srslte_pcfich_encode(&pcfich, cfi, sf_symbols, sf_idx);
/* Update DL resource allocation from control port */
if (update_control(sf_idx)) {
@ -806,86 +869,134 @@ int main(int argc, char **argv) {
} else {
send_data = false;
}
}
}
if (send_data) {
srslte_dci_format_t dci_format;
switch(pdsch_cfg.mimo_type) {
case SRSLTE_MIMO_TYPE_SINGLE_ANTENNA:
dci_format = SRSLTE_DCI_FORMAT1;
break;
case SRSLTE_MIMO_TYPE_TX_DIVERSITY:
case SRSLTE_MIMO_TYPE_CDD:
dci_format = SRSLTE_DCI_FORMAT2A;
break;
case SRSLTE_MIMO_TYPE_SPATIAL_MULTIPLEX:
dci_format = SRSLTE_DCI_FORMAT2;
if (multiplex_nof_layers == 1) {
ra_dl.pinfo = (uint8_t) (multiplex_pmi + 1);
} else {
ra_dl.pinfo = (uint8_t) multiplex_pmi;
}
break;
default:
fprintf(stderr, "Wrong MIMO configuration\n");
exit(SRSLTE_ERROR);
}
/* Encode PDCCH */
INFO("Putting DCI to location: n=%d, L=%d\n", locations[sf_idx][0].ncce, locations[sf_idx][0].L);
srslte_dci_msg_pack_pdsch(&ra_dl, dci_format, &dci_msg, cell.nof_prb, cell.nof_ports, false);
if (srslte_pdcch_encode(&pdcch, &dci_msg, locations[sf_idx][0], UE_CRNTI, sf_symbols, sf_idx, cfi)) {
fprintf(stderr, "Error encoding DCI message\n");
exit(-1);
}
if(sf_idx != 1 || mbsfn_area_id < 0) { // PDCCH + PDSCH
srslte_dci_format_t dci_format;
switch(pdsch_cfg.mimo_type) {
case SRSLTE_MIMO_TYPE_SINGLE_ANTENNA:
dci_format = SRSLTE_DCI_FORMAT1;
break;
case SRSLTE_MIMO_TYPE_TX_DIVERSITY:
case SRSLTE_MIMO_TYPE_CDD:
dci_format = SRSLTE_DCI_FORMAT2A;
break;
case SRSLTE_MIMO_TYPE_SPATIAL_MULTIPLEX:
dci_format = SRSLTE_DCI_FORMAT2;
if (multiplex_nof_layers == 1) {
ra_dl.pinfo = (uint8_t) (multiplex_pmi + 1);
} else {
ra_dl.pinfo = (uint8_t) multiplex_pmi;
}
break;
default:
fprintf(stderr, "Wrong MIMO configuration\n");
exit(SRSLTE_ERROR);
}
/* Encode PDCCH */
INFO("Putting DCI to location: n=%d, L=%d\n", locations[sf_idx][0].ncce, locations[sf_idx][0].L);
srslte_dci_msg_pack_pdsch(&ra_dl, dci_format, &dci_msg, cell.nof_prb, cell.nof_ports, false);
if (srslte_pdcch_encode(&pdcch, &dci_msg, locations[sf_idx][0], UE_CRNTI, sf_symbols, sf_idx, cfi)) {
fprintf(stderr, "Error encoding DCI message\n");
exit(-1);
}
/* Configure pdsch_cfg parameters */
srslte_ra_dl_grant_t grant;
srslte_ra_dl_dci_to_grant(&ra_dl, cell.nof_prb, UE_CRNTI, &grant);
if (srslte_pdsch_cfg_mimo(&pdsch_cfg, cell, &grant, cfi, sf_idx, rvidx, pdsch_cfg.mimo_type, multiplex_pmi)) {
fprintf(stderr, "Error configuring PDSCH\n");
exit(-1);
}
/* Encode PDSCH */
if (srslte_pdsch_encode(&pdsch, &pdsch_cfg, softbuffers, data, UE_CRNTI, sf_symbols)) {
fprintf(stderr, "Error encoding PDSCH\n");
exit(-1);
}
if (net_port > 0 && net_packet_ready) {
if (null_file_sink) {
for (uint32_t tb = 0; tb < SRSLTE_MAX_CODEWORDS; tb++) {
if (pdsch_cfg.grant.tb_en[tb]) {
/* Configure pdsch_cfg parameters */
srslte_ra_dl_grant_t grant;
srslte_ra_dl_dci_to_grant(&ra_dl, cell.nof_prb, UE_CRNTI, &grant);
if (srslte_pdsch_cfg_mimo(&pdsch_cfg, cell, &grant, cfi, sf_idx, rvidx, pdsch_cfg.mimo_type, multiplex_pmi)) {
fprintf(stderr, "Error configuring PDSCH\n");
exit(-1);
}
/* Encode PDSCH */
if (srslte_pdsch_encode(&pdsch, &pdsch_cfg, softbuffers, data, UE_CRNTI, sf_symbols)) {
fprintf(stderr, "Error encoding PDSCH\n");
exit(-1);
}
if (net_port > 0 && net_packet_ready) {
if (null_file_sink) {
for (uint32_t tb = 0; tb < SRSLTE_MAX_CODEWORDS; tb++) {
srslte_bit_pack_vector(data[tb], data_tmp, pdsch_cfg.grant.mcs[tb].tbs);
if (srslte_netsink_write(&net_sink, data_tmp, 1 + (pdsch_cfg.grant.mcs[tb].tbs - 1) / 8) < 0) {
fprintf(stderr, "Error sending data through UDP socket\n");
}
}
}
net_packet_ready = false;
sem_post(&net_sem);
}
}else{ // We're sending MCH on subframe 1 - PDCCH + PMCH
/* Encode PDCCH */
INFO("Putting DCI to location: n=%d, L=%d\n", locations[sf_idx][0].ncce, locations[sf_idx][0].L);
srslte_dci_msg_pack_pdsch(&ra_dl, SRSLTE_DCI_FORMAT1, &dci_msg, cell.nof_prb, cell.nof_ports, false);
if (srslte_pdcch_encode(&pdcch, &dci_msg, locations[sf_idx][0], M_CRNTI, sf_symbols, sf_idx, cfi)) {
fprintf(stderr, "Error encoding DCI message\n");
exit(-1);
}
/* Configure pmch_cfg parameters */
srslte_ra_dl_grant_t grant;
grant.nof_tb = 1;
grant.mcs[0].idx = 2;
grant.mcs[0].mod = SRSLTE_MOD_QPSK;
grant.nof_prb = cell.nof_prb;
grant.sf_type = SRSLTE_SF_MBSFN;
grant.Qm[0] = srslte_mod_bits_x_symbol(grant.mcs[0].mod);
srslte_dl_fill_ra_mcs(&grant.mcs[0], cell.nof_prb);
for(int i = 0; i < 2; i++){
for(int j = 0; j < grant.nof_prb; j++){
grant.prb_idx[i][j] = true;
}
}
if (srslte_pmch_cfg(&pmch_cfg, cell, &grant, cfi, sf_idx)) {
fprintf(stderr, "Error configuring PMCH\n");
exit(-1);
}
/* Encode PMCH */
if (srslte_pmch_encode(&pmch, &pmch_cfg, softbuffers[0], data[0], mbsfn_area_id, sf_symbols)) {
fprintf(stderr, "Error encoding PDSCH\n");
exit(-1);
}
if (net_port > 0 && net_packet_ready) {
if (null_file_sink) {
srslte_bit_pack_vector(data[0], data_tmp, pmch_cfg.grant.mcs[0].tbs);
if (srslte_netsink_write(&net_sink, data_tmp, 1+(pmch_cfg.grant.mcs[0].tbs-1)/8) < 0) {
fprintf(stderr, "Error sending data through UDP socket\n");
}
}
net_packet_ready = false;
sem_post(&net_sem);
}
net_packet_ready = false;
sem_post(&net_sem);
}
}
/* Transform to OFDM symbols */
for (i = 0; i < cell.nof_ports; i++) {
srslte_ofdm_tx_sf(&ifft, sf_buffer[i], output_buffer[i]);
}
/* Transform to OFDM symbols */
if(sf_idx != 1 || mbsfn_area_id < 0){
for (i = 0; i < cell.nof_ports; i++) {
srslte_ofdm_tx_sf(&ifft, sf_buffer[i], output_buffer[i]);
}
}else{
srslte_ofdm_tx_sf(&ifft_mbsfn, sf_buffer[0], output_buffer[0]);
}
/* send to file or usrp */
if (output_file_name) {
if (!null_file_sink) {
srslte_filesink_write_multi(&fsink, (void**) output_buffer, sf_n_samples, cell.nof_ports);
srslte_filesink_write_multi(&fsink, (void**) output_buffer, sf_n_samples, cell.nof_ports);
}
usleep(1000);
} else {
#ifndef DISABLE_RF
float norm_factor = (float) cell.nof_prb/15/sqrtf(pdsch_cfg.grant.nof_prb);
for (i = 0; i < cell.nof_ports; i++) {
srslte_vec_sc_prod_cfc(output_buffer[i], rf_amp * norm_factor, output_buffer[i], SRSLTE_SF_LEN_PRB(cell.nof_prb));
}
srslte_rf_send_multi(&rf, (void**) output_buffer, sf_n_samples, true, start_of_burst, false);
start_of_burst=false;
float norm_factor = (float) cell.nof_prb/15/sqrtf(pdsch_cfg.grant.nof_prb);
for (i = 0; i < cell.nof_ports; i++) {
srslte_vec_sc_prod_cfc(output_buffer[i], rf_amp * norm_factor, output_buffer[i], SRSLTE_SF_LEN_PRB(cell.nof_prb));
}
srslte_rf_send_multi(&rf, (void**) output_buffer, sf_n_samples, true, start_of_burst, false);
start_of_burst=false;
#endif
}
}

View File

@ -36,10 +36,8 @@
#include <signal.h>
#include <pthread.h>
#include <semaphore.h>
#include <srslte/srslte.h>
#include <srslte/phy/phch/pdsch_cfg.h>
#include <srslte/phy/phch/ra.h>
#include <srslte/phy/common/phy_common.h>
#include "srslte/phy/io/filesink.h"
#include "srslte/srslte.h"
#define ENABLE_AGC_DEFAULT
@ -69,7 +67,7 @@ sem_t plot_sem;
uint32_t plot_sf_idx=0;
bool plot_track = true;
#endif
char *output_file_name;
#define PRINT_CHANGE_SCHEDULIGN
//#define CORRECT_SAMPLE_OFFSET
@ -101,6 +99,8 @@ typedef struct {
int net_port_signal;
char *net_address_signal;
int decimate;
int32_t mbsfn_area_id;
uint8_t non_mbsfn_region;
int verbose;
}prog_args_t;
@ -132,10 +132,12 @@ void args_default(prog_args_t *args) {
args->net_address_signal = "127.0.0.1";
args->decimate = 0;
args->cpu_affinity = -1;
args->mbsfn_area_id = -1;
args->non_mbsfn_region = 2;
}
void usage(prog_args_t *args, char *prog) {
printf("Usage: %s [agpPoOcildDnruv] -f rx_frequency (in Hz) | -i input_file\n", prog);
printf("Usage: %s [agpPoOcildDnruMNv] -f rx_frequency (in Hz) | -i input_file\n", prog);
#ifndef DISABLE_RF
printf("\t-a RF args [Default %s]\n", args->rf_args);
printf("\t-A Number of RX antennas [Default %d]\n", args->rf_nof_rx_ant);
@ -169,13 +171,15 @@ void usage(prog_args_t *args, char *prog) {
printf("\t-S remote UDP address to send input signal [Default %s]\n", args->net_address_signal);
printf("\t-u remote TCP port to send data (-1 does nothing with it) [Default %d]\n", args->net_port);
printf("\t-U remote TCP address to send data [Default %s]\n", args->net_address);
printf("\t-M MBSFN area id [Default %d]\n", args->mbsfn_area_id);
printf("\t-N Non-MBSFN region [Default %d]\n", args->non_mbsfn_region);
printf("\t-v [set srslte_verbose to debug, default none]\n");
}
void parse_args(prog_args_t *args, int argc, char **argv) {
int opt;
args_default(args);
while ((opt = getopt(argc, argv, "aAoglipPcOCtdDnvrfuUsSZy")) != -1) {
while ((opt = getopt(argc, argv, "aAoglipPcOCtdDnvrfuUsSZyWMN")) != -1) {
switch (opt) {
case 'i':
args->input_file_name = argv[optind];
@ -250,6 +254,15 @@ void parse_args(prog_args_t *args, int argc, char **argv) {
case 'y':
args->cpu_affinity = atoi(argv[optind]);
break;
case 'W':
output_file_name = argv[optind];
break;
case 'M':
args->mbsfn_area_id = atoi(argv[optind]);
break;
case 'N':
args->non_mbsfn_region = atoi(argv[optind]);
break;
default:
usage(args, argv[0]);
exit(-1);
@ -278,6 +291,7 @@ void sig_int_handler(int signo)
cf_t *sf_buffer[SRSLTE_MAX_PORTS] = {NULL};
#ifndef DISABLE_RF
int srslte_rf_recv_wrapper(void *h, cf_t *data[SRSLTE_MAX_PORTS], uint32_t nsamples, srslte_timestamp_t *t) {
DEBUG(" ---- Receive %d samples ---- \n", nsamples);
@ -303,9 +317,9 @@ srslte_ue_sync_t ue_sync;
prog_args_t prog_args;
uint32_t sfn = 0; // system frame number
srslte_netsink_t net_sink, net_sink_signal;
srslte_netsink_t net_sink, net_sink_signal;
/* Useful macros for printing lines which will disappear */
#define PRINT_LINE_INIT() int this_nof_lines = 0; static int prev_nof_lines = 0
#define PRINT_LINE(_fmt, ...) printf("\033[K" _fmt "\n", ##__VA_ARGS__); this_nof_lines++
#define PRINT_LINE_RESET_CURSOR() printf("\033[%dA", this_nof_lines); prev_nof_lines = this_nof_lines
@ -317,6 +331,7 @@ int main(int argc, char **argv) {
srslte_cell_t cell;
int64_t sf_cnt;
srslte_ue_mib_t ue_mib;
#ifndef DISABLE_RF
srslte_rf_t rf;
#endif
@ -324,7 +339,7 @@ int main(int argc, char **argv) {
uint8_t bch_payload[SRSLTE_BCH_PAYLOAD_LEN];
int sfn_offset;
float cfo = 0;
parse_args(&prog_args, argc, argv);
for (int i = 0; i< SRSLTE_MAX_CODEWORDS; i++) {
@ -335,6 +350,7 @@ int main(int argc, char **argv) {
}
}
if(prog_args.cpu_affinity > -1) {
cpu_set_t cpuset;
@ -403,6 +419,7 @@ int main(int argc, char **argv) {
srslte_rf_set_rx_freq(&rf, prog_args.rf_freq + prog_args.file_offset_freq);
srslte_rf_rx_wait_lo_locked(&rf);
uint32_t ntrial=0;
do {
ret = rf_search_and_decode_mib(&rf, prog_args.rf_nof_rx_ant, &cell_detect_config, prog_args.force_N_id_2, &cell, &cfo);
@ -455,7 +472,7 @@ int main(int argc, char **argv) {
cell.nof_ports = prog_args.file_nof_ports;
cell.nof_prb = prog_args.file_nof_prb;
if (srslte_ue_sync_init_file_multi(&ue_sync, prog_args.file_nof_prb,
if (srslte_ue_sync_init_file_multi(&ue_sync, prog_args.file_nof_prb,
prog_args.input_file_name, prog_args.file_offset_time, prog_args.file_offset_freq, prog_args.rf_nof_rx_ant)) {
fprintf(stderr, "Error initiating ue_sync\n");
exit(-1);
@ -518,6 +535,11 @@ int main(int argc, char **argv) {
/* Configure downlink receiver for the SI-RNTI since will be the only one we'll use */
srslte_ue_dl_set_rnti(&ue_dl, prog_args.rnti);
/* Configure MBSFN area id and non-MBSFN Region */
if (prog_args.mbsfn_area_id > -1) {
srslte_ue_dl_set_mbsfn_area_id(&ue_dl, prog_args.mbsfn_area_id);
srslte_ue_dl_set_non_mbsfn_region(&ue_dl, prog_args.non_mbsfn_region);
}
/* Initialize subframe counter */
sf_cnt = 0;
@ -592,7 +614,6 @@ int main(int argc, char **argv) {
}
}
ret = srslte_ue_sync_zerocopy_multi(&ue_sync, sf_buffer);
if (ret < 0) {
fprintf(stderr, "Error calling srslte_ue_sync_work()\n");
@ -605,9 +626,12 @@ int main(int argc, char **argv) {
/* srslte_ue_sync_get_buffer returns 1 if successfully read 1 aligned subframe */
if (ret == 1) {
uint32_t sfidx = srslte_ue_sync_get_sfidx(&ue_sync);
switch (state) {
case DECODE_MIB:
if (srslte_ue_sync_get_sfidx(&ue_sync) == 0) {
if (sfidx == 0) {
n = srslte_ue_mib_decode(&ue_mib, sf_buffer[0], bch_payload, NULL, &sfn_offset);
if (n < 0) {
fprintf(stderr, "Error decoding UE MIB\n");
@ -626,51 +650,64 @@ int main(int argc, char **argv) {
decode_pdsch = true;
} else {
/* We are looking for SIB1 Blocks, search only in appropiate places */
if ((srslte_ue_sync_get_sfidx(&ue_sync) == 5 && (sfn%2)==0)) {
if ((sfidx == 5 && (sfn%2)==0) || sfidx == 1) {
decode_pdsch = true;
} else {
decode_pdsch = false;
}
}
INFO("Attempting DL decode SFN=%d\n", sfn);
if (decode_pdsch) {
if (cell.nof_ports == 1) {
/* Transmission mode 1 */
n = srslte_ue_dl_decode(&ue_dl, sf_buffer, data, 0, sfn*10+srslte_ue_sync_get_sfidx(&ue_sync), acks);
} else {
if (prog_args.rf_nof_rx_ant == 1) {
/* Transmission mode 2 */
n = srslte_ue_dl_decode(&ue_dl, sf_buffer, data, 1, sfn * 10 + srslte_ue_sync_get_sfidx(&ue_sync),
acks);
if(sfidx != 1 || prog_args.mbsfn_area_id < 0){ // Not an MBSFN subframe
if (cell.nof_ports == 1) {
/* Transmission mode 1 */
n = srslte_ue_dl_decode(&ue_dl, sf_buffer, data, 0, sfn*10+srslte_ue_sync_get_sfidx(&ue_sync), acks);
} else {
/* Transmission mode 3 */
n = srslte_ue_dl_decode(&ue_dl, sf_buffer, data, 2, sfn * 10 + srslte_ue_sync_get_sfidx(&ue_sync),
acks);
if (n < 1) {
/* Transmission mode 4 */
n = srslte_ue_dl_decode(&ue_dl, sf_buffer, data, 3, sfn * 10 + srslte_ue_sync_get_sfidx(&ue_sync),
if (prog_args.rf_nof_rx_ant == 1) {
/* Transmission mode 2 */
n = srslte_ue_dl_decode(&ue_dl, sf_buffer, data, 1, sfn * 10 + srslte_ue_sync_get_sfidx(&ue_sync),
acks);
} else {
/* Transmission mode 3 */
n = srslte_ue_dl_decode(&ue_dl, sf_buffer, data, 2, sfn * 10 + srslte_ue_sync_get_sfidx(&ue_sync),
acks);
if (n < 1) {
/* Transmission mode 4 */
n = srslte_ue_dl_decode(&ue_dl, sf_buffer, data, 3, sfn * 10 + srslte_ue_sync_get_sfidx(&ue_sync),
acks);
}
}
}
}else{ // MBSFN subframe
n = srslte_ue_dl_decode_mbsfn(&ue_dl,
sf_buffer,
data[0],
sfn*10+srslte_ue_sync_get_sfidx(&ue_sync));
if(n>0){
if(output_file_name){
//srslte_filesink_init(&sink, output_file_name, SRSLTE_BYTE_BIN);
// srslte_filesink_write(&sink, data, n);
//srslte_filesink_free(&sink);
}
INFO("mbsfn PDU size is %d\n", n);
}
}
if (n < 0) {
// fprintf(stderr, "Error decoding UE DL\n");fflush(stdout);
} else if (n > 0) {
/* Send data if socket active */
if (prog_args.net_port > 0) {
if(sfidx == 1) {
srslte_netsink_write(&net_sink, data[0], 1+(n-1)/8);
} else {
// FIXME: UDP Data transmission does not work
for (uint32_t tb = 0; tb < SRSLTE_MAX_CODEWORDS; tb++) {
if (ue_dl.pdsch_cfg.grant.tb_en[tb]) {
srslte_netsink_write(&net_sink, data[tb], 1 + (ue_dl.pdsch_cfg.grant.mcs[tb].tbs - 1) / 8);
for (uint32_t tb = 0; tb < SRSLTE_MAX_CODEWORDS; tb++) {
if (ue_dl.pdsch_cfg.grant.tb_en[tb]) {
srslte_netsink_write(&net_sink, data[tb], 1 + (ue_dl.pdsch_cfg.grant.mcs[tb].tbs - 1) / 8);
}
}
}
}
#ifdef PRINT_CHANGE_SCHEDULIGN
if (ue_dl.dl_dci.mcs_idx != old_dl_dci.mcs_idx ||
memcmp(&ue_dl.dl_dci.type0_alloc, &old_dl_dci.type0_alloc, sizeof(srslte_ra_type0_t)) ||
@ -689,6 +726,7 @@ int main(int argc, char **argv) {
nof_trials++;
rsrq = SRSLTE_VEC_EMA(srslte_chest_dl_get_rsrq(&ue_dl.chest), rsrq, 0.1f);
rsrp0 = SRSLTE_VEC_EMA(srslte_chest_dl_get_rsrp_port(&ue_dl.chest, 0), rsrp0, 0.05f);
rsrp1 = SRSLTE_VEC_EMA(srslte_chest_dl_get_rsrp_port(&ue_dl.chest, 1), rsrp1, 0.05f);
@ -696,6 +734,7 @@ int main(int argc, char **argv) {
enodebrate = SRSLTE_VEC_EMA((ue_dl.pdsch_cfg.grant.mcs[0].tbs + ue_dl.pdsch_cfg.grant.mcs[1].tbs)/1000.0f, enodebrate, 0.05f);
uerate = SRSLTE_VEC_EMA(((acks[0]?ue_dl.pdsch_cfg.grant.mcs[0].tbs:0) + (acks[1]?ue_dl.pdsch_cfg.grant.mcs[1].tbs:0))/1000.0f, uerate, 0.01f);
nframes++;
if (isnan(rsrq)) {
rsrq = 0;
@ -704,20 +743,20 @@ int main(int argc, char **argv) {
noise = 0;
}
if (isnan(rsrp0)) {
rsrp1 = 0;
rsrp0 = 0;
}
if (isnan(rsrp0)) {
rsrp1 = 0;
if (isnan(rsrp1)) {
rsrp1 = 0;
}
}
// Plot and Printf
if (srslte_ue_sync_get_sfidx(&ue_sync) == 5 && sfn % 20 == 0) {
if (sfidx == 5) {
float gain = prog_args.rf_gain;
if (gain < 0) {
gain = 10*log10(srslte_agc_get_gain(&ue_sync.agc));
}
/* Print transmission scheme */
if (ue_dl.pdsch_cfg.mimo_type == SRSLTE_MIMO_TYPE_SPATIAL_MULTIPLEX) {
PRINT_LINE(" Tx scheme: %s (codebook_idx=%d)", srslte_mimotype2str(ue_dl.pdsch_cfg.mimo_type),
@ -733,7 +772,10 @@ int main(int argc, char **argv) {
PRINT_LINE(" SNR: %+5.1f dB | %+5.1f dB", 10 * log10(rsrp0 / noise), 10 * log10(rsrp1 / noise));
PRINT_LINE(" Rb: %6.2f / %6.2f Mbps (net/maximum)", uerate, enodebrate);
PRINT_LINE(" PDCCH-Miss: %5.2f%%", 100 * (1 - (float) ue_dl.nof_detected / nof_trials));
PRINT_LINE(" PDSCH-BLER: %5.2f%%", (float) 100 * ue_dl.pkt_errors / ue_dl.pkts_total);
PRINT_LINE(" PDSCH-BLER: %5.2f%%", (float) 100 * ue_dl.pdsch_pkt_errors / ue_dl.pdsch_pkts_total);
if(prog_args.mbsfn_area_id > -1){
PRINT_LINE(" PMCH-BLER: %5.2f%%", (float) 100 * ue_dl.pmch_pkt_errors/ue_dl.pmch_pkts_total);
}
PRINT_LINE(" TB 0: mcs=%d; tbs=%d", ue_dl.pdsch_cfg.grant.mcs[0].idx,
ue_dl.pdsch_cfg.grant.mcs[0].tbs);
PRINT_LINE(" TB 1: mcs=%d; tbs=%d", ue_dl.pdsch_cfg.grant.mcs[1].idx,
@ -775,17 +817,20 @@ int main(int argc, char **argv) {
PRINT_LINE("Press enter maximum printing debug log of 1 subframe.");
PRINT_LINE("");
PRINT_LINE_RESET_CURSOR();
}
break;
}
if (srslte_ue_sync_get_sfidx(&ue_sync) == 9) {
if (sfidx == 9) {
sfn++;
if (sfn == 1024) {
sfn = 0;
PRINT_LINE_ADVANCE_CURSOR();
ue_dl.pdsch_pkt_errors = 0;
ue_dl.pdsch_pkts_total = 0;
/*
ue_dl.pkt_errors = 0;
ue_dl.pkts_total = 0;
ue_dl.pkts_total = 0;
ue_dl.nof_detected = 0;
nof_trials = 0;
*/
@ -794,7 +839,7 @@ int main(int argc, char **argv) {
#ifndef DISABLE_GRAPHICS
if (!prog_args.disable_plots) {
if ((sfn%4) == 0 && decode_pdsch) {
if ((sfn%3) == 0 && decode_pdsch) {
plot_sf_idx = srslte_ue_sync_get_sfidx(&ue_sync);
plot_track = true;
sem_post(&plot_sem);
@ -816,8 +861,7 @@ int main(int argc, char **argv) {
sf_cnt++;
} // Main loop
printf("\033[30B\n");
#ifndef DISABLE_GRAPHICS
if (!prog_args.disable_plots) {
if (!pthread_kill(plot_thread, 0)) {
@ -838,13 +882,14 @@ int main(int argc, char **argv) {
free(sf_buffer[i]);
}
}
#ifndef DISABLE_RF
if (!prog_args.input_file_name) {
srslte_ue_mib_free(&ue_mib);
srslte_rf_close(&rf);
}
#endif
printf("\nBye\n");
exit(0);
}

View File

@ -50,7 +50,7 @@
#define SRSLTE_MAX_BUFFER_SIZE_BYTES 12756
#define SRSLTE_BUFFER_HEADER_OFFSET 1024
#define SRSLTE_BUFFER_POOL_LOG_ENABLED
//#define SRSLTE_BUFFER_POOL_LOG_ENABLED
#ifdef SRSLTE_BUFFER_POOL_LOG_ENABLED
#define pool_allocate (pool->allocate(__FUNCTION__))

View File

@ -71,8 +71,9 @@ public:
/* Timer services with ms resolution.
* timer_id must be lower than MAC_NOF_UPPER_TIMERS
*/
virtual timers::timer* get(uint32_t timer_id) = 0;
virtual uint32_t get_unique_id() = 0;
virtual timers::timer* timer_get(uint32_t timer_id) = 0;
virtual void timer_release_id(uint32_t timer_id) = 0;
virtual uint32_t timer_get_unique_id() = 0;
};
class read_pdu_interface

View File

@ -24,7 +24,7 @@ template<typename metrics_t>
class metrics_listener
{
public:
virtual void set_metrics(metrics_t &m) = 0;
virtual void set_metrics(metrics_t &m, float report_period_secs=1.0) = 0;
};
template<typename metrics_t>
@ -38,6 +38,7 @@ public:
}
void stop() {
thread_cancel();
wait_thread_finish();
}
void add_listener(metrics_listener<metrics_t> *listener) {
@ -46,7 +47,8 @@ public:
private:
void run_period() {
metrics_t metric;
metrics_t metric;
bzero(&metric, sizeof(metrics_t));
m->get_metrics(metric);
for (uint32_t i=0;i<listeners.size();i++) {
listeners[i]->set_metrics(metric);

View File

@ -74,7 +74,7 @@ public:
}
void step() {
if (running) {
counter++;
counter++;
if (is_expired()) {
running = false;
if (callback) {
@ -145,7 +145,7 @@ public:
}
uint32_t get_unique_id() {
if (nof_used_timers >= nof_timers) {
fprintf(stderr, "Error getting uinque timer id: no more timers available\n");
fprintf(stderr, "Error getting unique timer id: no more timers available\n");
return 0;
} else {
while(used_timers[next_timer]) {

View File

@ -244,7 +244,7 @@ public:
class gtpu_interface_rrc
{
public:
virtual void add_bearer(uint16_t rnti, uint32_t lcid, uint32_t teid_out, uint32_t *teid_in) = 0;
virtual void add_bearer(uint16_t rnti, uint32_t lcid, uint32_t addr, uint32_t teid_out, uint32_t *teid_in) = 0;
virtual void rem_bearer(uint16_t rnti, uint32_t lcid) = 0;
virtual void rem_user(uint16_t rnti) = 0;
};

View File

@ -32,7 +32,7 @@
#include "upper/common_enb.h"
#include "upper/s1ap_metrics.h"
#include "upper/rrc_metrics.h"
#include "srslte/upper/gw_metrics.h"
#include "../../../../srsue/hdr/upper/gw_metrics.h"
#include "srslte/upper/rlc_metrics.h"
#include "mac/mac_metrics.h"
#include "phy/phy_metrics.h"

View File

@ -98,6 +98,7 @@ class nas_interface_rrc
{
public:
virtual bool is_attached() = 0;
virtual bool is_attaching() = 0;
virtual void notify_connection_setup() = 0;
virtual void write_pdu(uint32_t lcid, srslte::byte_buffer_t *pdu) = 0;
virtual uint32_t get_ul_count() = 0;
@ -113,6 +114,13 @@ public:
virtual void deattach_request() = 0;
};
// NAS interface for UE
class nas_interface_gw
{
public:
virtual void attach_request() = 0;
};
// RRC interface for MAC
class rrc_interface_mac_common
{
@ -172,6 +180,7 @@ class pdcp_interface_gw
{
public:
virtual void write_sdu(uint32_t lcid, srslte::byte_buffer_t *sdu) = 0;
virtual bool is_drb_enabled(uint32_t lcid) = 0;
};
// PDCP interface for RRC
@ -295,11 +304,11 @@ public:
} mac_grant_t;
typedef struct {
bool decode_enabled;
bool decode_enabled[SRSLTE_MAX_TB];
int rv[SRSLTE_MAX_TB];
uint16_t rnti;
bool generate_ack;
bool default_ack;
bool default_ack[SRSLTE_MAX_TB];
// If non-null, called after tb_decoded_ok to determine if ack needs to be sent
bool (*generate_ack_callback)(void*);
void *generate_ack_callback_arg;
@ -518,19 +527,18 @@ public:
/* Cell search and selection procedures */
virtual void cell_search_start() = 0;
virtual void cell_search_stop() = 0;
virtual void cell_search_next() = 0;
virtual bool cell_select(uint32_t earfcn, srslte_cell_t cell) = 0;
virtual bool sync_stop() = 0;
/* Is the PHY downlink synchronized? */
virtual bool sync_status() = 0;
virtual void sync_reset() = 0;
/* Configure UL using parameters written with set_param() */
virtual void configure_ul_params(bool pregen_disabled = false) = 0;
virtual void reset() = 0;
virtual void resync_sfn() = 0;
};

View File

@ -60,7 +60,10 @@ typedef enum {
typedef struct {
srslte_cell_t cell;
srslte_refsignal_cs_t csr_signal;
srslte_refsignal_t csr_refs;
srslte_refsignal_t **mbsfn_refs;
cf_t *pilot_estimates;
cf_t *pilot_estimates_average;
cf_t *pilot_recv_signal;
@ -75,7 +78,7 @@ typedef struct {
srslte_interp_linsrslte_vec_t srslte_interp_linvec;
srslte_interp_lin_t srslte_interp_lin;
srslte_interp_lin_t srslte_interp_lin_mbsfn;
float rssi[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS];
float rsrp[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS];
float noise_estimate[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS];
@ -96,9 +99,13 @@ SRSLTE_API int srslte_chest_dl_init(srslte_chest_dl_t *q,
SRSLTE_API void srslte_chest_dl_free(srslte_chest_dl_t *q);
SRSLTE_API int srslte_chest_dl_set_mbsfn_area_id(srslte_chest_dl_t *q,
uint16_t mbsfn_area_id);
SRSLTE_API int srslte_chest_dl_set_cell(srslte_chest_dl_t *q,
srslte_cell_t cell);
SRSLTE_API void srslte_chest_dl_set_smooth_filter(srslte_chest_dl_t *q,
float *filter,
uint32_t filter_len);
@ -109,6 +116,8 @@ SRSLTE_API void srslte_chest_dl_set_smooth_filter3_coeff(srslte_chest_dl_t* q,
SRSLTE_API void srslte_chest_dl_set_noise_alg(srslte_chest_dl_t *q,
srslte_chest_dl_noise_alg_t noise_estimation_alg);
SRSLTE_API int srslte_chest_dl_estimate_multi(srslte_chest_dl_t *q,
cf_t *input[SRSLTE_MAX_PORTS],
cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS],
@ -120,6 +129,14 @@ SRSLTE_API int srslte_chest_dl_estimate(srslte_chest_dl_t *q,
cf_t *ce[SRSLTE_MAX_PORTS],
uint32_t sf_idx);
SRSLTE_API int srslte_chest_dl_estimate_multi_mbsfn(srslte_chest_dl_t *q,
cf_t *input[SRSLTE_MAX_PORTS],
cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS],
uint32_t sf_idx,
uint32_t nof_rx_antennas,
uint16_t mbsfn_area_id);
SRSLTE_API int srslte_chest_dl_estimate_port(srslte_chest_dl_t *q,
cf_t *input,
cf_t *ce,

View File

@ -40,25 +40,34 @@
// Number of references in a subframe: there are 2 symbols for port_id=0,1 x 2 slots x 2 refs per prb
#define SRSLTE_REFSIGNAL_NUM_SF(nof_prb, port_id) (((port_id)<2?8:4)*(nof_prb))
#define SRSLTE_REFSIGNAL_NUM_SF_MBSFN(nof_prb, port_id) ((2 + 18)*(nof_prb))
#define SRSLTE_REFSIGNAL_MAX_NUM_SF(nof_prb) SRSLTE_REFSIGNAL_NUM_SF(nof_prb, 0)
#define SRSLTE_REFSIGNAL_MAX_NUM_SF_MBSFN(nof_prb) SRSLTE_REFSIGNAL_NUM_SF_MBSFN(nof_prb,0)
#define SRSLTE_REFSIGNAL_PILOT_IDX(i,l,cell) (2*cell.nof_prb*(l)+(i))
#define SRSLTE_REFSIGNAL_PILOT_IDX_MBSFN(i,l,cell) ((6*cell.nof_prb*(l)+(i)))
/** Cell-Specific Reference Signal */
typedef struct SRSLTE_API {
srslte_cell_t cell;
cf_t *pilots[2][SRSLTE_NSUBFRAMES_X_FRAME]; // Saves the reference signal per subframe for ports 0,1 and ports 2,3
} srslte_refsignal_cs_t;
cf_t *pilots[2][SRSLTE_NSUBFRAMES_X_FRAME]; // Saves the reference signal per subframe for ports 0,1 and ports 2,3
srslte_sf_t type;
uint16_t mbsfn_area_id;
} srslte_refsignal_t;
SRSLTE_API int srslte_refsignal_cs_init(srslte_refsignal_cs_t *q,
SRSLTE_API int srslte_refsignal_cs_init(srslte_refsignal_t *q,
uint32_t max_prb);
SRSLTE_API int srslte_refsignal_cs_set_cell(srslte_refsignal_cs_t * q,
SRSLTE_API int srslte_refsignal_cs_set_cell(srslte_refsignal_t * q,
srslte_cell_t cell);
SRSLTE_API void srslte_refsignal_cs_free(srslte_refsignal_cs_t *q);
SRSLTE_API void srslte_refsignal_free(srslte_refsignal_t *q);
SRSLTE_API int srslte_refsignal_cs_put_sf(srslte_cell_t cell,
uint32_t port_id,
@ -84,4 +93,29 @@ SRSLTE_API uint32_t srslte_refsignal_cs_v(uint32_t port_id,
SRSLTE_API uint32_t srslte_refsignal_cs_nof_symbols(uint32_t port_id);
SRSLTE_API int srslte_refsignal_mbsfn_init(srslte_refsignal_t *q, srslte_cell_t cell,
uint16_t mbsfn_area_id);
SRSLTE_API int srslte_refsignal_mbsfn_get_sf(srslte_cell_t cell,
uint32_t port_id,
cf_t *sf_symbols,
cf_t *pilots);
SRSLTE_API uint32_t srslte_refsignal_mbsfn_nsymbol(uint32_t l);
SRSLTE_API uint32_t srslte_refsignal_mbsfn_fidx(uint32_t l);
SRSLTE_API uint32_t srslte_refsignal_mbsfn_nof_symbols();
SRSLTE_API int srslte_refsignal_mbsfn_put_sf(srslte_cell_t cell,
uint32_t port_id,
cf_t *cs_pilots,
cf_t *mbsfn_pilots,
cf_t *sf_symbols);
SRSLTE_API int srslte_refsignal_mbsfn_gen_seq(srslte_refsignal_t * q,
srslte_cell_t cell,
uint32_t N_mbsfn_id);
#endif

View File

@ -63,7 +63,11 @@
#define SRSLTE_LTE_CRC16 0x11021
#define SRSLTE_LTE_CRC8 0x19B
#define SRSLTE_MAX_MBSFN_AREA_IDS 256
#define SRSLTE_PMCH_RV 0
typedef enum {SRSLTE_CP_NORM, SRSLTE_CP_EXT} srslte_cp_t;
typedef enum {SRSLTE_SF_NORM, SRSLTE_SF_MBSFN} srslte_sf_t;
#define SRSLTE_CRNTI_START 0x000B
@ -130,6 +134,13 @@ typedef enum {SRSLTE_CP_NORM, SRSLTE_CP_EXT} srslte_cp_t;
|| l == SRSLTE_CP_NSYMB(cp) - 3)
#define SRSLTE_SYMBOL_HAS_REF_MBSFN(l, s) ((l == 2 && s == 0) || (l == 0 && s == 1) || (l == 4 && s == 1))
#define SRSLTE_NON_MBSFN_REGION_GUARD_LENGTH(non_mbsfn_region,symbol_sz) ((non_mbsfn_region == 1)?(SRSLTE_CP_LEN_EXT(symbol_sz) - SRSLTE_CP_LEN_NORM(0, symbol_sz)):(2*SRSLTE_CP_LEN_EXT(symbol_sz) - SRSLTE_CP_LEN_NORM(0, symbol_sz)- SRSLTE_CP_LEN_NORM(1, symbol_sz)))
#define SRSLTE_NOF_LTE_BANDS 38
#define SRSLTE_DEFAULT_MAX_FRAMES_PBCH 500
@ -157,6 +168,7 @@ typedef enum {
SRSLTE_RNTI_TEMP, /* Temporary C-RNTI */
SRSLTE_RNTI_SPS, /* Semi-Persistent Scheduling C-RNTI */
SRSLTE_RNTI_PCH, /* Paging RNTI */
SRSLTE_RNTI_MBSFN,
SRSLTE_RNTI_NOF_TYPES
} srslte_rnti_type_t;

View File

@ -94,4 +94,10 @@ SRSLTE_API int srslte_sequence_pucch(srslte_sequence_t *seq,
uint16_t rnti,
uint32_t nslot,
uint32_t cell_id);
SRSLTE_API int srslte_sequence_pmch(srslte_sequence_t *seq,
uint32_t nslot,
uint32_t mbsfn_id,
uint32_t len);
#endif

View File

@ -56,6 +56,12 @@ typedef struct SRSLTE_API{
srslte_cp_t cp;
cf_t *tmp; // for removing zero padding
bool mbsfn_subframe;
uint32_t mbsfn_guard_len;
uint32_t nof_symbols_mbsfn;
uint8_t non_mbsfn_region;
bool freq_shift;
float freq_shift_f;
cf_t *shift_buffer;
@ -64,8 +70,21 @@ typedef struct SRSLTE_API{
SRSLTE_API int srslte_ofdm_init_(srslte_ofdm_t *q,
srslte_cp_t cp,
int symbol_sz,
int max_prb,
srslte_dft_dir_t dir);
int nof_prb,
srslte_dft_dir_t dir);
SRSLTE_API int srslte_ofdm_init_mbsfn_(srslte_ofdm_t *q,
srslte_cp_t cp,
int symbol_sz,
int nof_prb,
srslte_dft_dir_t dir,
srslte_sf_t sf_type);
SRSLTE_API int srslte_ofdm_rx_init_mbsfn(srslte_ofdm_t *q,
srslte_cp_t cp_type,
uint32_t nof_prb);
SRSLTE_API int srslte_ofdm_rx_init(srslte_ofdm_t *q,
srslte_cp_t cp_type,
@ -95,12 +114,22 @@ SRSLTE_API int srslte_ofdm_tx_init(srslte_ofdm_t *q,
srslte_cp_t cp_type,
uint32_t nof_prb);
SRSLTE_API int srslte_ofdm_tx_init_mbsfn(srslte_ofdm_t *q,
srslte_cp_t cp,
uint32_t nof_prb);
SRSLTE_API void srslte_ofdm_tx_free(srslte_ofdm_t *q);
SRSLTE_API void srslte_ofdm_tx_slot(srslte_ofdm_t *q,
cf_t *input,
cf_t *output);
SRSLTE_API void srslte_ofdm_tx_slot_mbsfn(srslte_ofdm_t *q,
cf_t *input,
cf_t *output);
SRSLTE_API void srslte_ofdm_tx_sf(srslte_ofdm_t *q,
cf_t *input,
cf_t *output);
@ -111,4 +140,8 @@ SRSLTE_API int srslte_ofdm_set_freq_shift(srslte_ofdm_t *q,
SRSLTE_API void srslte_ofdm_set_normalize(srslte_ofdm_t *q,
bool normalize_enable);
#endif
SRSLTE_API void srslte_ofdm_set_non_mbsfn_region(srslte_ofdm_t *q,
uint8_t non_mbsfn_region);
#endif

View File

@ -76,7 +76,7 @@ typedef struct SRSLTE_API {
srslte_pdsch_t pdsch;
srslte_phich_t phich;
srslte_refsignal_cs_t csr_signal;
srslte_refsignal_t csr_signal;
srslte_pdsch_cfg_t pdsch_cfg;
srslte_ra_dl_dci_t dl_dci;
@ -88,6 +88,8 @@ typedef struct SRSLTE_API {
float sss_signal5[SRSLTE_SSS_LEN];
float tx_amp;
uint8_t tmp[1024*128];
} srslte_enb_dl_t;
@ -176,5 +178,12 @@ SRSLTE_API int srslte_enb_dl_put_pdcch_ul(srslte_enb_dl_t *q,
uint16_t rnti,
uint32_t sf_idx);
SRSLTE_API void srslte_enb_dl_save_signal(srslte_enb_dl_t *q,
srslte_softbuffer_tx_t *softbuffer,
uint8_t *data,
uint32_t tti,
uint32_t rv_idx,
uint16_t rnti,
uint32_t cfi);
#endif

View File

@ -50,20 +50,14 @@
#define SRSLTE_TCOD_MAX_LEN_CODED (SRSLTE_TCOD_RATE*SRSLTE_TCOD_MAX_LEN_CB+SRSLTE_TCOD_TOTALTAIL)
#include "srslte/phy/fec/turbodecoder_gen.h"
#ifdef LV_HAVE_SSE
#include "srslte/phy/fec/turbodecoder_simd.h"
#else
#define SRSLTE_TDEC_NPAR 1
#endif
typedef struct SRSLTE_API {
#ifdef LV_HAVE_SSE
srslte_tdec_simd_t tdec_simd;
#else
float *input_conv;
srslte_tdec_gen_t tdec_gen;
#endif
float *input_conv;
union {
srslte_tdec_simd_t tdec_simd;
srslte_tdec_gen_t tdec_gen;
};
} srslte_tdec_t;
SRSLTE_API int srslte_tdec_init(srslte_tdec_t * h,
@ -80,7 +74,7 @@ SRSLTE_API int srslte_tdec_reset_cb(srslte_tdec_t * h,
SRSLTE_API int srslte_tdec_get_nof_iterations_cb(srslte_tdec_t * h,
uint32_t cb_idx);
SRSLTE_API int srslte_tdec_get_nof_parallel(srslte_tdec_t * h);
SRSLTE_API uint32_t srslte_tdec_get_nof_parallel(srslte_tdec_t * h);
SRSLTE_API void srslte_tdec_iteration(srslte_tdec_t * h,
int16_t* input,
@ -101,15 +95,15 @@ SRSLTE_API int srslte_tdec_run_all(srslte_tdec_t * h,
uint32_t long_cb);
SRSLTE_API void srslte_tdec_iteration_par(srslte_tdec_t * h,
int16_t* input[SRSLTE_TDEC_NPAR],
int16_t* input[SRSLTE_TDEC_MAX_NPAR],
uint32_t long_cb);
SRSLTE_API void srslte_tdec_decision_par(srslte_tdec_t * h,
uint8_t *output[SRSLTE_TDEC_NPAR],
uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t long_cb);
SRSLTE_API void srslte_tdec_decision_byte_par(srslte_tdec_t * h,
uint8_t *output[SRSLTE_TDEC_NPAR],
uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t long_cb);
SRSLTE_API void srslte_tdec_decision_byte_par_cb(srslte_tdec_t * h,
@ -118,8 +112,8 @@ SRSLTE_API void srslte_tdec_decision_byte_par_cb(srslte_tdec_t * h,
uint32_t long_cb);
SRSLTE_API int srslte_tdec_run_all_par(srslte_tdec_t * h,
int16_t * input[SRSLTE_TDEC_NPAR],
uint8_t *output[SRSLTE_TDEC_NPAR],
int16_t * input[SRSLTE_TDEC_MAX_NPAR],
uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t nof_iterations,
uint32_t long_cb);

View File

@ -43,23 +43,8 @@
#include "srslte/phy/fec/tc_interl.h"
#include "srslte/phy/fec/cbsegm.h"
//#define ENABLE_SIMD_INTER
// The constant SRSLTE_TDEC_NPAR defines the maximum number of parallel CB supported by all SIMD decoders
#ifdef ENABLE_SIMD_INTER
#include "srslte/phy/fec/turbodecoder_simd_inter.h"
#ifdef LV_HAVE_AVX2
#define SRSLTE_TDEC_NPAR_INTRA 2
#else
#define SRSLTE_TDEC_NPAR_INTRA 1
#endif
#else
#ifdef LV_HAVE_AVX2
#define SRSLTE_TDEC_NPAR 2
#else
#define SRSLTE_TDEC_NPAR 1
#endif
#endif
// Define maximum number of CB decoded in parallel (2 for AVX2)
#define SRSLTE_TDEC_MAX_NPAR 2
#define SRSLTE_TCOD_RATE 3
#define SRSLTE_TCOD_TOTALTAIL 12
@ -80,18 +65,18 @@ typedef struct SRSLTE_API {
map_gen_t dec;
int16_t *app1[SRSLTE_TDEC_NPAR];
int16_t *app2[SRSLTE_TDEC_NPAR];
int16_t *ext1[SRSLTE_TDEC_NPAR];
int16_t *ext2[SRSLTE_TDEC_NPAR];
int16_t *syst[SRSLTE_TDEC_NPAR];
int16_t *parity0[SRSLTE_TDEC_NPAR];
int16_t *parity1[SRSLTE_TDEC_NPAR];
int16_t *app1[SRSLTE_TDEC_MAX_NPAR];
int16_t *app2[SRSLTE_TDEC_MAX_NPAR];
int16_t *ext1[SRSLTE_TDEC_MAX_NPAR];
int16_t *ext2[SRSLTE_TDEC_MAX_NPAR];
int16_t *syst[SRSLTE_TDEC_MAX_NPAR];
int16_t *parity0[SRSLTE_TDEC_MAX_NPAR];
int16_t *parity1[SRSLTE_TDEC_MAX_NPAR];
int cb_mask;
int current_cbidx;
srslte_tc_interl_t interleaver[SRSLTE_NOF_TC_CB_SIZES];
int n_iter[SRSLTE_TDEC_NPAR];
int n_iter[SRSLTE_TDEC_MAX_NPAR];
} srslte_tdec_simd_t;
SRSLTE_API int srslte_tdec_simd_init(srslte_tdec_simd_t * h,
@ -103,6 +88,8 @@ SRSLTE_API void srslte_tdec_simd_free(srslte_tdec_simd_t * h);
SRSLTE_API int srslte_tdec_simd_reset(srslte_tdec_simd_t * h,
uint32_t long_cb);
SRSLTE_API
SRSLTE_API int srslte_tdec_simd_get_nof_iterations_cb(srslte_tdec_simd_t * h,
uint32_t cb_idx);
@ -110,15 +97,15 @@ SRSLTE_API int srslte_tdec_simd_reset_cb(srslte_tdec_simd_t * h,
uint32_t cb_idx);
SRSLTE_API void srslte_tdec_simd_iteration(srslte_tdec_simd_t * h,
int16_t * input[SRSLTE_TDEC_NPAR],
int16_t * input[SRSLTE_TDEC_MAX_NPAR],
uint32_t long_cb);
SRSLTE_API void srslte_tdec_simd_decision(srslte_tdec_simd_t * h,
uint8_t *output[SRSLTE_TDEC_NPAR],
uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t long_cb);
SRSLTE_API void srslte_tdec_simd_decision_byte(srslte_tdec_simd_t * h,
uint8_t *output[SRSLTE_TDEC_NPAR],
uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t long_cb);
SRSLTE_API void srslte_tdec_simd_decision_byte_cb(srslte_tdec_simd_t * h,
@ -127,8 +114,8 @@ SRSLTE_API void srslte_tdec_simd_decision_byte_cb(srslte_tdec_simd_t * h,
uint32_t long_cb);
SRSLTE_API int srslte_tdec_simd_run_all(srslte_tdec_simd_t * h,
int16_t * input[SRSLTE_TDEC_NPAR],
uint8_t *output[SRSLTE_TDEC_NPAR],
int16_t * input[SRSLTE_TDEC_MAX_NPAR],
uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t nof_iterations,
uint32_t long_cb);

View File

@ -49,9 +49,9 @@
#include "srslte/phy/fec/cbsegm.h"
#if LV_HAVE_AVX2
#define SRSLTE_TDEC_NPAR 16
#define SRSLTE_TDEC_MAX_NPAR 16
#else
#define SRSLTE_TDEC_NPAR 8
#define SRSLTE_TDEC_MAX_NPAR 8
#endif
@ -71,7 +71,7 @@ typedef struct SRSLTE_API {
int current_cbidx;
uint32_t current_long_cb;
srslte_tc_interl_t interleaver[SRSLTE_NOF_TC_CB_SIZES];
int n_iter[SRSLTE_TDEC_NPAR];
int n_iter[SRSLTE_TDEC_MAX_NPAR];
} srslte_tdec_simd_inter_t;
SRSLTE_API int srslte_tdec_simd_inter_init(srslte_tdec_simd_inter_t * h,
@ -90,17 +90,17 @@ SRSLTE_API int srslte_tdec_simd_inter_reset_cb(srslte_tdec_simd_inter_t * h,
uint32_t cb_idx);
SRSLTE_API void srslte_tdec_simd_inter_iteration(srslte_tdec_simd_inter_t * h,
int16_t * input[SRSLTE_TDEC_NPAR],
int16_t * input[SRSLTE_TDEC_MAX_NPAR],
uint32_t nof_cb,
uint32_t long_cb);
SRSLTE_API void srslte_tdec_simd_inter_decision(srslte_tdec_simd_inter_t * h,
uint8_t *output[SRSLTE_TDEC_NPAR],
uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t nof_cb,
uint32_t long_cb);
SRSLTE_API void srslte_tdec_simd_inter_decision_byte(srslte_tdec_simd_inter_t * h,
uint8_t *output[SRSLTE_TDEC_NPAR],
uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t nof_cb,
uint32_t long_cb);
@ -110,8 +110,8 @@ SRSLTE_API void srslte_tdec_simd_inter_decision_byte_cb(srslte_tdec_simd_inter_t
uint32_t long_cb);
SRSLTE_API int srslte_tdec_simd_inter_run_all(srslte_tdec_simd_inter_t * h,
int16_t *input[SRSLTE_TDEC_NPAR],
uint8_t *output[SRSLTE_TDEC_NPAR],
int16_t *input[SRSLTE_TDEC_MAX_NPAR],
uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t nof_iterations,
uint32_t nof_cb,
uint32_t long_cb);

View File

@ -58,7 +58,8 @@ typedef struct SRSLTE_API {
srslte_cell_t cell;
uint32_t nof_rx_antennas;
uint32_t last_nof_iterations[SRSLTE_MAX_CODEWORDS];
uint32_t max_re;
uint16_t ue_rnti;
@ -149,10 +150,12 @@ SRSLTE_API int srslte_pdsch_cn_compute(srslte_pdsch_t *q,
uint32_t nof_ce,
float *cn);
SRSLTE_API void srslte_pdsch_set_max_noi(srslte_pdsch_t *q, uint32_t max_iter);
SRSLTE_API void srslte_pdsch_set_max_noi(srslte_pdsch_t *q,
uint32_t max_iter);
SRSLTE_API float srslte_pdsch_average_noi(srslte_pdsch_t *q);
SRSLTE_API float srslte_pdsch_last_noi(srslte_pdsch_t *q);
SRSLTE_API uint32_t srslte_pdsch_last_noi(srslte_pdsch_t *q);
SRSLTE_API uint32_t srslte_pdsch_last_noi_cw(srslte_pdsch_t *q,
uint32_t cw_idx);
#endif

View File

@ -101,8 +101,8 @@ SRSLTE_API void srslte_phich_calc(srslte_phich_t *q,
uint32_t *nseq);
SRSLTE_API int srslte_phich_decode(srslte_phich_t *q,
cf_t *slot_symbols,
cf_t *ce[SRSLTE_MAX_PORTS],
cf_t *slot_symbols[SRSLTE_MAX_PORTS],
cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS],
float noise_estimate,
uint32_t ngroup,
uint32_t nseq,
@ -110,16 +110,6 @@ SRSLTE_API int srslte_phich_decode(srslte_phich_t *q,
uint8_t *ack,
float *distance);
SRSLTE_API int srslte_phich_decode_multi(srslte_phich_t *q,
cf_t *slot_symbols[SRSLTE_MAX_PORTS],
cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS],
float noise_estimate,
uint32_t ngroup,
uint32_t nseq,
uint32_t nsubframe,
uint8_t *ack,
float *distance);
SRSLTE_API int srslte_phich_encode(srslte_phich_t *q,
uint8_t ack,
uint32_t ngroup,

View File

@ -0,0 +1,152 @@
/**
*
* \section COPYRIGHT
*
* Copyright 2013-2015 Software Radio Systems Limited
*
* \section LICENSE
*
* This file is part of the srsLTE library.
*
* srsLTE is free software: you can redistribute it and/or modify
* it under the terms of the GNU Affero General Public License as
* published by the Free Software Foundation, either version 3 of
* the License, or (at your option) any later version.
*
* srsLTE 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 Affero General Public License for more details.
*
* A copy of the GNU Affero General Public License can be found in
* the LICENSE file in the top-level directory of this distribution
* and at http://www.gnu.org/licenses/.
*
*/
/******************************************************************************
* File: pmch.h
*
* Description: Physical multicast channel
*
* Reference: 3GPP TS 36.211 version 10.0.0 Release 10 Sec. 6.5
*****************************************************************************/
#ifndef PMCH_
#define PMCH_
#include "srslte/config.h"
#include "srslte/phy/common/phy_common.h"
#include "srslte/phy/mimo/precoding.h"
#include "srslte/phy/mimo/layermap.h"
#include "srslte/phy/modem/mod.h"
#include "srslte/phy/modem/demod_soft.h"
#include "srslte/phy/scrambling/scrambling.h"
#include "srslte/phy/phch/dci.h"
#include "srslte/phy/phch/regs.h"
#include "srslte/phy/phch/sch.h"
#include "srslte/phy/common/sequence.h"
typedef struct {
srslte_sequence_t seq[SRSLTE_NSUBFRAMES_X_FRAME];
} srslte_pmch_seq_t;
typedef struct SRSLTE_API {
srslte_cbsegm_t cb_segm;
srslte_ra_dl_grant_t grant;
srslte_ra_nbits_t nbits[SRSLTE_MAX_CODEWORDS];
uint32_t sf_idx;
} srslte_pmch_cfg_t;
/* PMCH object */
typedef struct SRSLTE_API {
srslte_cell_t cell;
uint32_t nof_rx_antennas;
uint32_t max_re;
/* buffers */
// void buffers are shared for tx and rx
cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS];
cf_t *symbols[SRSLTE_MAX_PORTS];
cf_t *x[SRSLTE_MAX_PORTS];
cf_t *d;
void *e;
/* tx & rx objects */
srslte_modem_table_t mod[4];
// This is to generate the scrambling seq for multiple MBSFN Area IDs
srslte_pmch_seq_t **seqs;
srslte_sch_t dl_sch;
} srslte_pmch_t;
SRSLTE_API int srslte_pmch_init(srslte_pmch_t *q,
uint32_t max_prb);
SRSLTE_API int srslte_pmch_init_multi(srslte_pmch_t *q,
uint32_t max_prb,
uint32_t nof_rx_antennas);
SRSLTE_API void srslte_pmch_free(srslte_pmch_t *q);
SRSLTE_API int srslte_pmch_set_area_id(srslte_pmch_t *q, uint16_t area_id);
SRSLTE_API void srslte_pmch_free_area_id(srslte_pmch_t *q, uint16_t area_id);
SRSLTE_API int srslte_pmch_get(srslte_pmch_t *q, cf_t *sf_symbols, cf_t *symbols, uint32_t lstart);
SRSLTE_API int srslte_pmch_put(srslte_pmch_t *q, cf_t *symbols, cf_t *sf_symbols, uint32_t lstart);
SRSLTE_API int srslte_pmch_cp(srslte_pmch_t *q, cf_t *input, cf_t *output, uint32_t lstart_grant, bool put);
SRSLTE_API float srslte_pmch_coderate(uint32_t tbs,
uint32_t nof_re);
SRSLTE_API int srslte_pmch_cfg(srslte_pdsch_cfg_t *cfg,
srslte_cell_t cell,
srslte_ra_dl_grant_t *grant,
uint32_t cfi,
uint32_t sf_idx);
SRSLTE_API int srslte_pmch_encode(srslte_pmch_t *q,
srslte_pdsch_cfg_t *cfg,
srslte_softbuffer_tx_t *softbuffer,
uint8_t *data,
uint16_t area_id,
cf_t *sf_symbols[SRSLTE_MAX_PORTS]);
SRSLTE_API int srslte_pmch_decode(srslte_pmch_t *q,
srslte_pdsch_cfg_t *cfg,
srslte_softbuffer_rx_t *softbuffer,
cf_t *sf_symbols,
cf_t *ce[SRSLTE_MAX_PORTS],
float noise_estimate,
uint16_t area_id,
uint8_t *data);
SRSLTE_API int srslte_pmch_decode_multi(srslte_pmch_t *q,
srslte_pdsch_cfg_t *cfg,
srslte_softbuffer_rx_t *softbuffer,
cf_t *sf_symbols[SRSLTE_MAX_PORTS],
cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS],
float noise_estimate,
uint16_t area_id,
uint8_t *data);
SRSLTE_API float srslte_pmch_average_noi(srslte_pmch_t *q);
SRSLTE_API uint32_t srslte_pmch_last_noi(srslte_pmch_t *q);
#endif

View File

@ -103,7 +103,11 @@ typedef struct SRSLTE_API {
bool prb_idx[2][SRSLTE_MAX_PRB];
uint32_t nof_prb;
uint32_t Qm[SRSLTE_MAX_CODEWORDS];
uint32_t Qm2[SRSLTE_MAX_CODEWORDS];
srslte_ra_mcs_t mcs[SRSLTE_MAX_CODEWORDS];
srslte_ra_mcs_t mcs2[SRSLTE_MAX_CODEWORDS];
uint32_t nof_tb;
srslte_sf_t sf_type;
bool tb_en[SRSLTE_MAX_CODEWORDS];
uint32_t pinfo;
} srslte_ra_dl_grant_t;
@ -290,4 +294,9 @@ SRSLTE_API void srslte_ra_pusch_fprint(FILE *f,
SRSLTE_API void srslte_ra_ul_grant_fprint(FILE *f,
srslte_ra_ul_grant_t *grant);
SRSLTE_API int srslte_dl_fill_ra_mcs_pmch(srslte_ra_mcs_t *mcs, uint32_t nprb);
SRSLTE_API int srslte_dl_fill_ra_mcs(srslte_ra_mcs_t *mcs, uint32_t nprb);
#endif /* RB_ALLOC_H_ */

View File

@ -56,10 +56,9 @@
/* DL-SCH AND UL-SCH common functions */
typedef struct SRSLTE_API {
uint32_t max_iterations;
uint32_t nof_iterations;
float average_nof_iterations;
uint32_t max_iterations;
uint32_t nof_iterations;
/* buffers */
uint8_t *cb_in;
uint8_t *parity_bits;
@ -77,6 +76,7 @@ typedef struct SRSLTE_API {
srslte_uci_cqi_pusch_t uci_cqi;
} srslte_sch_t;
#include "srslte/phy/phch/pmch.h"
SRSLTE_API int srslte_sch_init(srslte_sch_t *q);
@ -86,8 +86,6 @@ SRSLTE_API void srslte_sch_free(srslte_sch_t *q);
SRSLTE_API void srslte_sch_set_max_noi(srslte_sch_t *q,
uint32_t max_iterations);
SRSLTE_API float srslte_sch_average_noi(srslte_sch_t *q);
SRSLTE_API uint32_t srslte_sch_last_noi(srslte_sch_t *q);
SRSLTE_API int srslte_dlsch_encode(srslte_sch_t *q,

View File

@ -48,6 +48,7 @@
#include "srslte/phy/phch/pcfich.h"
#include "srslte/phy/phch/pdcch.h"
#include "srslte/phy/phch/pdsch.h"
#include "srslte/phy/phch/pmch.h"
#include "srslte/phy/phch/pdsch_cfg.h"
#include "srslte/phy/phch/phich.h"
#include "srslte/phy/phch/ra.h"
@ -76,14 +77,17 @@ typedef struct SRSLTE_API {
srslte_pcfich_t pcfich;
srslte_pdcch_t pdcch;
srslte_pdsch_t pdsch;
srslte_pmch_t pmch;
srslte_phich_t phich;
srslte_regs_t regs;
srslte_ofdm_t fft;
srslte_ofdm_t fft_mbsfn;
srslte_chest_dl_t chest;
srslte_cfo_t sfo_correct;
srslte_pdsch_cfg_t pdsch_cfg;
srslte_pdsch_cfg_t pdsch_cfg;
srslte_pdsch_cfg_t pmch_cfg;
srslte_softbuffer_rx_t *softbuffers[SRSLTE_MAX_CODEWORDS];
srslte_ra_dl_dci_t dl_dci;
srslte_cell_t cell;
@ -103,9 +107,14 @@ typedef struct SRSLTE_API {
srslte_dci_format_t dci_format;
uint64_t pkt_errors;
uint64_t pkts_total;
uint64_t pdsch_pkt_errors;
uint64_t pdsch_pkts_total;
uint64_t pmch_pkt_errors;
uint64_t pmch_pkts_total;
uint64_t nof_detected;
uint16_t current_rnti;
uint16_t current_mbsfn_area_id;
dci_blind_search_t current_ss_ue[3][10];
dci_blind_search_t current_ss_common[3];
srslte_dci_location_t last_location;
@ -127,14 +136,26 @@ SRSLTE_API void srslte_ue_dl_free(srslte_ue_dl_t *q);
SRSLTE_API int srslte_ue_dl_set_cell(srslte_ue_dl_t *q,
srslte_cell_t cell);
SRSLTE_API int srslte_ue_dl_decode_fft_estimate(srslte_ue_dl_t *q,
int srslte_ue_dl_decode_fft_estimate(srslte_ue_dl_t *q,
cf_t *input[SRSLTE_MAX_PORTS],
uint32_t sf_idx,
uint32_t *cfi);
SRSLTE_API int srslte_ue_dl_decode_fft_estimate_mbsfn(srslte_ue_dl_t *q,
cf_t *input[SRSLTE_MAX_PORTS],
uint32_t sf_idx,
uint32_t *cfi);
uint32_t *cfi,
srslte_sf_t sf_type);
SRSLTE_API int srslte_ue_dl_decode_estimate(srslte_ue_dl_t *q,
int srslte_ue_dl_decode_estimate(srslte_ue_dl_t *q,
uint32_t sf_idx,
uint32_t *cfi);
SRSLTE_API int srslte_ue_dl_decode_estimate_mbsfn(srslte_ue_dl_t *q,
uint32_t sf_idx,
uint32_t *cfi);
uint32_t *cfi,
srslte_sf_t sf_type);
SRSLTE_API int srslte_ue_dl_cfg_grant(srslte_ue_dl_t *q,
srslte_ra_dl_grant_t *grant,
@ -184,6 +205,18 @@ SRSLTE_API int srslte_ue_dl_decode_rnti(srslte_ue_dl_t *q,
uint16_t rnti,
bool acks[SRSLTE_MAX_CODEWORDS]);
/* Used by example applications - full PMCH decode for a given MBSFN area ID
* srslte_ue_dl_decode_fft_estimate_multi,
* srslte_chest_dl_get_noise_estimate,
* srslte_ue_dl_cfg_grant,
* srslte_pmch_decode_multi
*/
SRSLTE_API int srslte_ue_dl_decode_mbsfn(srslte_ue_dl_t * q,
cf_t *input[SRSLTE_MAX_PORTS],
uint8_t *data,
uint32_t tti);
SRSLTE_API int srslte_ue_dl_ri_pmi_select(srslte_ue_dl_t *q,
uint8_t *ri,
uint8_t *pmi,
@ -203,6 +236,15 @@ SRSLTE_API void srslte_ue_dl_reset(srslte_ue_dl_t *q);
SRSLTE_API void srslte_ue_dl_set_rnti(srslte_ue_dl_t *q,
uint16_t rnti);
/* Generate signals if required, store in q->current_mbsfn_area_id */
SRSLTE_API int srslte_ue_dl_set_mbsfn_area_id(srslte_ue_dl_t *q,
uint16_t mbsfn_area_id);
SRSLTE_API void srslte_ue_dl_set_non_mbsfn_region(srslte_ue_dl_t *q,
uint8_t non_mbsfn_region_length);
SRSLTE_API void srslte_ue_dl_save_signal(srslte_ue_dl_t *q,
srslte_softbuffer_rx_t *softbuffer,
uint32_t tti,

View File

@ -57,8 +57,7 @@ namespace srslte {
bzero(&end_of_burst_time, sizeof(srslte_timestamp_t));
bzero(zeros, burst_preamble_max_samples*sizeof(cf_t));
sf_len = 0;
burst_preamble_sec = 0;
burst_preamble_sec = 0;
is_start_of_burst = false;
burst_preamble_samples = 0;
burst_preamble_time_rounded = 0;
@ -72,13 +71,12 @@ namespace srslte {
rx_freq = 0;
trace_enabled = false;
tti = 0;
agc_enabled = false;
offset = 0;
agc_enabled = false;
};
bool init(char *args = NULL, char *devname = NULL);
void stop();
void stop();
void reset();
bool start_agc(bool tx_gain_same_rx);
void set_burst_preamble(double preamble_us);
@ -123,9 +121,8 @@ namespace srslte {
void stop_rx();
void set_tti(uint32_t tti);
void tx_offset(int offset);
void set_tti_len(uint32_t sf_len);
uint32_t get_tti_len();
bool is_first_of_burst();
void register_error_handler(srslte_rf_error_handler_t h);
@ -168,8 +165,10 @@ namespace srslte {
bool trace_enabled;
uint32_t tti;
bool agc_enabled;
int offset;
uint32_t sf_len;
char saved_args[128];
char saved_devname[128];
};
}

View File

@ -50,6 +50,9 @@ public:
uint8_t direction_);
void stop();
// GW interface
bool is_drb_enabled(uint32_t lcid);
// RRC interface
void reset();
void write_sdu(uint32_t lcid, byte_buffer_t *sdu);

View File

@ -78,6 +78,7 @@ public:
mac_interface_timers *mac_timers);
void configure(srslte_rlc_config_t cnfg);
void reset();
void stop();
void empty_queue();
rlc_mode_t get_mode();

View File

@ -158,6 +158,7 @@ public:
srslte::mac_interface_timers *mac_timers_) = 0;
virtual void configure(srslte_rlc_config_t cnfg) = 0;
virtual void reset() = 0;
virtual void stop() = 0;
virtual void empty_queue() = 0;
virtual rlc_mode_t get_mode() = 0;

View File

@ -56,6 +56,7 @@ public:
void configure(srslte_rlc_config_t cnfg);
void reset();
void stop();
void empty_queue();
bool active();

View File

@ -48,6 +48,7 @@ public:
mac_interface_timers *mac_timers);
void configure(srslte_rlc_config_t cnfg);
void reset();
void stop();
void empty_queue();
rlc_mode_t get_mode();

View File

@ -58,6 +58,7 @@ public:
mac_interface_timers *mac_timers_);
void configure(srslte_rlc_config_t cnfg);
void reset();
void stop();
void empty_queue();
rlc_mode_t get_mode();
@ -124,7 +125,8 @@ private:
* Timers
* Ref: 3GPP TS 36.322 v10.0.0 Section 7
***************************************************************************/
uint32_t reordering_timeout_id;
srslte::timers::timer *reordering_timer;
uint32_t reordering_timer_id;
bool pdu_lost;

View File

@ -81,29 +81,46 @@ int srslte_chest_dl_init(srslte_chest_dl_t *q, uint32_t max_prb)
{
bzero(q, sizeof(srslte_chest_dl_t));
ret = srslte_refsignal_cs_init(&q->csr_signal, max_prb);
ret = srslte_refsignal_cs_init(&q->csr_refs, max_prb);
if (ret != SRSLTE_SUCCESS) {
fprintf(stderr, "Error initializing CSR signal (%d)\n",ret);
goto clean_exit;
}
q->tmp_noise = srslte_vec_malloc(sizeof(cf_t) * SRSLTE_REFSIGNAL_MAX_NUM_SF(max_prb));
q->mbsfn_refs = calloc(SRSLTE_MAX_MBSFN_AREA_IDS, sizeof(srslte_refsignal_t*));
if (!q->mbsfn_refs) {
fprintf(stderr, "Calloc error initializing mbsfn_refs (%d)\n", ret);
goto clean_exit;
}
int pilot_vec_size;
if(SRSLTE_REFSIGNAL_MAX_NUM_SF_MBSFN(max_prb)>SRSLTE_REFSIGNAL_MAX_NUM_SF(max_prb)) {
pilot_vec_size = SRSLTE_REFSIGNAL_MAX_NUM_SF_MBSFN(max_prb);
}else{
pilot_vec_size = SRSLTE_REFSIGNAL_MAX_NUM_SF(max_prb);
}
q->tmp_noise = srslte_vec_malloc(sizeof(cf_t) * pilot_vec_size);
if (!q->tmp_noise) {
perror("malloc");
goto clean_exit;
}
q->pilot_estimates = srslte_vec_malloc(sizeof(cf_t) * pilot_vec_size);
q->pilot_estimates = srslte_vec_malloc(sizeof(cf_t) * SRSLTE_REFSIGNAL_MAX_NUM_SF(max_prb));
if (!q->pilot_estimates) {
perror("malloc");
goto clean_exit;
}
q->pilot_estimates_average = srslte_vec_malloc(sizeof(cf_t) * SRSLTE_REFSIGNAL_MAX_NUM_SF(max_prb));
q->pilot_estimates_average = srslte_vec_malloc(sizeof(cf_t) * pilot_vec_size);
if (!q->pilot_estimates_average) {
perror("malloc");
goto clean_exit;
}
q->pilot_recv_signal = srslte_vec_malloc(sizeof(cf_t) * SRSLTE_REFSIGNAL_MAX_NUM_SF(max_prb));
q->pilot_recv_signal = srslte_vec_malloc(sizeof(cf_t) * pilot_vec_size);
if (!q->pilot_recv_signal) {
perror("malloc");
goto clean_exit;
@ -118,8 +135,13 @@ int srslte_chest_dl_init(srslte_chest_dl_t *q, uint32_t max_prb)
fprintf(stderr, "Error initializing interpolator\n");
goto clean_exit;
}
if (srslte_interp_linear_init(&q->srslte_interp_lin_mbsfn, 6*max_prb, SRSLTE_NRE/6)) {
fprintf(stderr, "Error initializing interpolator\n");
goto clean_exit;
}
q->noise_alg = SRSLTE_NOISE_ALG_REFS;
q->noise_alg = SRSLTE_NOISE_ALG_REFS;
q->smooth_filter_len = 3;
srslte_chest_dl_set_smooth_filter3_coeff(q, 0.1);
@ -137,14 +159,25 @@ clean_exit:
void srslte_chest_dl_free(srslte_chest_dl_t *q)
{
srslte_refsignal_cs_free(&q->csr_signal);
int i;
if(&q->csr_refs)
srslte_refsignal_free(&q->csr_refs);
if (q->mbsfn_refs) {
for (i=0; i<SRSLTE_MAX_MBSFN_AREA_IDS; i++) {
if (q->mbsfn_refs[i]) {
srslte_refsignal_free(q->mbsfn_refs[i]);
}
}
free(q->mbsfn_refs);
}
if (q->tmp_noise) {
free(q->tmp_noise);
}
srslte_interp_linear_vector_free(&q->srslte_interp_linvec);
srslte_interp_linear_free(&q->srslte_interp_lin);
srslte_interp_linear_free(&q->srslte_interp_lin_mbsfn);
if (q->pilot_estimates) {
free(q->pilot_estimates);
}
@ -157,6 +190,19 @@ void srslte_chest_dl_free(srslte_chest_dl_t *q)
bzero(q, sizeof(srslte_chest_dl_t));
}
int srslte_chest_dl_set_mbsfn_area_id(srslte_chest_dl_t *q, uint16_t mbsfn_area_id){
if(!q->mbsfn_refs[mbsfn_area_id]){
q->mbsfn_refs[mbsfn_area_id] = calloc(1, sizeof(srslte_refsignal_t));
}
if(q->mbsfn_refs[mbsfn_area_id]) {
if(srslte_refsignal_mbsfn_init(q->mbsfn_refs[mbsfn_area_id], q->cell, mbsfn_area_id)) {
return SRSLTE_ERROR;
}
}
return SRSLTE_SUCCESS;
}
int srslte_chest_dl_set_cell(srslte_chest_dl_t *q, srslte_cell_t cell)
{
int ret = SRSLTE_ERROR_INVALID_INPUTS;
@ -165,7 +211,7 @@ int srslte_chest_dl_set_cell(srslte_chest_dl_t *q, srslte_cell_t cell)
{
if (q->cell.id != cell.id || q->cell.nof_prb == 0) {
memcpy(&q->cell, &cell, sizeof(srslte_cell_t));
ret = srslte_refsignal_cs_set_cell(&q->csr_signal, cell);
ret = srslte_refsignal_cs_set_cell(&q->csr_refs, cell);
if (ret != SRSLTE_SUCCESS) {
fprintf(stderr, "Error initializing CSR signal (%d)\n",ret);
return SRSLTE_ERROR;
@ -187,7 +233,6 @@ int srslte_chest_dl_set_cell(srslte_chest_dl_t *q, srslte_cell_t cell)
}
ret = SRSLTE_SUCCESS;
}
return ret;
}
@ -253,46 +298,70 @@ static float estimate_noise_empty_sc(srslte_chest_dl_t *q, cf_t *input) {
#define cesymb(i) ce[SRSLTE_RE_IDX(q->cell.nof_prb,i,0)]
static void interpolate_pilots(srslte_chest_dl_t *q, cf_t *pilot_estimates, cf_t *ce, uint32_t port_id)
static void interpolate_pilots(srslte_chest_dl_t *q, cf_t *pilot_estimates, cf_t *ce, uint32_t port_id, srslte_sf_t ch_mode)
{
/* interpolate the symbols with references in the freq domain */
uint32_t l;
uint32_t nsymbols = srslte_refsignal_cs_nof_symbols(port_id);
uint32_t nsymbols = (ch_mode == SRSLTE_SF_MBSFN ) ? srslte_refsignal_mbsfn_nof_symbols() + 1 : srslte_refsignal_cs_nof_symbols(port_id);
uint32_t fidx_offset = 0;
/* Interpolate in the frequency domain */
for (l=0;l<nsymbols;l++) {
uint32_t fidx_offset = srslte_refsignal_cs_fidx(q->cell, l, port_id, 0);
srslte_interp_linear_offset(&q->srslte_interp_lin, &pilot_estimates[2*q->cell.nof_prb*l],
&ce[srslte_refsignal_cs_nsymbol(l,q->cell.cp, port_id) * q->cell.nof_prb * SRSLTE_NRE],
fidx_offset, SRSLTE_NRE/2-fidx_offset);
// we add one to nsymbols to allow for inclusion of the non-mbms references in the channel estimation
for (l=0;l<(nsymbols);l++) {
if (ch_mode == SRSLTE_SF_MBSFN) {
if (l == 0) {
fidx_offset = srslte_refsignal_cs_fidx(q->cell, l, port_id, 0);
srslte_interp_linear_offset(&q->srslte_interp_lin, &pilot_estimates[2*q->cell.nof_prb*l],
&ce[srslte_refsignal_cs_nsymbol(l,q->cell.cp, port_id) * q->cell.nof_prb * SRSLTE_NRE],
fidx_offset, SRSLTE_NRE/2-fidx_offset);
} else {
fidx_offset = srslte_refsignal_mbsfn_fidx(l - 1);
srslte_interp_linear_offset(&q->srslte_interp_lin_mbsfn, &pilot_estimates[(2*q->cell.nof_prb) + 6*q->cell.nof_prb*(l - 1)],
&ce[srslte_refsignal_mbsfn_nsymbol(l - 1) * q->cell.nof_prb * SRSLTE_NRE],
fidx_offset, SRSLTE_NRE/6-fidx_offset);
}
} else {
fidx_offset = srslte_refsignal_cs_fidx(q->cell, l, port_id, 0);
srslte_interp_linear_offset(&q->srslte_interp_lin, &pilot_estimates[2*q->cell.nof_prb*l],
&ce[srslte_refsignal_cs_nsymbol(l,q->cell.cp, port_id) * q->cell.nof_prb * SRSLTE_NRE],
fidx_offset, SRSLTE_NRE/2-fidx_offset);
}
}
/* Now interpolate in the time domain between symbols */
if (SRSLTE_CP_ISNORM(q->cell.cp)) {
if (nsymbols == 4) {
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(0), &cesymb(4), &cesymb(1), 4, 3);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(4), &cesymb(7), &cesymb(5), 3, 2);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(7), &cesymb(11), &cesymb(8), 4, 3);
srslte_interp_linear_vector2(&q->srslte_interp_linvec, &cesymb(7), &cesymb(11), &cesymb(11), &cesymb(12), 4, 2);
if (ch_mode == SRSLTE_SF_MBSFN) {
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(0), &cesymb(2), &cesymb(1), 2, 1);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(2), &cesymb(6), &cesymb(3), 4, 3);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(6), &cesymb(10), &cesymb(7), 4, 3);
srslte_interp_linear_vector2(&q->srslte_interp_linvec, &cesymb(6), &cesymb(10), &cesymb(10), &cesymb(11), 4, 1);
} else {
if (SRSLTE_CP_ISNORM(q->cell.cp)) {
if (nsymbols == 4) {
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(0), &cesymb(4), &cesymb(1), 4, 3);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(4), &cesymb(7), &cesymb(5), 3, 2);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(7), &cesymb(11), &cesymb(8), 4, 3);
srslte_interp_linear_vector2(&q->srslte_interp_linvec, &cesymb(7), &cesymb(11), &cesymb(11), &cesymb(12), 4, 2);
} else {
srslte_interp_linear_vector2(&q->srslte_interp_linvec, &cesymb(8), &cesymb(1), &cesymb(1), &cesymb(0), 7, 1);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(1), &cesymb(8), &cesymb(2), 7, 6);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(1), &cesymb(8), &cesymb(9), 7, 5);
}
} else {
srslte_interp_linear_vector2(&q->srslte_interp_linvec, &cesymb(8), &cesymb(1), &cesymb(1), &cesymb(0), 7, 1);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(1), &cesymb(8), &cesymb(2), 7, 6);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(1), &cesymb(8), &cesymb(9), 7, 5);
}
} else {
if (nsymbols == 4) {
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(0), &cesymb(3), &cesymb(1), 3, 2);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(3), &cesymb(6), &cesymb(4), 3, 2);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(6), &cesymb(9), &cesymb(7), 3, 2);
srslte_interp_linear_vector2(&q->srslte_interp_linvec, &cesymb(6), &cesymb(9), &cesymb(9), &cesymb(10), 3, 2);
} else {
srslte_interp_linear_vector2(&q->srslte_interp_linvec, &cesymb(7), &cesymb(1), &cesymb(1), &cesymb(0), 6, 1);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(1), &cesymb(7), &cesymb(2), 6, 5);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(1), &cesymb(7), &cesymb(8), 6, 4);
}
if (nsymbols == 4) {
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(0), &cesymb(3), &cesymb(1), 3, 2);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(3), &cesymb(6), &cesymb(4), 3, 2);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(6), &cesymb(9), &cesymb(7), 3, 2);
srslte_interp_linear_vector2(&q->srslte_interp_linvec, &cesymb(6), &cesymb(9), &cesymb(9), &cesymb(10), 3, 2);
} else {
srslte_interp_linear_vector2(&q->srslte_interp_linvec, &cesymb(7), &cesymb(1), &cesymb(1), &cesymb(0), 6, 1);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(1), &cesymb(7), &cesymb(2), 6, 5);
srslte_interp_linear_vector(&q->srslte_interp_linvec, &cesymb(1), &cesymb(7), &cesymb(8), 6, 4);
}
}
}
}
void srslte_chest_dl_set_smooth_filter(srslte_chest_dl_t *q, float *filter, uint32_t filter_len) {
if (filter_len < SRSLTE_CHEST_MAX_SMOOTH_FIL_LEN) {
if (filter) {
@ -319,9 +388,9 @@ void srslte_chest_dl_set_smooth_filter3_coeff(srslte_chest_dl_t* q, float w)
q->smooth_filter[1] = 1-2*w;
}
static void average_pilots(srslte_chest_dl_t *q, cf_t *input, cf_t *output, uint32_t port_id) {
uint32_t nsymbols = srslte_refsignal_cs_nof_symbols(port_id);
uint32_t nref = 2*q->cell.nof_prb;
static void average_pilots(srslte_chest_dl_t *q, cf_t *input, cf_t *output, uint32_t port_id, srslte_sf_t ch_mode) {
uint32_t nsymbols = (ch_mode == SRSLTE_SF_MBSFN)?srslte_refsignal_mbsfn_nof_symbols(port_id):srslte_refsignal_cs_nof_symbols(port_id);
uint32_t nref = (ch_mode == SRSLTE_SF_MBSFN)?6*q->cell.nof_prb:2*q->cell.nof_prb;
// Average in the frequency domain
for (int l=0;l<nsymbols;l++) {
@ -341,25 +410,16 @@ float srslte_chest_dl_rssi(srslte_chest_dl_t *q, cf_t *input, uint32_t port_id)
return rssi/nsymbols;
}
int srslte_chest_dl_estimate_port(srslte_chest_dl_t *q, cf_t *input, cf_t *ce, uint32_t sf_idx, uint32_t port_id, uint32_t rxant_id)
{
/* Get references from the input signal */
srslte_refsignal_cs_get_sf(q->cell, port_id, input, q->pilot_recv_signal);
/* Use the known CSR signal to compute Least-squares estimates */
srslte_vec_prod_conj_ccc(q->pilot_recv_signal, q->csr_signal.pilots[port_id/2][sf_idx],
q->pilot_estimates, SRSLTE_REFSIGNAL_NUM_SF(q->cell.nof_prb, port_id));
if (ce != NULL) {
void chest_interpolate_noise_est(srslte_chest_dl_t *q, cf_t *input, cf_t *ce, uint32_t sf_idx, uint32_t port_id, uint32_t rxant_id, srslte_sf_t ch_mode){
if (ce != NULL) {
/* Smooth estimates (if applicable) and interpolate */
if (q->smooth_filter_len == 0 || (q->smooth_filter_len == 3 && q->smooth_filter[0] == 0)) {
interpolate_pilots(q, q->pilot_estimates, ce, port_id);
interpolate_pilots(q, q->pilot_estimates, ce, port_id, ch_mode);
} else {
average_pilots(q, q->pilot_estimates, q->pilot_estimates_average, port_id);
interpolate_pilots(q, q->pilot_estimates_average, ce, port_id);
average_pilots(q, q->pilot_estimates, q->pilot_estimates_average, port_id, ch_mode);
interpolate_pilots(q, q->pilot_estimates_average, ce, port_id, ch_mode);
}
/* Estimate noise power */
if (q->noise_alg == SRSLTE_NOISE_ALG_REFS && q->smooth_filter_len > 0) {
q->noise_estimate[rxant_id][port_id] = estimate_noise_pilots(q, port_id);
@ -371,8 +431,7 @@ int srslte_chest_dl_estimate_port(srslte_chest_dl_t *q, cf_t *input, cf_t *ce, u
if (sf_idx == 0 || sf_idx == 5) {
q->noise_estimate[rxant_id][port_id] = estimate_noise_empty_sc(q, input);
}
}
}
}
/* Compute RSRP for the channel estimates in this port */
@ -381,10 +440,42 @@ int srslte_chest_dl_estimate_port(srslte_chest_dl_t *q, cf_t *input, cf_t *ce, u
/* compute rssi only for port 0 */
q->rssi[rxant_id][port_id] = srslte_chest_dl_rssi(q, input, port_id);
}
}
int srslte_chest_dl_estimate_port(srslte_chest_dl_t *q, cf_t *input, cf_t *ce, uint32_t sf_idx, uint32_t port_id, uint32_t rxant_id)
{
/* Get references from the input signal */
srslte_refsignal_cs_get_sf(q->cell, port_id, input, q->pilot_recv_signal);
/* Use the known CSR signal to compute Least-squares estimates */
srslte_vec_prod_conj_ccc(q->pilot_recv_signal, q->csr_refs.pilots[port_id/2][sf_idx],
q->pilot_estimates, SRSLTE_REFSIGNAL_NUM_SF(q->cell.nof_prb, port_id));
chest_interpolate_noise_est(q, input, ce, sf_idx, port_id, rxant_id, SRSLTE_SF_NORM);
return 0;
}
int srslte_chest_dl_estimate_port_mbsfn(srslte_chest_dl_t *q, cf_t *input, cf_t *ce, uint32_t sf_idx, uint32_t port_id, uint32_t rxant_id, uint16_t mbsfn_area_id)
{
/* Use the known CSR signal to compute Least-squares estimates */
srslte_refsignal_mbsfn_get_sf(q->cell, port_id, input, q->pilot_recv_signal);
// estimate for non-mbsfn section of subframe
srslte_vec_prod_conj_ccc(q->pilot_recv_signal, q->csr_refs.pilots[port_id/2][sf_idx],
q->pilot_estimates, (2*q->cell.nof_prb));
srslte_vec_prod_conj_ccc(q->pilot_recv_signal+(2*q->cell.nof_prb), q->mbsfn_refs[mbsfn_area_id]->pilots[port_id/2][sf_idx],
q->pilot_estimates+(2*q->cell.nof_prb), SRSLTE_REFSIGNAL_NUM_SF_MBSFN(q->cell.nof_prb, port_id)-(2*q->cell.nof_prb));
chest_interpolate_noise_est(q, input, ce, sf_idx, port_id, rxant_id, SRSLTE_SF_MBSFN);
return 0;
}
int srslte_chest_dl_estimate_multi(srslte_chest_dl_t *q, cf_t *input[SRSLTE_MAX_PORTS], cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS], uint32_t sf_idx, uint32_t nof_rx_antennas)
{
for (uint32_t rxant_id=0;rxant_id<nof_rx_antennas;rxant_id++) {
@ -411,6 +502,21 @@ int srslte_chest_dl_estimate(srslte_chest_dl_t *q, cf_t *input, cf_t *ce[SRSLTE_
return SRSLTE_SUCCESS;
}
int srslte_chest_dl_estimate_multi_mbsfn(srslte_chest_dl_t *q, cf_t *input[SRSLTE_MAX_PORTS], cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS], uint32_t sf_idx, uint32_t nof_rx_antennas, uint16_t mbsfn_area_id)
{
for (uint32_t rxant_id=0;rxant_id<nof_rx_antennas;rxant_id++) {
for (uint32_t port_id=0;port_id<q->cell.nof_ports;port_id++) {
if (srslte_chest_dl_estimate_port_mbsfn(q, input[rxant_id], ce[port_id][rxant_id], sf_idx, port_id, rxant_id, mbsfn_area_id)) {
return SRSLTE_ERROR;
}
}
}
q->last_nof_antennas = nof_rx_antennas;
return SRSLTE_SUCCESS;
}
float srslte_chest_dl_get_noise_estimate(srslte_chest_dl_t *q) {
float n = 0;
for (int i=0;i<q->last_nof_antennas;i++) {

View File

@ -75,17 +75,44 @@ uint32_t srslte_refsignal_cs_v(uint32_t port_id, uint32_t ref_symbol_idx)
uint32_t srslte_refsignal_cs_nof_symbols(uint32_t port_id)
{
uint32_t ret;
if (port_id < 2) {
return 4;
ret = 4;
} else {
return 2;
ret = 2;
}
return ret;
}
uint32_t srslte_refsignal_mbsfn_nof_symbols()
{
if(false){
return 3;
}else{
return 3;
}
}
inline uint32_t srslte_refsignal_cs_fidx(srslte_cell_t cell, uint32_t l, uint32_t port_id, uint32_t m) {
return 6*m + ((srslte_refsignal_cs_v(port_id, l) + (cell.id % 6)) % 6);
}
inline uint32_t srslte_refsignal_mbsfn_fidx(uint32_t l)
{
uint32_t ret = 0;
if(l == 0){
ret = 0;
}else if (l == 1){
ret = 1;
}else if(l == 2){
ret = 0;
}
return ret;
}
inline uint32_t srslte_refsignal_cs_nsymbol(uint32_t l, srslte_cp_t cp, uint32_t port_id) {
if (port_id < 2) {
if (l % 2) {
@ -97,11 +124,104 @@ inline uint32_t srslte_refsignal_cs_nsymbol(uint32_t l, srslte_cp_t cp, uint32_t
return 1+l*SRSLTE_CP_NSYMB(cp);
}
}
inline uint32_t srslte_refsignal_mbsfn_nsymbol(uint32_t l)
{
uint32_t ret = 0;
if(l == 0){
ret = 2;
} else if (l == 1) {
ret = 6;
} else if (l == 2){
ret = 10;
}
return ret;
}
int srslte_refsignal_mbsfn_gen_seq(srslte_refsignal_t * q, srslte_cell_t cell, uint32_t N_mbsfn_id)
{
uint32_t c_init;
uint32_t i, ns, l, p;
uint32_t mp;
int ret = SRSLTE_ERROR;
srslte_sequence_t seq_mbsfn;
bzero(&seq_mbsfn, sizeof(srslte_sequence_t));
if (srslte_sequence_init(&seq_mbsfn, 20* SRSLTE_MAX_PRB)) {
goto free_and_exit;
}
for(ns=0; ns<SRSLTE_NSUBFRAMES_X_FRAME;ns++){
for(p=0;p<2;p++) {
uint32_t nsymbols = 3; // replace with function
for(l=0;l<nsymbols;l++) {
uint32_t lp = (srslte_refsignal_mbsfn_nsymbol(l))%6;
uint32_t slot =(l)?(ns*2+1):(ns*2);
c_init = 512*(7*(slot+1)+lp+1)*(2*N_mbsfn_id + 1) + N_mbsfn_id;
srslte_sequence_set_LTE_pr(&seq_mbsfn,SRSLTE_MAX_PRB*20 ,c_init);
for(i=0;i< 6*q->cell.nof_prb;i++) {
mp = i + 3*(SRSLTE_MAX_PRB - cell.nof_prb);
q->pilots[p][ns][ SRSLTE_REFSIGNAL_PILOT_IDX_MBSFN(i, l ,q->cell)] = (1 - 2 * (float) seq_mbsfn.c[2 * mp]) / sqrt(2) +_Complex_I * (1 - 2 * (float) seq_mbsfn.c[2 * mp + 1]) / sqrt(2);
}
}
}
}
srslte_sequence_free(&seq_mbsfn);
ret = SRSLTE_SUCCESS;
free_and_exit:
if (ret == SRSLTE_ERROR) {
srslte_sequence_free(&seq_mbsfn);
srslte_refsignal_free(q);
}
return ret;
}
int srslte_refsignal_mbsfn_init(srslte_refsignal_t * q, srslte_cell_t cell, uint16_t mbsfn_area_id)
{
int ret = SRSLTE_ERROR_INVALID_INPUTS;
uint32_t i, p;
if (q != NULL &&
srslte_cell_isvalid(&cell))
{
ret = SRSLTE_ERROR;
bzero(q, sizeof(srslte_refsignal_t));
q->cell = cell;
q->type = SRSLTE_SF_MBSFN;
q->mbsfn_area_id = mbsfn_area_id;
for (p=0;p<2;p++) {
for (i=0;i<SRSLTE_NSUBFRAMES_X_FRAME;i++) {
q->pilots[p][i] = srslte_vec_malloc(sizeof(cf_t) * q->cell.nof_prb * 18);
if (!q->pilots[p][i]) {
perror("malloc");
goto free_and_exit;
}
}
}
if(srslte_refsignal_mbsfn_gen_seq(q, q->cell, q->mbsfn_area_id)) {
goto free_and_exit;
}
ret = SRSLTE_SUCCESS;
}
free_and_exit:
if (ret == SRSLTE_ERROR) {
srslte_refsignal_free(q);
}
return ret;
}
/** Allocates memory for the 20 slots in a subframe
*/
int srslte_refsignal_cs_init(srslte_refsignal_cs_t * q, uint32_t max_prb)
int srslte_refsignal_cs_init(srslte_refsignal_t * q, uint32_t max_prb)
{
int ret = SRSLTE_ERROR_INVALID_INPUTS;
@ -109,7 +229,6 @@ int srslte_refsignal_cs_init(srslte_refsignal_cs_t * q, uint32_t max_prb)
if (q != NULL)
{
ret = SRSLTE_ERROR;
for (int p=0;p<2;p++) {
for (int i=0;i<SRSLTE_NSUBFRAMES_X_FRAME;i++) {
q->pilots[p][i] = srslte_vec_malloc(sizeof(cf_t) * SRSLTE_REFSIGNAL_NUM_SF(max_prb, 2*p));
@ -123,7 +242,7 @@ int srslte_refsignal_cs_init(srslte_refsignal_cs_t * q, uint32_t max_prb)
}
free_and_exit:
if (ret == SRSLTE_ERROR) {
srslte_refsignal_cs_free(q);
srslte_refsignal_free(q);
}
return ret;
}
@ -131,7 +250,7 @@ free_and_exit:
/** Allocates and precomputes the Cell-Specific Reference (CSR) signal for
* the 20 slots in a subframe
*/
int srslte_refsignal_cs_set_cell(srslte_refsignal_cs_t * q, srslte_cell_t cell)
int srslte_refsignal_cs_set_cell(srslte_refsignal_t * q, srslte_cell_t cell)
{
uint32_t c_init;
@ -188,7 +307,7 @@ int srslte_refsignal_cs_set_cell(srslte_refsignal_cs_t * q, srslte_cell_t cell)
}
/** Deallocates a srslte_refsignal_cs_t object allocated with srslte_refsignal_cs_init */
void srslte_refsignal_cs_free(srslte_refsignal_cs_t * q)
void srslte_refsignal_free(srslte_refsignal_t * q)
{
for (int p=0;p<2;p++) {
for (int i=0;i<SRSLTE_NSUBFRAMES_X_FRAME;i++) {
@ -197,10 +316,12 @@ void srslte_refsignal_cs_free(srslte_refsignal_cs_t * q)
}
}
}
bzero(q, sizeof(srslte_refsignal_cs_t));
bzero(q, sizeof(srslte_refsignal_t));
}
/* Maps a reference signal initialized with srslte_refsignal_cs_init() into an array of subframe symbols */
int srslte_refsignal_cs_put_sf(srslte_cell_t cell, uint32_t port_id, cf_t *pilots, cf_t *sf_symbols)
{
@ -228,6 +349,45 @@ int srslte_refsignal_cs_put_sf(srslte_cell_t cell, uint32_t port_id, cf_t *pilot
}
}
SRSLTE_API int srslte_refsignal_mbsfn_put_sf(srslte_cell_t cell,
uint32_t port_id,
cf_t *cs_pilots,
cf_t *mbsfn_pilots,
cf_t *sf_symbols)
{
uint32_t i, l;
uint32_t fidx;
if (srslte_cell_isvalid(&cell) &&
srslte_portid_isvalid(port_id) &&
cs_pilots != NULL &&
mbsfn_pilots != NULL &&
sf_symbols != NULL)
{
// adding CS refs for the non-mbsfn section of the sub-frame
fidx = ((srslte_refsignal_cs_v(port_id, 0) + (cell.id % 6)) % 6);
for (i = 0; i < 2*cell.nof_prb; i++) {
sf_symbols[SRSLTE_RE_IDX(cell.nof_prb, 0, fidx)] = cs_pilots[SRSLTE_REFSIGNAL_PILOT_IDX(i,0,cell)];
fidx += SRSLTE_NRE/2; // 1 reference every 6 RE
}
for (l = 0; l<srslte_refsignal_mbsfn_nof_symbols(); l++) {
uint32_t nsymbol = srslte_refsignal_mbsfn_nsymbol(l);
fidx = srslte_refsignal_mbsfn_fidx(l);
for (i = 0; i < 6*cell.nof_prb; i++) {
sf_symbols[SRSLTE_RE_IDX(cell.nof_prb, nsymbol, fidx)] = mbsfn_pilots[SRSLTE_REFSIGNAL_PILOT_IDX_MBSFN(i,l,cell)];
fidx += SRSLTE_NRE/6;
}
}
return SRSLTE_SUCCESS;
} else {
return SRSLTE_ERROR_INVALID_INPUTS;
}
}
/** Copies the RE containing references from an array of subframe symbols to the pilots array. */
int srslte_refsignal_cs_get_sf(srslte_cell_t cell, uint32_t port_id, cf_t *sf_symbols, cf_t *pilots)
{
@ -254,4 +414,39 @@ int srslte_refsignal_cs_get_sf(srslte_cell_t cell, uint32_t port_id, cf_t *sf_sy
}
}
int srslte_refsignal_mbsfn_get_sf(srslte_cell_t cell, uint32_t port_id, cf_t *sf_symbols, cf_t *pilots)
{
uint32_t i, l;
uint32_t fidx;
uint32_t nsymbol;
if (srslte_cell_isvalid(&cell) &&
srslte_portid_isvalid(port_id) &&
pilots != NULL &&
sf_symbols != NULL)
{
// getting refs from non mbsfn section of subframe
nsymbol = srslte_refsignal_cs_nsymbol(0, cell.cp, port_id);
fidx = ((srslte_refsignal_cs_v(port_id, 0) + (cell.id % 6)) % 6);
for (i = 0; i < 2*cell.nof_prb; i++) {
pilots[SRSLTE_REFSIGNAL_PILOT_IDX(i,0,cell)] = sf_symbols[SRSLTE_RE_IDX(cell.nof_prb, nsymbol, fidx)];
fidx += SRSLTE_NRE/2; // 2 references per PRB
}
for (l = 0; l< srslte_refsignal_mbsfn_nof_symbols() ;l++){
nsymbol = srslte_refsignal_mbsfn_nsymbol(l);
fidx = srslte_refsignal_mbsfn_fidx(l);
for (i = 0; i < 6*cell.nof_prb; i++) {
pilots[SRSLTE_REFSIGNAL_PILOT_IDX_MBSFN(i,l,cell) + (2*cell.nof_prb)] = sf_symbols[SRSLTE_RE_IDX(cell.nof_prb, nsymbol, fidx)];
fidx += SRSLTE_NRE/6;
}
}
return SRSLTE_SUCCESS;
} else {
return SRSLTE_ERROR_INVALID_INPUTS;
}
}

View File

@ -152,7 +152,7 @@ int main(int argc, char **argv) {
bzero(h, sizeof(cf_t) * num_re);
srslte_refsignal_cs_put_sf(cell, n_port,
est.csr_signal.pilots[n_port/2][sf_idx], input);
est.csr_refs.pilots[n_port/2][sf_idx], input);
for (i=0;i<2*SRSLTE_CP_NSYMB(cell.cp);i++) {
for (j=0;j<cell.nof_prb * SRSLTE_NRE;j++) {

View File

@ -37,7 +37,13 @@
#include "srslte/phy/utils/debug.h"
#include "srslte/phy/utils/vector.h"
int srslte_ofdm_init_(srslte_ofdm_t *q, srslte_cp_t cp, int symbol_sz, int nof_prb, srslte_dft_dir_t dir) {
return srslte_ofdm_init_mbsfn_(q, cp, symbol_sz, nof_prb, dir, SRSLTE_SF_NORM);
}
int srslte_ofdm_init_mbsfn_(srslte_ofdm_t *q, srslte_cp_t cp, int symbol_sz, int nof_prb, srslte_dft_dir_t dir, srslte_sf_t sf_type) {
if (srslte_dft_plan_c(&q->fft_plan, symbol_sz, dir)) {
fprintf(stderr, "Error: Creating DFT plan\n");
@ -60,6 +66,7 @@ int srslte_ofdm_init_(srslte_ofdm_t *q, srslte_cp_t cp, int symbol_sz, int nof_p
q->symbol_sz = (uint32_t) symbol_sz;
q->nof_symbols = SRSLTE_CP_NSYMB(cp);
q->nof_symbols_mbsfn = SRSLTE_CP_NSYMB(SRSLTE_CP_EXT);
q->cp = cp;
q->freq_shift = false;
q->nof_re = nof_prb * SRSLTE_NRE;
@ -69,10 +76,20 @@ int srslte_ofdm_init_(srslte_ofdm_t *q, srslte_cp_t cp, int symbol_sz, int nof_p
DEBUG("Init %s symbol_sz=%d, nof_symbols=%d, cp=%s, nof_re=%d, nof_guards=%d\n",
dir==SRSLTE_DFT_FORWARD?"FFT":"iFFT", q->symbol_sz, q->nof_symbols,
q->cp==SRSLTE_CP_NORM?"Normal":"Extended", q->nof_re, q->nof_guards);
// MBSFN logic
if (sf_type == SRSLTE_SF_MBSFN) {
q->mbsfn_subframe = true;
q->non_mbsfn_region = 2; // default set to 2
}
return SRSLTE_SUCCESS;
}
void srslte_ofdm_set_non_mbsfn_region(srslte_ofdm_t *q, uint8_t non_mbsfn_region)
{
q->non_mbsfn_region = non_mbsfn_region;
}
int srslte_ofdm_replan_(srslte_ofdm_t *q, srslte_cp_t cp, int symbol_sz, int nof_prb) {
@ -120,6 +137,17 @@ int srslte_ofdm_rx_init(srslte_ofdm_t *q, srslte_cp_t cp, uint32_t max_prb) {
return srslte_ofdm_init_(q, cp, symbol_sz, max_prb, SRSLTE_DFT_FORWARD);
}
int srslte_ofdm_rx_init_mbsfn(srslte_ofdm_t *q, srslte_cp_t cp, uint32_t nof_prb)
{
int symbol_sz = srslte_symbol_sz(nof_prb);
if (symbol_sz < 0) {
fprintf(stderr, "Error: Invalid nof_prb=%d\n", nof_prb);
return -1;
}
return srslte_ofdm_init_mbsfn_(q, cp, symbol_sz, nof_prb, SRSLTE_DFT_FORWARD, SRSLTE_SF_MBSFN);
}
int srslte_ofdm_tx_init(srslte_ofdm_t *q, srslte_cp_t cp, uint32_t max_prb) {
uint32_t i;
int ret;
@ -130,8 +158,33 @@ int srslte_ofdm_tx_init(srslte_ofdm_t *q, srslte_cp_t cp, uint32_t max_prb) {
return -1;
}
q->max_prb = max_prb;
ret = srslte_ofdm_init_(q, cp, symbol_sz, max_prb, SRSLTE_DFT_BACKWARD);
ret = srslte_ofdm_init_(q, cp, symbol_sz, max_prb, SRSLTE_DFT_BACKWARD);
if (ret == SRSLTE_SUCCESS) {
srslte_dft_plan_set_norm(&q->fft_plan, false);
/* set now zeros at CP */
for (i=0;i<q->nof_symbols;i++) {
bzero(q->tmp, q->nof_guards * sizeof(cf_t));
bzero(&q->tmp[q->nof_re + q->nof_guards], q->nof_guards * sizeof(cf_t));
}
}
return ret;
}
int srslte_ofdm_tx_init_mbsfn(srslte_ofdm_t *q, srslte_cp_t cp, uint32_t nof_prb)
{
uint32_t i;
int ret;
int symbol_sz = srslte_symbol_sz(nof_prb);
if (symbol_sz < 0) {
fprintf(stderr, "Error: Invalid nof_prb=%d\n", nof_prb);
return -1;
}
ret = srslte_ofdm_init_mbsfn_(q, cp, symbol_sz, nof_prb, SRSLTE_DFT_BACKWARD, SRSLTE_SF_MBSFN);
if (ret == SRSLTE_SUCCESS) {
srslte_dft_plan_set_norm(&q->fft_plan, false);
@ -190,7 +243,6 @@ int srslte_ofdm_tx_set_prb(srslte_ofdm_t *q, srslte_cp_t cp, uint32_t nof_prb) {
void srslte_ofdm_rx_free(srslte_ofdm_t *q) {
srslte_ofdm_free_(q);
}
/* Shifts the signal after the iFFT or before the FFT.
* Freq_shift is relative to inter-carrier spacing.
* Caution: This function shall not be called during run-time
@ -233,6 +285,23 @@ void srslte_ofdm_rx_slot(srslte_ofdm_t *q, cf_t *input, cf_t *output) {
}
}
void srslte_ofdm_rx_slot_mbsfn(srslte_ofdm_t *q, cf_t *input, cf_t *output)
{
uint32_t i;
for(i = 0; i < q->nof_symbols_mbsfn; i++){
if(i == q->non_mbsfn_region) {
input += SRSLTE_NON_MBSFN_REGION_GUARD_LENGTH(q->non_mbsfn_region,q->symbol_sz);
}
input += (i>=q->non_mbsfn_region)?SRSLTE_CP_LEN_EXT(q->symbol_sz):SRSLTE_CP_LEN_NORM(i, q->symbol_sz);
srslte_dft_run_c(&q->fft_plan, input, q->tmp);
memcpy(output, &q->tmp[q->nof_guards], q->nof_re * sizeof(cf_t));
input += q->symbol_sz;
output += q->nof_re;
}
}
void srslte_ofdm_rx_slot_zerocopy(srslte_ofdm_t *q, cf_t *input, cf_t *output) {
uint32_t i;
for (i=0;i<q->nof_symbols;i++) {
@ -250,8 +319,14 @@ void srslte_ofdm_rx_sf(srslte_ofdm_t *q, cf_t *input, cf_t *output) {
if (q->freq_shift) {
srslte_vec_prod_ccc(input, q->shift_buffer, input, 2*q->slot_sz);
}
for (n=0;n<2;n++) {
srslte_ofdm_rx_slot(q, &input[n*q->slot_sz], &output[n*q->nof_re*q->nof_symbols]);
if(!q->mbsfn_subframe){
for (n=0;n<2;n++) {
srslte_ofdm_rx_slot(q, &input[n*q->slot_sz], &output[n*q->nof_re*q->nof_symbols]);
}
}
else{
srslte_ofdm_rx_slot_mbsfn(q, &input[0*q->slot_sz], &output[0*q->nof_re*q->nof_symbols]);
srslte_ofdm_rx_slot(q, &input[1*q->slot_sz], &output[1*q->nof_re*q->nof_symbols]);
}
}
@ -271,16 +346,43 @@ void srslte_ofdm_tx_slot(srslte_ofdm_t *q, cf_t *input, cf_t *output) {
}
}
void srslte_ofdm_tx_slot_mbsfn(srslte_ofdm_t *q, cf_t *input, cf_t *output)
{
uint32_t i, cp_len;
for(i=0;i<q->nof_symbols_mbsfn;i++) {
cp_len = ( i>(q->non_mbsfn_region-1) )?SRSLTE_CP_LEN_EXT(q->symbol_sz):SRSLTE_CP_LEN_NORM(i, q->symbol_sz);
memcpy(&q->tmp[q->nof_guards], input, q->nof_re * sizeof(cf_t));
srslte_dft_run_c(&q->fft_plan, q->tmp, &output[cp_len]);
input += q->nof_re;
/* add CP */
memcpy(output, &output[q->symbol_sz], cp_len * sizeof(cf_t));
output += q->symbol_sz + cp_len;
/*skip the small section between the non mbms region and the mbms region*/
if(i == (q->non_mbsfn_region - 1))
output += SRSLTE_NON_MBSFN_REGION_GUARD_LENGTH(q->non_mbsfn_region,q->symbol_sz);
}
}
void srslte_ofdm_set_normalize(srslte_ofdm_t *q, bool normalize_enable) {
srslte_dft_plan_set_norm(&q->fft_plan, normalize_enable);
}
void srslte_ofdm_tx_sf(srslte_ofdm_t *q, cf_t *input, cf_t *output) {
void srslte_ofdm_tx_sf(srslte_ofdm_t *q, cf_t *input, cf_t *output)
{
uint32_t n;
for (n=0;n<2;n++) {
srslte_ofdm_tx_slot(q, &input[n*q->nof_re*q->nof_symbols], &output[n*q->slot_sz]);
if(!q->mbsfn_subframe){
for (n=0;n<2;n++) {
srslte_ofdm_tx_slot(q, &input[n*q->nof_re*q->nof_symbols], &output[n*q->slot_sz]);
}
}
else{
srslte_ofdm_tx_slot_mbsfn(q, &input[0*q->nof_re*q->nof_symbols], &output[0*q->slot_sz]);
srslte_ofdm_tx_slot(q, &input[1*q->nof_re*q->nof_symbols], &output[1*q->slot_sz]);
}
if (q->freq_shift) {
srslte_vec_prod_ccc(output, q->shift_buffer, output, 2*q->slot_sz);
}
}

View File

@ -122,7 +122,7 @@ void srslte_enb_dl_free(srslte_enb_dl_t *q)
srslte_pdcch_free(&q->pdcch);
srslte_pdsch_free(&q->pdsch);
srslte_refsignal_cs_free(&q->csr_signal);
srslte_refsignal_free(&q->csr_signal);
for (int i=0;i<SRSLTE_MAX_PORTS;i++) {
if (q->sf_symbols[i]) {
@ -336,3 +336,33 @@ int srslte_enb_dl_put_pdsch(srslte_enb_dl_t *q, srslte_ra_dl_grant_t *grant, srs
}
return SRSLTE_SUCCESS;
}
void srslte_enb_dl_save_signal(srslte_enb_dl_t *q, srslte_softbuffer_tx_t *softbuffer, uint8_t *data, uint32_t tti, uint32_t rv_idx, uint16_t rnti, uint32_t cfi)
{
char tmpstr[64];
snprintf(tmpstr,64,"output/sf_symbols_%d",tti);
srslte_vec_save_file(tmpstr, q->sf_symbols[0], SRSLTE_SF_LEN_RE(q->cell.nof_prb, q->cell.cp)*sizeof(cf_t));
snprintf(tmpstr,64,"output/e_%d",tti);
srslte_bit_unpack_vector(q->pdsch.e[0], q->tmp, q->pdsch_cfg.nbits[0].nof_bits);
srslte_vec_save_file(tmpstr, q->tmp, q->pdsch_cfg.nbits[0].nof_bits*sizeof(uint8_t));
/*
int cb_len = q->pdsch_cfg.cb_segm[0].K1;
for (int i=0;i<q->pdsch_cfg.cb_segm[0].C;i++) {
snprintf(tmpstr,64,"output/rmout_%d_%d",i,tti);
srslte_bit_unpack_vector(softbuffer->buffer_b[i], q->tmp, (3*cb_len+12));
srslte_vec_save_file(tmpstr, q->tmp, (3*cb_len+12)*sizeof(uint8_t));
}*/
snprintf(tmpstr,64,"output/data_%d",tti);
srslte_bit_unpack_vector(data, q->tmp, q->pdsch_cfg.grant.mcs[0].tbs);
srslte_vec_save_file(tmpstr, q->tmp, q->pdsch_cfg.grant.mcs[0].tbs*sizeof(uint8_t));
//printf("Saved files for tti=%d, sf=%d, cfi=%d, mcs=%d, tbs=%d, rv=%d, rnti=0x%x\n", tti, tti%10, cfi,
// q->pdsch_cfg.grant.mcs[0].idx, q->pdsch_cfg.grant.mcs[0].tbs, rv_idx, rnti);
}

View File

@ -117,7 +117,7 @@ int main(int argc, char **argv) {
float *llr;
short *llr_s;
uint8_t *llr_c;
uint8_t *data_tx, *data_rx, *data_rx_bytes[SRSLTE_TDEC_NPAR], *symbols;
uint8_t *data_tx, *data_rx, *data_rx_bytes[SRSLTE_TDEC_MAX_NPAR], *symbols;
uint32_t i, j;
float var[SNR_POINTS];
uint32_t snr_points;
@ -159,7 +159,7 @@ int main(int argc, char **argv) {
perror("malloc");
exit(-1);
}
for (int cb=0;cb<SRSLTE_TDEC_NPAR;cb++) {
for (int cb=0;cb<SRSLTE_TDEC_MAX_NPAR;cb++) {
data_rx_bytes[cb] = srslte_vec_malloc(frame_length * sizeof(uint8_t));
if (!data_rx_bytes[cb]) {
perror("malloc");
@ -254,10 +254,10 @@ int main(int argc, char **argv) {
t = nof_iterations;
}
int16_t *input[SRSLTE_TDEC_NPAR];
uint8_t *output[SRSLTE_TDEC_NPAR];
int16_t *input[SRSLTE_TDEC_MAX_NPAR];
uint8_t *output[SRSLTE_TDEC_MAX_NPAR];
for (int n=0;n<SRSLTE_TDEC_NPAR;n++) {
for (int n=0;n<SRSLTE_TDEC_MAX_NPAR;n++) {
if (n < nof_cb) {
input[n] = llr_s;
} else {

View File

@ -43,7 +43,7 @@
int srslte_tdec_init(srslte_tdec_t * h, uint32_t max_long_cb) {
#ifdef LV_HAVE_SSE
return srslte_tdec_simd_init(&h->tdec_simd, SRSLTE_TDEC_NPAR, max_long_cb);
return srslte_tdec_simd_init(&h->tdec_simd, SRSLTE_TDEC_MAX_NPAR, max_long_cb);
#else
h->input_conv = srslte_vec_malloc(sizeof(float) * (3*max_long_cb+12));
if (!h->input_conv) {
@ -91,7 +91,7 @@ int srslte_tdec_get_nof_iterations_cb(srslte_tdec_t * h, uint32_t cb_idx)
#endif
}
void srslte_tdec_iteration_par(srslte_tdec_t * h, int16_t* input[SRSLTE_TDEC_NPAR], uint32_t long_cb) {
void srslte_tdec_iteration_par(srslte_tdec_t * h, int16_t* input[SRSLTE_TDEC_MAX_NPAR], uint32_t long_cb) {
#ifdef LV_HAVE_SSE
srslte_tdec_simd_iteration(&h->tdec_simd, input, long_cb);
#else
@ -101,12 +101,12 @@ void srslte_tdec_iteration_par(srslte_tdec_t * h, int16_t* input[SRSLTE_TDEC_NPA
}
void srslte_tdec_iteration(srslte_tdec_t * h, int16_t* input, uint32_t long_cb) {
int16_t *input_par[SRSLTE_TDEC_NPAR];
int16_t *input_par[SRSLTE_TDEC_MAX_NPAR];
input_par[0] = input;
return srslte_tdec_iteration_par(h, input_par, long_cb);
}
void srslte_tdec_decision_par(srslte_tdec_t * h, uint8_t *output[SRSLTE_TDEC_NPAR], uint32_t long_cb) {
void srslte_tdec_decision_par(srslte_tdec_t * h, uint8_t *output[SRSLTE_TDEC_MAX_NPAR], uint32_t long_cb) {
#ifdef LV_HAVE_SSE
return srslte_tdec_simd_decision(&h->tdec_simd, output, long_cb);
#else
@ -114,13 +114,21 @@ void srslte_tdec_decision_par(srslte_tdec_t * h, uint8_t *output[SRSLTE_TDEC_NPA
#endif
}
uint32_t srslte_tdec_get_nof_parallel(srslte_tdec_t *h) {
#ifdef LV_HAVE_AVX2
return 2;
#else
return 1;
#endif
}
void srslte_tdec_decision(srslte_tdec_t * h, uint8_t *output, uint32_t long_cb) {
uint8_t *output_par[SRSLTE_TDEC_NPAR];
uint8_t *output_par[SRSLTE_TDEC_MAX_NPAR];
output_par[0] = output;
srslte_tdec_decision_par(h, output_par, long_cb);
}
void srslte_tdec_decision_byte_par(srslte_tdec_t * h, uint8_t *output[SRSLTE_TDEC_NPAR], uint32_t long_cb) {
void srslte_tdec_decision_byte_par(srslte_tdec_t * h, uint8_t *output[SRSLTE_TDEC_MAX_NPAR], uint32_t long_cb) {
#ifdef LV_HAVE_SSE
srslte_tdec_simd_decision_byte(&h->tdec_simd, output, long_cb);
#else
@ -137,13 +145,13 @@ void srslte_tdec_decision_byte_par_cb(srslte_tdec_t * h, uint8_t *output, uint32
}
void srslte_tdec_decision_byte(srslte_tdec_t * h, uint8_t *output, uint32_t long_cb) {
uint8_t *output_par[SRSLTE_TDEC_NPAR];
uint8_t *output_par[SRSLTE_TDEC_MAX_NPAR];
output_par[0] = output;
srslte_tdec_decision_byte_par(h, output_par, long_cb);
}
int srslte_tdec_run_all_par(srslte_tdec_t * h, int16_t * input[SRSLTE_TDEC_NPAR],
uint8_t *output[SRSLTE_TDEC_NPAR],
int srslte_tdec_run_all_par(srslte_tdec_t * h, int16_t * input[SRSLTE_TDEC_MAX_NPAR],
uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t nof_iterations, uint32_t long_cb) {
#ifdef LV_HAVE_SSE
return srslte_tdec_simd_run_all(&h->tdec_simd, input, output, nof_iterations, long_cb);
@ -155,9 +163,9 @@ int srslte_tdec_run_all_par(srslte_tdec_t * h, int16_t * input[SRSLTE_TDEC_NPAR]
int srslte_tdec_run_all(srslte_tdec_t * h, int16_t * input, uint8_t *output, uint32_t nof_iterations, uint32_t long_cb)
{
uint8_t *output_par[SRSLTE_TDEC_NPAR];
uint8_t *output_par[SRSLTE_TDEC_MAX_NPAR];
output_par[0] = output;
int16_t *input_par[SRSLTE_TDEC_NPAR];
int16_t *input_par[SRSLTE_TDEC_MAX_NPAR];
input_par[0] = input;
return srslte_tdec_run_all_par(h, input_par, output_par, nof_iterations, long_cb);

View File

@ -81,7 +81,7 @@ static inline int16_t hMax1(__m256i masked_value)
}
/* Computes beta values */
void map_avx_beta(map_gen_t * s, int16_t * output[SRSLTE_TDEC_NPAR], uint32_t long_cb)
void map_avx_beta(map_gen_t * s, int16_t * output[SRSLTE_TDEC_MAX_NPAR], uint32_t long_cb)
{
int k;
uint32_t end = long_cb + 3;

View File

@ -54,13 +54,13 @@ void map_sse_alpha(map_gen_t * s, uint32_t long_cb);
void map_sse_gamma(map_gen_t * h, int16_t *input, int16_t *app, int16_t *parity, uint32_t long_cb);
#ifdef LV_HAVE_AVX2
void map_avx_beta(map_gen_t * s, int16_t * output[SRSLTE_TDEC_NPAR], uint32_t long_cb);
void map_avx_beta(map_gen_t * s, int16_t * output[SRSLTE_TDEC_MAX_NPAR], uint32_t long_cb);
void map_avx_alpha(map_gen_t * s, uint32_t long_cb);
void map_avx_gamma(map_gen_t * h, int16_t *input, int16_t *app, int16_t *parity, uint32_t cbidx, uint32_t long_cb);
#endif
void map_simd_beta(map_gen_t * s, int16_t * output[SRSLTE_TDEC_NPAR], uint32_t nof_cb, uint32_t long_cb)
void map_simd_beta(map_gen_t * s, int16_t * output[SRSLTE_TDEC_MAX_NPAR], uint32_t nof_cb, uint32_t long_cb)
{
if (nof_cb == 1) {
map_sse_beta(s, output[0], long_cb);
@ -128,12 +128,12 @@ void map_simd_free(map_gen_t * h)
}
/* Runs one instance of a decoder */
void map_simd_dec(map_gen_t * h, int16_t * input[SRSLTE_TDEC_NPAR], int16_t *app[SRSLTE_TDEC_NPAR], int16_t * parity[SRSLTE_TDEC_NPAR],
int16_t *output[SRSLTE_TDEC_NPAR], uint32_t cb_mask, uint32_t long_cb)
void map_simd_dec(map_gen_t * h, int16_t * input[SRSLTE_TDEC_MAX_NPAR], int16_t *app[SRSLTE_TDEC_MAX_NPAR], int16_t * parity[SRSLTE_TDEC_MAX_NPAR],
int16_t *output[SRSLTE_TDEC_MAX_NPAR], uint32_t cb_mask, uint32_t long_cb)
{
uint32_t nof_cb = 1;
int16_t *outptr[SRSLTE_TDEC_NPAR];
int16_t *outptr[SRSLTE_TDEC_MAX_NPAR];
// Compute branch metrics
switch(cb_mask) {
@ -354,21 +354,21 @@ void deinterleave_input_simd(srslte_tdec_simd_t *h, int16_t *input, uint32_t cbi
}
/* Runs 1 turbo decoder iteration */
void srslte_tdec_simd_iteration(srslte_tdec_simd_t * h, int16_t * input[SRSLTE_TDEC_NPAR], uint32_t long_cb)
void srslte_tdec_simd_iteration(srslte_tdec_simd_t * h, int16_t * input[SRSLTE_TDEC_MAX_NPAR], uint32_t long_cb)
{
int16_t *tmp_app[SRSLTE_TDEC_NPAR];
int16_t *tmp_app[SRSLTE_TDEC_MAX_NPAR];
if (h->current_cbidx >= 0) {
uint16_t *inter = h->interleaver[h->current_cbidx].forward;
uint16_t *deinter = h->interleaver[h->current_cbidx].reverse;
#if SRSLTE_TDEC_NPAR == 2
h->cb_mask = (input[0]?1:0) | (input[1]?2:0);
#else
h->cb_mask = input[0]?1:0;
#ifndef LV_HAVE_AVX2
input[1] = NULL;
#endif
h->cb_mask = (input[0]?1:0) | (input[1]?2:0);
for (int i=0;i<h->max_par_cb;i++) {
if (h->n_iter[i] == 0 && input[i]) {
//printf("deinterleaveing %d\n",i);
@ -484,7 +484,7 @@ void tdec_simd_decision(srslte_tdec_simd_t * h, uint8_t *output, uint32_t cbidx,
}
}
void srslte_tdec_simd_decision(srslte_tdec_simd_t * h, uint8_t *output[SRSLTE_TDEC_NPAR], uint32_t long_cb)
void srslte_tdec_simd_decision(srslte_tdec_simd_t * h, uint8_t *output[SRSLTE_TDEC_MAX_NPAR], uint32_t long_cb)
{
for (int i=0;i<h->max_par_cb;i++) {
tdec_simd_decision(h, output[i], i, long_cb);
@ -510,7 +510,7 @@ void srslte_tdec_simd_decision_byte_cb(srslte_tdec_simd_t * h, uint8_t *output,
}
}
void srslte_tdec_simd_decision_byte(srslte_tdec_simd_t * h, uint8_t *output[SRSLTE_TDEC_NPAR], uint32_t long_cb)
void srslte_tdec_simd_decision_byte(srslte_tdec_simd_t * h, uint8_t *output[SRSLTE_TDEC_MAX_NPAR], uint32_t long_cb)
{
for (int i=0;i<h->max_par_cb;i++) {
srslte_tdec_simd_decision_byte_cb(h, output[i], i, long_cb);
@ -519,7 +519,7 @@ void srslte_tdec_simd_decision_byte(srslte_tdec_simd_t * h, uint8_t *output[SRSL
/* Runs nof_iterations iterations and decides the output bits */
int srslte_tdec_simd_run_all(srslte_tdec_simd_t * h, int16_t * input[SRSLTE_TDEC_NPAR], uint8_t *output[SRSLTE_TDEC_NPAR],
int srslte_tdec_simd_run_all(srslte_tdec_simd_t * h, int16_t * input[SRSLTE_TDEC_MAX_NPAR], uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t nof_iterations, uint32_t long_cb)
{
if (srslte_tdec_simd_reset(h, long_cb)) {

View File

@ -172,7 +172,7 @@ void extract_input(srslte_tdec_simd_inter_t *h, int16_t *input, uint32_t cbidx,
}
}
void srslte_tdec_simd_inter_iteration(srslte_tdec_simd_inter_t * h, int16_t *input[SRSLTE_TDEC_NPAR], uint32_t nof_cb, uint32_t long_cb)
void srslte_tdec_simd_inter_iteration(srslte_tdec_simd_inter_t * h, int16_t *input[SRSLTE_TDEC_MAX_NPAR], uint32_t nof_cb, uint32_t long_cb)
{
if (h->current_cbidx >= 0) {
@ -239,7 +239,7 @@ void srslte_tdec_simd_inter_decision_cb(srslte_tdec_simd_inter_t * h, uint8_t *o
}
}
void srslte_tdec_simd_inter_decision(srslte_tdec_simd_inter_t * h, uint8_t *output[SRSLTE_TDEC_NPAR], uint32_t nof_cb, uint32_t long_cb)
void srslte_tdec_simd_inter_decision(srslte_tdec_simd_inter_t * h, uint8_t *output[SRSLTE_TDEC_MAX_NPAR], uint32_t nof_cb, uint32_t long_cb)
{
for (int i=0;i<nof_cb;i++) {
srslte_tdec_simd_inter_decision_cb(h, output[i], i, long_cb);
@ -269,7 +269,7 @@ void srslte_tdec_simd_inter_decision_byte_cb(srslte_tdec_simd_inter_t * h, uint8
}
}
void srslte_tdec_simd_inter_decision_byte(srslte_tdec_simd_inter_t * h, uint8_t *output[SRSLTE_TDEC_NPAR], uint32_t nof_cb, uint32_t long_cb)
void srslte_tdec_simd_inter_decision_byte(srslte_tdec_simd_inter_t * h, uint8_t *output[SRSLTE_TDEC_MAX_NPAR], uint32_t nof_cb, uint32_t long_cb)
{
for (int i=0;i<nof_cb;i++) {
srslte_tdec_simd_inter_decision_byte_cb(h, output[i], i, long_cb);
@ -277,7 +277,7 @@ void srslte_tdec_simd_inter_decision_byte(srslte_tdec_simd_inter_t * h, uint8_t
}
int srslte_tdec_simd_inter_run_all(srslte_tdec_simd_inter_t * h,
int16_t *input[SRSLTE_TDEC_NPAR], uint8_t *output[SRSLTE_TDEC_NPAR],
int16_t *input[SRSLTE_TDEC_MAX_NPAR], uint8_t *output[SRSLTE_TDEC_MAX_NPAR],
uint32_t nof_iterations, uint32_t nof_cb, uint32_t long_cb)
{
uint32_t iter = 0;

View File

@ -36,13 +36,16 @@
#include "srslte/phy/utils/mat.h"
#ifdef LV_HAVE_SSE
#include <immintrin.h>
int srslte_predecoding_single_sse(cf_t *y[SRSLTE_MAX_PORTS], cf_t *h[SRSLTE_MAX_PORTS], cf_t *x, int nof_rxant, int nof_symbols, float noise_estimate);
int srslte_predecoding_diversity2_sse(cf_t *y[SRSLTE_MAX_PORTS], cf_t *h[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS], cf_t *x[SRSLTE_MAX_LAYERS], int nof_rxant, int nof_symbols);
#endif
#ifdef LV_HAVE_AVX
#include <immintrin.h>
int srslte_predecoding_single_avx(cf_t *y[SRSLTE_MAX_PORTS], cf_t *h[SRSLTE_MAX_PORTS], cf_t *x, int nof_rxant, int nof_symbols, float noise_estimate);
#endif
#include "srslte/phy/utils/mat.h"
static srslte_mimo_decoder_t mimo_decoder = SRSLTE_MIMO_DECODER_MMSE;
@ -1364,7 +1367,7 @@ int srslte_predecoding_multiplex(cf_t *y[SRSLTE_MAX_PORTS], cf_t *h[SRSLTE_MAX_P
int nof_rxant, int nof_ports, int nof_layers, int codebook_idx, int nof_symbols,
float noise_estimate)
{
if (nof_ports == 2 && nof_rxant == 2) {
if (nof_ports == 2 && nof_rxant <= 2) {
if (nof_layers == 2) {
switch (mimo_decoder) {
case SRSLTE_MIMO_DECODER_ZF:
@ -1404,7 +1407,7 @@ int srslte_predecoding_multiplex(cf_t *y[SRSLTE_MAX_PORTS], cf_t *h[SRSLTE_MAX_P
} else if (nof_ports == 4) {
ERROR("Error predecoding multiplex: not implemented for %d Tx ports", nof_ports);
} else {
ERROR("Error predecoding multiplex: Invalid combination of ports %d and rx antennax %d\n", nof_ports, nof_rxant);
ERROR("Error predecoding multiplex: Invalid combination of ports %d and rx antennas %d\n", nof_ports, nof_rxant);
}
return SRSLTE_ERROR;
}

View File

@ -29,15 +29,11 @@
#include <string.h>
#include <stdlib.h>
#include <stdbool.h>
#include <srslte/phy/phch/pdsch_cfg.h>
#include <srslte/phy/common/sequence.h>
#include <srslte/phy/phch/pdsch.h>
#include "prb_dl.h"
#include "srslte/phy/phch/pdsch.h"
#include "srslte/phy/utils/debug.h"
#include "srslte/phy/utils/vector.h"
#include "srslte/phy/utils/bit.h"
#define MAX_PDSCH_RE(cp) (2 * SRSLTE_CP_NSYMB(cp) * 12)
@ -246,7 +242,7 @@ static int pdsch_init(srslte_pdsch_t *q, uint32_t max_prb, bool is_ue, uint32_t
goto clean;
}
if (q->is_ue) {
for (int j=0;j<q->nof_rx_antennas;j++) {
for (int j = 0; j < SRSLTE_MAX_PORTS; j++) {
q->ce[i][j] = srslte_vec_malloc(sizeof(cf_t) * q->max_re);
if (!q->ce[i][j]) {
goto clean;
@ -309,7 +305,7 @@ void srslte_pdsch_free(srslte_pdsch_t *q) {
free(q->symbols[i]);
}
if (q->is_ue) {
for (int j=0;j<q->nof_rx_antennas;j++) {
for (int j = 0; j < SRSLTE_MAX_PORTS; j++) {
if (q->ce[i][j]) {
free(q->ce[i][j]);
}
@ -606,6 +602,9 @@ static int srslte_pdsch_codeword_decode(srslte_pdsch_t *q, srslte_pdsch_cfg_t *c
/* Return */
ret = srslte_dlsch_decode2(&q->dl_sch, cfg, softbuffer, q->e[codeword_idx], data, codeword_idx);
q->last_nof_iterations[codeword_idx] = srslte_sch_last_noi(&q->dl_sch);
if (ret == SRSLTE_SUCCESS) {
*ack = true;
} else if (ret == SRSLTE_ERROR) {
@ -613,7 +612,7 @@ static int srslte_pdsch_codeword_decode(srslte_pdsch_t *q, srslte_pdsch_cfg_t *c
ret = SRSLTE_SUCCESS;
}
} else {
ERROR("Detected NULL pointer");
ERROR("Detected NULL pointer in TB%d &softbuffer=%p &data=%p &ack=%p", codeword_idx, softbuffer, (void*)data, ack);
}
return ret;
@ -686,10 +685,10 @@ int srslte_pdsch_decode(srslte_pdsch_t *q,
srslte_layerdemap_type(x, q->d, cfg->nof_layers, nof_tb,
nof_symbols[0], nof_symbols, cfg->mimo_type);
}
// Codeword decoding
for (uint32_t tb = 0; tb < SRSLTE_MAX_CODEWORDS; tb ++) {
if (cfg->grant.tb_en[tb]) {
/* Decode only if transport block is enabled and the default ACK is not true */
if (cfg->grant.tb_en[tb] && !acks[tb]) {
int ret = srslte_pdsch_codeword_decode(q, cfg, softbuffers[tb], rnti, data[tb], tb, &acks[tb]);
/* Check if there has been any execution error */
@ -712,8 +711,9 @@ int srslte_pdsch_pmi_select(srslte_pdsch_t *q,
cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS], float noise_estimate, uint32_t nof_ce,
uint32_t pmi[SRSLTE_MAX_LAYERS], float sinr[SRSLTE_MAX_LAYERS][SRSLTE_MAX_CODEBOOKS]) {
if (q->cell.nof_ports == 2 && q->nof_rx_antennas == 2) {
for (int nof_layers = 1; nof_layers <= 2; nof_layers++ ) {
if (q->cell.nof_ports == 2 && q->nof_rx_antennas <= 2) {
int nof_layers = 1;
for (; nof_layers <= q->nof_rx_antennas; nof_layers++ ) {
if (sinr[nof_layers - 1] && pmi) {
if (srslte_precoding_pmi_select(ce, nof_ce, noise_estimate, nof_layers, &pmi[nof_layers - 1],
sinr[nof_layers - 1]) < 0) {
@ -722,6 +722,16 @@ int srslte_pdsch_pmi_select(srslte_pdsch_t *q,
}
}
}
/* FIXME: Set other layers to 0 */
for (; nof_layers <= SRSLTE_MAX_LAYERS; nof_layers++ ) {
if (sinr[nof_layers - 1] && pmi) {
for (int cb = 0; cb < SRSLTE_MAX_CODEBOOKS; cb++) {
sinr[nof_layers - 1][cb] = -INFINITY;
}
pmi[nof_layers - 1] = 0;
}
}
} else {
ERROR("Not implemented configuration");
return SRSLTE_ERROR_INVALID_INPUTS;
@ -816,14 +826,13 @@ void srslte_pdsch_set_max_noi(srslte_pdsch_t *q, uint32_t max_iter) {
srslte_sch_set_max_noi(&q->dl_sch, max_iter);
}
float srslte_pdsch_average_noi(srslte_pdsch_t *q) {
return q->dl_sch.average_nof_iterations;
float srslte_pdsch_last_noi(srslte_pdsch_t *q) {
return srslte_pdsch_last_noi_cw(q, 0);
}
uint32_t srslte_pdsch_last_noi(srslte_pdsch_t *q) {
return q->dl_sch.nof_iterations;
uint32_t srslte_pdsch_last_noi_cw(srslte_pdsch_t *q, uint32_t cw_idx) {
return q->last_nof_iterations[cw_idx];
}

View File

@ -173,26 +173,9 @@ void srslte_phich_ack_encode(uint8_t ack, uint8_t bits[SRSLTE_PHICH_NBITS]) {
memset(bits, ack, 3 * sizeof(uint8_t));
}
int srslte_phich_decode(srslte_phich_t *q, cf_t *sf_symbols, cf_t *ce[SRSLTE_MAX_PORTS], float noise_estimate,
uint32_t ngroup, uint32_t nseq, uint32_t subframe, uint8_t *ack, float *distance)
{
cf_t *_sf_symbols[SRSLTE_MAX_PORTS];
cf_t *_ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS];
_sf_symbols[0] = sf_symbols;
for (int i=0;i<q->cell.nof_ports;i++) {
_ce[i][0] = ce[i];
}
return srslte_phich_decode_multi(q, _sf_symbols, _ce, noise_estimate, ngroup, nseq, subframe, ack, distance);
}
/* Decodes the phich channel and saves the CFI in the cfi pointer.
*
* Returns 1 if successfully decoded the CFI, 0 if not and -1 on error
*/
int srslte_phich_decode_multi(srslte_phich_t *q, cf_t *sf_symbols[SRSLTE_MAX_PORTS], cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS], float noise_estimate,
uint32_t ngroup, uint32_t nseq, uint32_t subframe, uint8_t *ack, float *distance)
{
int srslte_phich_decode(srslte_phich_t *q, cf_t *sf_symbols[SRSLTE_MAX_PORTS],
cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS], float noise_estimate,
uint32_t ngroup, uint32_t nseq, uint32_t subframe, uint8_t *ack, float *distance) {
/* Set pointers for layermapping & precoding */
int i, j;

481
lib/src/phy/phch/pmch.c Normal file
View File

@ -0,0 +1,481 @@
/**
*
* \section COPYRIGHT
*
* Copyright 2013-2015 Software Radio Systems Limited
*
* \section LICENSE
*
* This file is part of the srsLTE library.
*
* srsLTE is free software: you can redistribute it and/or modify
* it under the terms of the GNU Affero General Public License as
* published by the Free Software Foundation, either version 3 of
* the License, or (at your option) any later version.
*
* srsLTE 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 Affero General Public License for more details.
*
* A copy of the GNU Affero General Public License can be found in
* the LICENSE file in the top-level directory of this distribution
* and at http://www.gnu.org/licenses/.
*
*/
#include <stdint.h>
#include <stdio.h>
#include <string.h>
#include <strings.h>
#include <stdlib.h>
#include <stdbool.h>
#include <assert.h>
#include <math.h>
#include "prb_dl.h"
#include "srslte/phy/phch/sch.h"
#include "srslte/phy/common/phy_common.h"
#include "srslte/phy/utils/bit.h"
#include "srslte/phy/utils/debug.h"
#include "srslte/phy/utils/vector.h"
#define MAX_PMCH_RE (2 * SRSLTE_CP_EXT_NSYMB * 12)
const static srslte_mod_t modulations[4] =
{ SRSLTE_MOD_BPSK, SRSLTE_MOD_QPSK, SRSLTE_MOD_16QAM, SRSLTE_MOD_64QAM };
//#define DEBUG_IDX
#ifdef DEBUG_IDX
cf_t *offset_original=NULL;
extern int indices[100000];
extern int indices_ptr;
#endif
float srslte_pmch_coderate(uint32_t tbs, uint32_t nof_re)
{
return (float) (tbs + 24)/(nof_re);
}
int srslte_pmch_cp(srslte_pmch_t *q, cf_t *input, cf_t *output, uint32_t lstart_grant, bool put)
{
uint32_t s, n, l, lp, lstart, lend, nof_refs;
cf_t *in_ptr = input, *out_ptr = output;
uint32_t offset = 0;
#ifdef DEBUG_IDX
indices_ptr = 0;
if (put) {
offset_original = output;
} else {
offset_original = input;
}
#endif
nof_refs = 6;
for (s = 0; s < 2; s++) {
for (l = 0; l < SRSLTE_CP_EXT_NSYMB; l++) {
for (n = 0; n < q->cell.nof_prb; n++) {
// If this PRB is assigned
if (true) {
if (s == 0) {
lstart = lstart_grant;
} else {
lstart = 0;
}
lend = SRSLTE_CP_EXT_NSYMB;
lp = l + s * SRSLTE_CP_EXT_NSYMB;
if (put) {
out_ptr = &output[(lp * q->cell.nof_prb + n) * SRSLTE_NRE];
} else {
in_ptr = &input[(lp * q->cell.nof_prb + n) * SRSLTE_NRE];
}
// This is a symbol in a normal PRB with or without references
if (l >= lstart && l < lend) {
if (SRSLTE_SYMBOL_HAS_REF_MBSFN(l,s)) {
if (l == 0 && s == 1) {
offset = 1;
} else {
offset = 0;
}
prb_cp_ref(&in_ptr, &out_ptr, offset, nof_refs, nof_refs, put);
} else {
prb_cp(&in_ptr, &out_ptr, 1);
}
}
}
}
}
}
int r;
if (put) {
r = abs((int) (input - in_ptr));
} else {
r = abs((int) (output - out_ptr));
}
return r;
}
/**
* Puts PMCH in slot number 1
*
* Returns the number of symbols written to sf_symbols
*
* 36.211 10.3 section 6.3.5
*/
int srslte_pmch_put(srslte_pmch_t *q, cf_t *symbols, cf_t *sf_symbols, uint32_t lstart)
{
return srslte_pmch_cp(q, symbols, sf_symbols, lstart, true);
}
/**
* Extracts PMCH from slot number 1
*
* Returns the number of symbols written to PMCH
*
* 36.211 10.3 section 6.3.5
*/
int srslte_pmch_get(srslte_pmch_t *q, cf_t *sf_symbols, cf_t *symbols, uint32_t lstart)
{
return srslte_pmch_cp(q, sf_symbols, symbols, lstart, false);
}
int srslte_pmch_init(srslte_pmch_t *q, uint32_t max_prb)
{
return srslte_pmch_init_multi(q, max_prb, 1);
}
int srslte_pmch_init_multi(srslte_pmch_t *q, uint32_t max_prb, uint32_t nof_rx_antennas)
{
int ret = SRSLTE_ERROR_INVALID_INPUTS;
int i;
if (q != NULL &&
nof_rx_antennas <= SRSLTE_MAX_PORTS)
{
bzero(q, sizeof(srslte_pmch_t));
ret = SRSLTE_ERROR;
q->cell.nof_prb = max_prb;
q->cell.nof_ports = 1;
q->max_re = max_prb * MAX_PMCH_RE;
q->nof_rx_antennas = nof_rx_antennas;
INFO("Init PMCH: %d PRBs, max_symbols: %d\n",
max_prb, q->max_re);
for (i = 0; i < 4; i++) {
if (srslte_modem_table_lte(&q->mod[i], modulations[i])) {
goto clean;
}
srslte_modem_table_bytes(&q->mod[i]);
}
srslte_sch_init(&q->dl_sch);
// Allocate int16_t for reception (LLRs)
q->e = srslte_vec_malloc(sizeof(int16_t) * q->max_re * srslte_mod_bits_x_symbol(SRSLTE_MOD_64QAM));
if (!q->e) {
goto clean;
}
q->d = srslte_vec_malloc(sizeof(cf_t) * q->max_re);
if (!q->d) {
goto clean;
}
for (i = 0; i < SRSLTE_MAX_PORTS; i++) {
q->x[i] = srslte_vec_malloc(sizeof(cf_t) * q->max_re);
if (!q->x[i]) {
goto clean;
}
for (int j=0;j<q->nof_rx_antennas;j++) {
q->ce[i][j] = srslte_vec_malloc(sizeof(cf_t) * q->max_re);
if (!q->ce[i][j]) {
goto clean;
}
}
}
for (int j=0;j<q->nof_rx_antennas;j++) {
q->symbols[j] = srslte_vec_malloc(sizeof(cf_t) * q->max_re);
if (!q->symbols[j]) {
goto clean;
}
}
q->seqs = calloc(SRSLTE_MAX_MBSFN_AREA_IDS, sizeof(srslte_pmch_seq_t*));
if (!q->seqs) {
perror("calloc");
goto clean;
}
ret = SRSLTE_SUCCESS;
}
clean:
if (ret == SRSLTE_ERROR) {
srslte_pmch_free(q);
}
return ret;
}
void srslte_pmch_free(srslte_pmch_t *q) {
uint16_t i;
if (q->e) {
free(q->e);
}
if (q->d) {
free(q->d);
}
for (i = 0; i < q->cell.nof_ports; i++) {
if (q->x[i]) {
free(q->x[i]);
}
for (int j=0;j<q->nof_rx_antennas;j++) {
if (q->ce[i][j]) {
free(q->ce[i][j]);
}
}
}
for (i=0;i<q->nof_rx_antennas;i++) {
if (q->symbols[i]) {
free(q->symbols[i]);
}
}
if (q->seqs) {
for (i=0; i<SRSLTE_MAX_MBSFN_AREA_IDS; i++) {
if (q->seqs[i]) {
srslte_pmch_free_area_id(q, i);
}
}
free(q->seqs);
}
for (i = 0; i < 4; i++) {
srslte_modem_table_free(&q->mod[i]);
}
srslte_sch_free(&q->dl_sch);
bzero(q, sizeof(srslte_pmch_t));
}
/* Precalculate the scramble sequences for a given MBSFN area ID. This function takes a while
* to execute.
*/
int srslte_pmch_set_area_id(srslte_pmch_t *q, uint16_t area_id) {
uint32_t i;
if (!q->seqs[area_id]) {
q->seqs[area_id] = calloc(1, sizeof(srslte_pmch_seq_t));
if (q->seqs[area_id]) {
for (i = 0; i < SRSLTE_NSUBFRAMES_X_FRAME; i++) {
if (srslte_sequence_pmch(&q->seqs[area_id]->seq[i], 2 * i , area_id, q->max_re * srslte_mod_bits_x_symbol(SRSLTE_MOD_64QAM))) {
return SRSLTE_ERROR;
}
}
}
}
return SRSLTE_SUCCESS;
}
void srslte_pmch_free_area_id(srslte_pmch_t* q, uint16_t area_id)
{
if (q->seqs[area_id]) {
for (int i = 0; i < SRSLTE_NSUBFRAMES_X_FRAME; i++) {
srslte_sequence_free(&q->seqs[area_id]->seq[i]);
}
free(q->seqs[area_id]);
q->seqs[area_id] = NULL;
}
}
int srslte_pmch_cfg(srslte_pdsch_cfg_t *cfg, srslte_cell_t cell, srslte_ra_dl_grant_t *grant, uint32_t cfi, uint32_t sf_idx)
{
if (cfg) {
if (grant) {
memcpy(&cfg->grant, grant, sizeof(srslte_ra_dl_grant_t));
}
if (srslte_cbsegm(&cfg->cb_segm[0], cfg->grant.mcs[0].tbs)) {
fprintf(stderr, "Error computing Codeblock segmentation for TBS=%d\n", cfg->grant.mcs[0].tbs);
return SRSLTE_ERROR;
}
srslte_ra_dl_grant_to_nbits(&cfg->grant, cfi, cell, sf_idx, cfg->nbits);
cfg->sf_idx = sf_idx;
cfg->rv[0] = SRSLTE_PMCH_RV;
return SRSLTE_SUCCESS;
} else {
return SRSLTE_ERROR_INVALID_INPUTS;
}
}
int srslte_pmch_decode(srslte_pmch_t *q,
srslte_pdsch_cfg_t *cfg, srslte_softbuffer_rx_t *softbuffer,
cf_t *sf_symbols, cf_t *ce[SRSLTE_MAX_PORTS], float noise_estimate,
uint16_t area_id, uint8_t *data)
{
cf_t *_sf_symbols[SRSLTE_MAX_PORTS];
cf_t *_ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS];
_sf_symbols[0] = sf_symbols;
for (int i=0;i<q->cell.nof_ports;i++) {
_ce[i][0] = ce[i];
}
return srslte_pmch_decode_multi(q, cfg, softbuffer, _sf_symbols, _ce, noise_estimate, area_id, data);
}
/** Decodes the pmch from the received symbols
*/
int srslte_pmch_decode_multi(srslte_pmch_t *q,
srslte_pdsch_cfg_t *cfg, srslte_softbuffer_rx_t *softbuffer,
cf_t *sf_symbols[SRSLTE_MAX_PORTS], cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS], float noise_estimate,
uint16_t area_id, uint8_t *data)
{
/* Set pointers for layermapping & precoding */
uint32_t i, n;
cf_t *x[SRSLTE_MAX_LAYERS];
if (q != NULL &&
sf_symbols != NULL &&
data != NULL &&
cfg != NULL)
{
INFO("Decoding PMCH SF: %d, MBSFN area ID: 0x%x, Mod %s, TBS: %d, NofSymbols: %d, NofBitsE: %d, rv_idx: %d, C_prb=%d, cfi=%d\n",
cfg->sf_idx, area_id, srslte_mod_string(cfg->grant.mcs[0].mod), cfg->grant.mcs[0].tbs, cfg->nbits[0].nof_re,
cfg->nbits[0].nof_bits, 0, cfg->grant.nof_prb, cfg->nbits[0].lstart-1);
/* number of layers equals number of ports */
for (i = 0; i < q->cell.nof_ports; i++) {
x[i] = q->x[i];
}
memset(&x[q->cell.nof_ports], 0, sizeof(cf_t*) * (SRSLTE_MAX_LAYERS - q->cell.nof_ports));
for (int j=0;j<q->nof_rx_antennas;j++) {
/* extract symbols */
n = srslte_pmch_get(q, sf_symbols[j], q->symbols[j], cfg->nbits[0].lstart);
if (n != cfg->nbits[0].nof_re) {
fprintf(stderr, "PMCH 1 extract symbols error expecting %d symbols but got %d, lstart %d\n", cfg->nbits[0].nof_re, n, cfg->nbits[0].lstart);
return SRSLTE_ERROR;
}
/* extract channel estimates */
for (i = 0; i < q->cell.nof_ports; i++) {
n = srslte_pmch_get(q, ce[i][j], q->ce[i][j], cfg->nbits[0].lstart);
if (n != cfg->nbits[0].nof_re) {
fprintf(stderr, "PMCH 2 extract chest error expecting %d symbols but got %d\n", cfg->nbits[0].nof_re, n);
return SRSLTE_ERROR;
}
}
}
// No tx diversity in MBSFN
srslte_predecoding_single_multi(q->symbols, q->ce[0], q->d, q->nof_rx_antennas, cfg->nbits[0].nof_re, noise_estimate);
if (SRSLTE_VERBOSE_ISDEBUG()) {
DEBUG("SAVED FILE subframe.dat: received subframe symbols\n",0);
srslte_vec_save_file("subframe.dat", sf_symbols, SRSLTE_SF_LEN_RE(q->cell.nof_prb, q->cell.cp)*sizeof(cf_t));
DEBUG("SAVED FILE hest0.dat: channel estimates for port 4\n",0);
srslte_vec_save_file("hest0.dat", ce[0], SRSLTE_SF_LEN_RE(q->cell.nof_prb, q->cell.cp)*sizeof(cf_t));
DEBUG("SAVED FILE pmch_symbols.dat: symbols after equalization\n",0);
srslte_vec_save_file("pmch_symbols.bin", q->d, cfg->nbits[0].nof_re*sizeof(cf_t));
}
/* demodulate symbols
* The MAX-log-MAP algorithm used in turbo decoding is unsensitive to SNR estimation,
* thus we don't need tot set it in thde LLRs normalization
*/
srslte_demod_soft_demodulate_s(cfg->grant.mcs[0].mod, q->d, q->e, cfg->nbits[0].nof_re);
/* descramble */
srslte_scrambling_s_offset(&q->seqs[area_id]->seq[cfg->sf_idx], q->e, 0, cfg->nbits[0].nof_bits);
if (SRSLTE_VERBOSE_ISDEBUG()) {
DEBUG("SAVED FILE llr.dat: LLR estimates after demodulation and descrambling\n",0);
srslte_vec_save_file("llr.dat", q->e, cfg->nbits[0].nof_bits*sizeof(int16_t));
}
return srslte_dlsch_decode(&q->dl_sch, cfg, softbuffer, q->e, data);
} else {
return SRSLTE_ERROR_INVALID_INPUTS;
}
}
int srslte_pmch_encode(srslte_pmch_t *q,
srslte_pdsch_cfg_t *cfg, srslte_softbuffer_tx_t *softbuffer,
uint8_t *data, uint16_t area_id, cf_t *sf_symbols[SRSLTE_MAX_PORTS])
{
int i;
/* Set pointers for layermapping & precoding */
cf_t *x[SRSLTE_MAX_LAYERS];
int ret = SRSLTE_ERROR_INVALID_INPUTS;
if (q != NULL && cfg != NULL)
{
for (i=0;i<q->cell.nof_ports;i++) {
if (sf_symbols[i] == NULL) {
return SRSLTE_ERROR_INVALID_INPUTS;
}
}
if (cfg->grant.mcs[0].tbs == 0) {
return SRSLTE_ERROR_INVALID_INPUTS;
}
if (cfg->nbits[0].nof_re > q->max_re) {
fprintf(stderr,
"Error too many RE per subframe (%d). PMCH configured for %d RE (%d PRB)\n",
cfg->nbits[0].nof_re, q->max_re, q->cell.nof_prb);
return SRSLTE_ERROR_INVALID_INPUTS;
}
INFO("Encoding PMCH SF: %d, Mod %s, NofBits: %d, NofSymbols: %d, NofBitsE: %d, rv_idx: %d\n",
cfg->sf_idx, srslte_mod_string(cfg->grant.mcs[0].mod), cfg->grant.mcs[0].tbs,
cfg->nbits[0].nof_re, cfg->nbits[0].nof_bits, 0);
/* number of layers equals number of ports */
for (i = 0; i < q->cell.nof_ports; i++) {
x[i] = q->x[i];
}
memset(&x[q->cell.nof_ports], 0, sizeof(cf_t*) * (SRSLTE_MAX_LAYERS - q->cell.nof_ports));
// TODO: use tb_encode directly
if (srslte_dlsch_encode(&q->dl_sch, cfg, softbuffer, data, q->e)) {
fprintf(stderr, "Error encoding TB\n");
return SRSLTE_ERROR;
}
/* scramble */
srslte_scrambling_bytes(&q->seqs[area_id]->seq[cfg->sf_idx], (uint8_t*) q->e, cfg->nbits[0].nof_bits);
srslte_mod_modulate_bytes(&q->mod[cfg->grant.mcs[0].mod], (uint8_t*) q->e, q->d, cfg->nbits[0].nof_bits);
/* No tx diversity in MBSFN */
memcpy(q->symbols[0], q->d, cfg->nbits[0].nof_re * sizeof(cf_t));
/* mapping to resource elements */
for (i = 0; i < q->cell.nof_ports; i++) {
srslte_pmch_put(q, q->symbols[i], sf_symbols[i], cfg->nbits[0].lstart);
}
ret = SRSLTE_SUCCESS;
}
return ret;
}
uint32_t srslte_pmch_last_noi(srslte_pmch_t *q) {
return q->dl_sch.nof_iterations;
}

View File

@ -41,15 +41,19 @@
/* Returns the number of RE in a PRB in a slot and subframe */
uint32_t ra_re_x_prb(uint32_t subframe, uint32_t slot, uint32_t prb_idx, uint32_t nof_prb,
uint32_t nof_ports, uint32_t nof_ctrl_symbols, srslte_cp_t cp) {
uint32_t nof_ports, uint32_t nof_ctrl_symbols, srslte_cp_t cp, srslte_sf_t sf_type) {
uint32_t re;
bool skip_refs = false;
bool skip_refs = true;
srslte_cp_t cp_ = cp;
if(SRSLTE_SF_MBSFN == sf_type) {
cp_ = SRSLTE_CP_EXT;
}
if (slot == 0) {
re = (SRSLTE_CP_NSYMB(cp) - nof_ctrl_symbols) * SRSLTE_NRE;
re = (SRSLTE_CP_NSYMB(cp_) - nof_ctrl_symbols) * SRSLTE_NRE;
} else {
re = SRSLTE_CP_NSYMB(cp) * SRSLTE_NRE;
re = SRSLTE_CP_NSYMB(cp_) * SRSLTE_NRE;
}
/* if it's the prb in the middle, there are less RE due to PBCH and PSS/SSS */
@ -57,18 +61,18 @@ uint32_t ra_re_x_prb(uint32_t subframe, uint32_t slot, uint32_t prb_idx, uint32_
&& (prb_idx >= nof_prb / 2 - 3 && prb_idx < nof_prb / 2 + 3 + (nof_prb%2))) {
if (subframe == 0) {
if (slot == 0) {
re = (SRSLTE_CP_NSYMB(cp) - nof_ctrl_symbols - 2) * SRSLTE_NRE;
re = (SRSLTE_CP_NSYMB(cp_) - nof_ctrl_symbols - 2) * SRSLTE_NRE;
} else {
if (SRSLTE_CP_ISEXT(cp)) {
re = (SRSLTE_CP_NSYMB(cp) - 4) * SRSLTE_NRE;
skip_refs = true;
if (SRSLTE_CP_ISEXT(cp_)) {
re = (SRSLTE_CP_NSYMB(cp_) - 4) * SRSLTE_NRE;
skip_refs = false;
} else {
re = (SRSLTE_CP_NSYMB(cp) - 4) * SRSLTE_NRE + 2 * nof_ports;
re = (SRSLTE_CP_NSYMB(cp_) - 4) * SRSLTE_NRE + 2 * nof_ports;
}
}
} else if (subframe == 5) {
if (slot == 0) {
re = (SRSLTE_CP_NSYMB(cp) - nof_ctrl_symbols - 2) * SRSLTE_NRE;
re = (SRSLTE_CP_NSYMB(cp_) - nof_ctrl_symbols - 2) * SRSLTE_NRE;
}
}
if ((nof_prb % 2)
@ -77,7 +81,7 @@ uint32_t ra_re_x_prb(uint32_t subframe, uint32_t slot, uint32_t prb_idx, uint32_
re += 2 * SRSLTE_NRE / 2;
} else if (subframe == 0) {
re += 4 * SRSLTE_NRE / 2 - nof_ports;
if (SRSLTE_CP_ISEXT(cp)) {
if (SRSLTE_CP_ISEXT(cp_)) {
re -= nof_ports > 2 ? 2 : nof_ports;
}
}
@ -85,22 +89,27 @@ uint32_t ra_re_x_prb(uint32_t subframe, uint32_t slot, uint32_t prb_idx, uint32_
}
// remove references
if (!skip_refs) {
switch (nof_ports) {
case 1:
case 2:
re -= 2 * (slot + 1) * nof_ports;
break;
case 4:
if (slot == 1) {
re -= 12;
} else {
re -= 4;
if (nof_ctrl_symbols == 1) {
if (skip_refs) {
if(sf_type == SRSLTE_SF_NORM){
switch (nof_ports) {
case 1:
case 2:
re -= 2 * (slot + 1) * nof_ports;
break;
case 4:
if (slot == 1) {
re -= 12;
} else {
re -= 4;
if (nof_ctrl_symbols == 1) {
re -= 4;
}
}
break;
}
break;
}
if(sf_type == SRSLTE_SF_MBSFN){
re -= 6*(slot + 1);
}
}
return re;
@ -278,23 +287,23 @@ uint32_t srslte_ra_dl_approx_nof_re(srslte_cell_t cell, uint32_t nof_prb, uint32
/* Computes the number of RE for each PRB in the prb_dist structure */
uint32_t srslte_ra_dl_grant_nof_re(srslte_ra_dl_grant_t *grant, srslte_cell_t cell,
uint32_t sf_idx, uint32_t nof_ctrl_symbols)
uint32_t sf_idx, uint32_t nof_ctrl_symbols)
{
uint32_t j, s;
// Compute number of RE per PRB
uint32_t nof_re = 0;
for (s = 0; s < 2; s++) {
for (j = 0; j < cell.nof_prb; j++) {
if (grant->prb_idx[s][j]) {
nof_re += ra_re_x_prb(sf_idx, s, j,
cell.nof_prb, cell.nof_ports, nof_ctrl_symbols, cell.cp);
nof_re += ra_re_x_prb(sf_idx, s, j, cell.nof_prb, cell.nof_ports,
nof_ctrl_symbols, cell.cp, grant->sf_type);
}
}
}
}
return nof_re;
}
/** Compute PRB allocation for Downlink as defined in 7.1.6 of 36.213
* Decode dci->type?_alloc to grant
* This function only reads dci->type?_alloc and dci->alloc_type fields.
@ -432,7 +441,7 @@ int srslte_ra_dl_dci_to_grant_prb_allocation(srslte_ra_dl_dci_t *dci, srslte_ra_
return SRSLTE_SUCCESS;
}
int dl_fill_ra_mcs(srslte_ra_mcs_t *mcs, uint32_t nprb) {
int srslte_dl_fill_ra_mcs(srslte_ra_mcs_t *mcs, uint32_t nprb) {
uint32_t i_tbs = 0;
int tbs = -1;
if (mcs->idx < 10) {
@ -466,6 +475,52 @@ int dl_fill_ra_mcs(srslte_ra_mcs_t *mcs, uint32_t nprb) {
return tbs;
}
int srslte_dl_fill_ra_mcs_pmch(srslte_ra_mcs_t *mcs, uint32_t nprb) {
uint32_t i_tbs = 0;
int tbs = -1;
if (mcs->idx < 5) {
mcs->mod = SRSLTE_MOD_QPSK;
i_tbs = mcs->idx*2;
}else if (mcs->idx < 6) {
mcs->mod = SRSLTE_MOD_16QAM;
i_tbs = mcs->idx*2;
}else if (mcs->idx < 11) {
mcs->mod = SRSLTE_MOD_16QAM;
i_tbs = mcs->idx + 5;
}else if (mcs->idx < 20) {
mcs->mod = SRSLTE_MOD_64QAM;
i_tbs = mcs->idx + 5;
}else if (mcs->idx < 28) {
//mcs->mod = SRSLTE_MOD_256QAM;
i_tbs = mcs->idx + 5;
}else if (mcs->idx == 28) {
mcs->mod = SRSLTE_MOD_QPSK;
tbs = 0;
i_tbs = 0;
}else if (mcs->idx == 29) {
mcs->mod = SRSLTE_MOD_16QAM;
tbs = 0;
i_tbs = 0;
}else if (mcs->idx == 30) {
mcs->mod = SRSLTE_MOD_64QAM;
tbs = 0;
i_tbs = 0;
}else if (mcs->idx == 31) {
mcs->mod = SRSLTE_MOD_64QAM;
tbs = 0;
i_tbs = 0;
}
if (tbs == -1) {
tbs = srslte_ra_tbs_from_idx(i_tbs, nprb);
if (tbs >= 0) {
mcs->tbs = tbs;
}
}
return tbs;
}
/* Modulation order and transport block size determination 7.1.7 in 36.213
* This looks at DCI type, type of RNTI and reads fields dci->type?_alloc, dci->mcs_idx,
* dci->dci_is_1a and dci->dci_is_1c
@ -496,21 +551,23 @@ static int dl_dci_to_grant_mcs(srslte_ra_dl_dci_t *dci, srslte_ra_dl_grant_t *gr
grant->mcs[0].tbs = (uint32_t) tbs;
} else {
n_prb = grant->nof_prb;
grant->nof_tb = 0;
if (dci->tb_en[0]) {
grant->mcs[0].idx = dci->mcs_idx;
tbs = dl_fill_ra_mcs(&grant->mcs[0], n_prb);
tbs = srslte_dl_fill_ra_mcs(&grant->mcs[0], n_prb);
if (tbs) {
last_dl_tbs[dci->harq_process%8] = tbs;
} else {
// For mcs>=29, set last TBS received for this PID
grant->mcs[0].tbs = last_dl_tbs[dci->harq_process%8];
}
grant->nof_tb++;
} else {
grant->mcs[0].tbs = 0;
}
if (dci->tb_en[1]) {
grant->mcs[1].idx = dci->mcs_idx_1;
tbs = dl_fill_ra_mcs(&grant->mcs[1], n_prb);
tbs = srslte_dl_fill_ra_mcs(&grant->mcs[1], n_prb);
if (tbs) {
last_dl_tbs2[dci->harq_process%8] = tbs;
} else {
@ -545,7 +602,11 @@ void srslte_ra_dl_grant_to_nbits(srslte_ra_dl_grant_t *grant, uint32_t cfi, srsl
/* Compute number of RE for first transport block */
nbits[i].nof_re = srslte_ra_dl_grant_nof_re(grant, cell, sf_idx, cell.nof_prb < 10 ? (cfi + 1) : cfi);
nbits[i].lstart = cell.nof_prb < 10 ? (cfi + 1) : cfi;
nbits[i].nof_symb = 2 * SRSLTE_CP_NSYMB(cell.cp) - nbits[0].lstart;
if (SRSLTE_SF_NORM == grant->sf_type) {
nbits[i].nof_symb = 2 * SRSLTE_CP_NSYMB(cell.cp) - nbits[0].lstart;
} else if (SRSLTE_SF_MBSFN == grant->sf_type) {
nbits[i].nof_symb = 2 * SRSLTE_CP_EXT_NSYMB - nbits[0].lstart;
}
nbits[i].nof_bits = nbits[i].nof_re * grant->Qm[i];
}
}
@ -554,7 +615,8 @@ void srslte_ra_dl_grant_to_nbits(srslte_ra_dl_grant_t *grant, uint32_t cfi, srsl
/** Obtains a DL grant from a DCI grant for PDSCH */
int srslte_ra_dl_dci_to_grant(srslte_ra_dl_dci_t *dci,
uint32_t nof_prb, uint16_t msg_rnti, srslte_ra_dl_grant_t *grant)
{
{
grant->sf_type = SRSLTE_SF_NORM;
bool crc_is_crnti = false;
if (msg_rnti >= SRSLTE_CRNTI_START && msg_rnti <= SRSLTE_CRNTI_END) {
crc_is_crnti = true;
@ -844,6 +906,4 @@ void srslte_ra_prb_fprint(FILE *f, srslte_ra_dl_grant_t *grant) {
}
}
}
}

View File

@ -32,12 +32,7 @@
#include <stdbool.h>
#include <assert.h>
#include <math.h>
#include "srslte/phy/phch/pdsch.h"
#include "srslte/phy/phch/pusch.h"
#include "srslte/phy/phch/sch.h"
#include "srslte/phy/phch/uci.h"
#include "srslte/phy/common/phy_common.h"
#include "srslte/phy/utils/bit.h"
#include "srslte/phy/utils/debug.h"
#include "srslte/phy/utils/vector.h"
@ -174,15 +169,10 @@ void srslte_sch_set_max_noi(srslte_sch_t *q, uint32_t max_iterations) {
q->max_iterations = max_iterations;
}
float srslte_sch_average_noi(srslte_sch_t *q) {
return q->average_nof_iterations;
}
uint32_t srslte_sch_last_noi(srslte_sch_t *q) {
return q->nof_iterations;
}
/* Encode a transport block according to 36.212 5.3.2
*
*/
@ -320,8 +310,8 @@ bool decode_tb_cb(srslte_sch_t *q,
bool cb_map[SRSLTE_MAX_CODEBLOCKS];
uint32_t cb_idx[SRSLTE_TDEC_NPAR];
int16_t *decoder_input[SRSLTE_TDEC_NPAR];
uint32_t cb_idx[SRSLTE_TDEC_MAX_NPAR];
int16_t *decoder_input[SRSLTE_TDEC_MAX_NPAR];
uint32_t nof_cb = cb_size_group?cb_segm->C2:cb_segm->C1;
uint32_t first_cb = cb_size_group?cb_segm->C1:0;
@ -338,9 +328,9 @@ bool decode_tb_cb(srslte_sch_t *q,
return false;
}
for (int i=0;i<SRSLTE_TDEC_NPAR;i++) {
for (int i=0;i<srslte_tdec_get_nof_parallel(&q->decoder);i++) {
cb_idx[i] = i+first_cb;
decoder_input[i] = false;
decoder_input[i] = NULL;
}
for (int i=0;i<nof_cb;i++) {
@ -349,12 +339,14 @@ bool decode_tb_cb(srslte_sch_t *q,
srslte_tdec_reset(&q->decoder, cb_len);
uint32_t remaining_cb = nof_cb;
uint32_t remaining_cb = nof_cb;
q->nof_iterations = 0;
while(remaining_cb>0) {
// Unratematch the codeblocks left to decode
for (int i=0;i<SRSLTE_TDEC_NPAR;i++) {
for (int i=0;i<srslte_tdec_get_nof_parallel(&q->decoder);i++) {
if (!decoder_input[i] && remaining_cb > 0) {
// Find an unprocessed CB
@ -372,25 +364,23 @@ bool decode_tb_cb(srslte_sch_t *q,
n_e2 = n_e+Qm;
rp = (cb_segm->C - gamma)*n_e + (cb_idx[i]-(cb_segm->C - gamma))*n_e2;
}
INFO("CB %d: rp=%d, n_e=%d, i=%d\n", cb_idx[i], rp, n_e2, i);
if (srslte_rm_turbo_rx_lut(&e_bits[rp], softbuffer->buffer_f[cb_idx[i]], n_e2, cb_len_idx, rv)) {
fprintf(stderr, "Error in rate matching\n");
return SRSLTE_ERROR;
}
decoder_input[i] = softbuffer->buffer_f[cb_idx[i]];
decoder_input[i] = softbuffer->buffer_f[cb_idx[i]];
}
}
}
// Run 1 iteration for up to TDEC_NPAR codeblocks
// Run 1 iteration for the codeblocks in queue
srslte_tdec_iteration_par(&q->decoder, decoder_input, cb_len);
q->nof_iterations = srslte_tdec_get_nof_iterations_cb(&q->decoder, 0);
// Decide output bits and compute CRC
for (int i=0;i<SRSLTE_TDEC_NPAR;i++) {
for (int i=0;i<srslte_tdec_get_nof_parallel(&q->decoder);i++) {
if (decoder_input[i]) {
srslte_tdec_decision_byte_par_cb(&q->decoder, q->cb_in, i, cb_len);
@ -409,24 +399,30 @@ bool decode_tb_cb(srslte_sch_t *q,
if (!srslte_crc_checksum_byte(crc_ptr, q->cb_in, len_crc)) {
memcpy(&data[(cb_idx[i]*rlen)/8], q->cb_in, rlen/8 * sizeof(uint8_t));
q->nof_iterations += srslte_tdec_get_nof_iterations_cb(&q->decoder, i);
// Reset number of iterations for that CB in the decoder
srslte_tdec_reset_cb(&q->decoder, i);
remaining_cb--;
decoder_input[i] = NULL;
cb_idx[i] = 0;
// CRC is error and exceeded maximum iterations for this CB.
// CRC is error and exceeded maximum iterations for this CB.
// Early stop the whole transport block.
} else if (srslte_tdec_get_nof_iterations_cb(&q->decoder, i) >= q->max_iterations) {
INFO("CB %d: Error. CB is erroneous. remaining_cb=%d, i=%d, first_cb=%d, nof_cb=%d\n",
cb_idx[i], remaining_cb, i, first_cb, nof_cb);
return false;
cb_idx[i], remaining_cb, i, first_cb, nof_cb);
q->nof_iterations += q->max_iterations;
q->nof_iterations /= (nof_cb-remaining_cb+1);
return false;
}
}
}
}
q->nof_iterations /= nof_cb;
return true;
}
@ -478,7 +474,7 @@ static int decode_tb(srslte_sch_t *q,
data[cb_segm->tbs/8+1] = 0;
data[cb_segm->tbs/8+2] = 0;
// Process Codeblocks in groups of equal CB size to parallelize according to SRSLTE_TDEC_NPAR
// Process Codeblocks in groups of equal CB size to parallelize according to SRSLTE_TDEC_MAX_NPAR
for (uint32_t i=0;i<nof_cb_groups && crc_ok;i++) {
crc_ok = decode_tb_cb(q, softbuffer, cb_segm, Qm, rv, nof_e_bits, e_bits, data, i);
}

View File

@ -78,3 +78,9 @@ int srslte_sequence_pusch(srslte_sequence_t *seq, uint16_t rnti, uint32_t nslot,
int srslte_sequence_pucch(srslte_sequence_t *seq, uint16_t rnti, uint32_t nslot, uint32_t cell_id) {
return srslte_sequence_LTE_pr(seq, 20, ((((nslot/2)+1)*(2*cell_id+1))<<16)+rnti);
}
int srslte_sequence_pmch(srslte_sequence_t *seq, uint32_t nslot, uint32_t mbsfn_id , uint32_t len){
bzero(seq,sizeof(srslte_sequence_t));
return srslte_sequence_LTE_pr(seq, len, (((nslot/2)<<9) + mbsfn_id));
}

View File

@ -460,6 +460,10 @@ int main(int argc, char **argv) {
srslte_softbuffer_rx_reset_tbs(softbuffers_rx[i], (uint32_t) grant.mcs[i].tbs);
}
}
/* Set ACKs to zero, otherwise will not decode if there are positive ACKs*/
bzero(acks, sizeof(acks));
r = srslte_pdsch_decode(&pdsch_rx, &pdsch_cfg, softbuffers_rx, rx_slot_symbols, ce, 0, rnti, data_rx, acks);
}
gettimeofday(&t[2], NULL);

View File

@ -263,7 +263,7 @@ int main(int argc, char **argv) {
for (ngroup=0;ngroup<srslte_phich_ngroups(&phich);ngroup++) {
for (nseq=0;nseq<max_nseq;nseq++) {
if (srslte_phich_decode(&phich, fft_buffer, ce, srslte_chest_dl_get_noise_estimate(&chest), ngroup, nseq, numsubframe, &ack_rx, &distance)<0) {
if (srslte_phich_decode(&phich, &fft_buffer, &ce, srslte_chest_dl_get_noise_estimate(&chest), ngroup, nseq, numsubframe, &ack_rx, &distance)<0) {
printf("Error decoding ACK\n");
exit(-1);
}

View File

@ -103,7 +103,7 @@ int main(int argc, char **argv) {
srslte_phich_t phich;
srslte_regs_t regs;
int i, j;
cf_t *ce[SRSLTE_MAX_PORTS];
cf_t *ce[SRSLTE_MAX_PORTS][SRSLTE_MAX_PORTS];
int nof_re;
cf_t *slot_symbols[SRSLTE_MAX_PORTS];
uint8_t ack[50][SRSLTE_PHICH_NORM_NSEQUENCES], ack_rx;
@ -120,13 +120,15 @@ int main(int argc, char **argv) {
/* init memory */
for (i=0;i<SRSLTE_MAX_PORTS;i++) {
ce[i] = malloc(sizeof(cf_t) * nof_re);
if (!ce[i]) {
perror("malloc");
exit(-1);
}
for (j=0;j<nof_re;j++) {
ce[i][j] = 1;
for (int k=0;k<SRSLTE_MAX_PORTS;k++) {
ce[k][i] = malloc(sizeof(cf_t) * nof_re);
if (!ce[k][i]) {
perror("malloc");
exit(-1);
}
for (j = 0; j < nof_re; j++) {
ce[k][i][j] = 1;
}
}
slot_symbols[i] = malloc(sizeof(cf_t) * nof_re);
if (!slot_symbols[i]) {
@ -185,7 +187,7 @@ int main(int argc, char **argv) {
for (ngroup=0;ngroup<srslte_phich_ngroups(&phich);ngroup++) {
for (nseq=0;nseq<max_nseq;nseq++) {
if (srslte_phich_decode(&phich, slot_symbols[0], ce, 0, ngroup, nseq, nsf, &ack_rx, &distance)<0) {
if (srslte_phich_decode(&phich, slot_symbols, ce, 0, ngroup, nseq, nsf, &ack_rx, &distance)<0) {
printf("Error decoding ACK\n");
exit(-1);
}
@ -208,7 +210,9 @@ int main(int argc, char **argv) {
srslte_phich_free(&phich);
for (i=0;i<SRSLTE_MAX_PORTS;i++) {
free(ce[i]);
for (j = 0; j < SRSLTE_MAX_PORTS; j++) {
free(ce[i][j]);
}
free(slot_symbols[i]);
}
printf("OK\n");

View File

@ -190,7 +190,7 @@ int main(int argc, char **argv) {
bzero(&uci_data_tx, sizeof(srslte_uci_data_t));
uci_data_tx.uci_cqi_len = 4;
uci_data_tx.uci_ri_len = 0;
uci_data_tx.uci_ack_len = 2;
uci_data_tx.uci_ack_len = 1;
memcpy(&uci_data_rx, &uci_data_tx, sizeof(srslte_uci_data_t));
for (uint32_t i=0;i<20;i++) {

View File

@ -581,7 +581,49 @@ static uint32_t encode_ri_ack(uint8_t data[2], uint32_t data_len, srslte_uci_bit
return i;
}
/* Decode UCI HARQ/ACK bits as described in 5.2.2.6 of 36.212
* Currently only supporting 1-bit HARQ
*/
#ifndef MIMO_ENB
static int32_t decode_ri_ack(int16_t *q_bits, uint8_t *c_seq, srslte_uci_bit_t *pos)
{
uint32_t p0 = pos[0].position;
uint32_t p1 = pos[1].position;
uint32_t q0 = c_seq[p0]?q_bits[p0]:-q_bits[p0];
uint32_t q1 = c_seq[p0]?q_bits[p1]:-q_bits[p1];
return -(q0+q1);
}
int srslte_uci_decode_ack(srslte_pusch_cfg_t *cfg, int16_t *q_bits, uint8_t *c_seq,
float beta, uint32_t H_prime_total,
uint32_t O_cqi, srslte_uci_bit_t *ack_bits, uint8_t acks[2], uint32_t nof_acks)
{
int32_t rx_ack = 0;
if (beta < 0) {
fprintf(stderr, "Error beta is reserved\n");
return -1;
}
uint32_t Qprime = Q_prime_ri_ack(cfg, 1, O_cqi, beta);
// Use the same interleaver function to get the HARQ bit position
for (uint32_t i=0;i<Qprime;i++) {
uci_ulsch_interleave_ack_gen(i, cfg->grant.Qm, H_prime_total, cfg->nbits.nof_symb, cfg->cp, &ack_bits[cfg->grant.Qm*i]);
rx_ack += (int32_t) decode_ri_ack(q_bits, c_seq, &ack_bits[cfg->grant.Qm*i]);
}
if (acks) {
acks[0] = rx_ack>0;
}
return (int) Qprime;
}
#else
static void decode_ri_ack(int16_t *q_bits, uint8_t *c_seq, srslte_uci_bit_t *pos, uint32_t Qm, int32_t data[3])
{
uint32_t p0 = pos[Qm * 0 + 0].position;
@ -603,10 +645,6 @@ static void decode_ri_ack(int16_t *q_bits, uint8_t *c_seq, srslte_uci_bit_t *pos
data[2] -= q2 + q5;
}
/* Decode UCI HARQ/ACK bits as described in 5.2.2.6 of 36.212
* Currently only supporting 1-bit HARQ
*/
int srslte_uci_decode_ack(srslte_pusch_cfg_t *cfg, int16_t *q_bits, uint8_t *c_seq,
float beta, uint32_t H_prime_total,
uint32_t O_cqi, srslte_uci_bit_t *ack_bits, uint8_t acks[2], uint32_t nof_acks)
@ -635,6 +673,7 @@ int srslte_uci_decode_ack(srslte_pusch_cfg_t *cfg, int16_t *q_bits, uint8_t *c_s
}
return (int) Qprime;
}
#endif
/* Encode UCI HARQ/ACK bits as described in 5.2.2.6 of 36.212
* Currently only supporting 1-bit HARQ
@ -681,7 +720,7 @@ int srslte_uci_decode_ri(srslte_pusch_cfg_t *cfg, int16_t *q_bits, uint8_t *c_se
for (uint32_t i=0;i<Qprime;i++) {
uci_ulsch_interleave_ri_gen(i, cfg->grant.Qm, H_prime_total, cfg->nbits.nof_symb, cfg->cp, &ri_bits[cfg->grant.Qm*i]);
if ((i % 3 == 0) && i > 0) {
decode_ri_ack(q_bits, &c_seq[0], &ri_bits[cfg->grant.Qm*(i-3)], cfg->grant.Qm, ri_sum);
//decode_ri_ack(q_bits, &c_seq[0], &ri_bits[cfg->grant.Qm*(i-3)], cfg->grant.Qm, ri_sum);
}
}

View File

@ -76,9 +76,10 @@ static void log_overflow(rf_uhd_handler_t *h) {
}
}
static void log_late(rf_uhd_handler_t *h) {
static void log_late(rf_uhd_handler_t *h, bool is_rx) {
if (h->uhd_error_handler) {
srslte_rf_error_t error;
srslte_rf_error_t error;
error.opt = is_rx?1:0;
bzero(&error, sizeof(srslte_rf_error_t));
error.type = SRSLTE_RF_ERROR_LATE;
h->uhd_error_handler(error);
@ -109,7 +110,7 @@ static void* async_thread(void *h) {
event_code == UHD_ASYNC_METADATA_EVENT_CODE_UNDERFLOW_IN_PACKET) {
log_underflow(handler);
} else if (event_code == UHD_ASYNC_METADATA_EVENT_CODE_TIME_ERROR) {
log_late(handler);
log_late(handler, false);
}
}
} else {
@ -290,6 +291,13 @@ int rf_uhd_open(char *args, void **h)
return rf_uhd_open_multi(args, h, 1);
}
static void remove_substring(char *s,const char *toremove)
{
while((s=strstr(s,toremove))) {
memmove(s,s+strlen(toremove),1+strlen(s+strlen(toremove)));
}
}
int rf_uhd_open_multi(char *args, void **h, uint32_t nof_channels)
{
if (h) {
@ -324,7 +332,31 @@ int rf_uhd_open_multi(char *args, void **h, uint32_t nof_channels)
handler->uhd_error_handler = NULL;
bzero(zero_mem, sizeof(cf_t)*64*1024);
// Check external clock argument
enum {DEFAULT, EXTERNAL, GPSDO} clock_src;
if (strstr(args, "clock=external")) {
remove_substring(args, "clock=external");
clock_src = EXTERNAL;
} else if (strstr(args, "clock=gpsdo")) {
printf("Using GPSDO clock\n");
remove_substring(args, "clock=gpsdo");
clock_src = GPSDO;
} else {
clock_src = DEFAULT;
}
// Set over the wire format
char *otw_format = "sc16";
if (strstr(args, "otw_format=sc12")) {
otw_format = "sc12";
} else if (strstr(args, "otw_format=sc16")) {
/* Do nothing */
} else if (strstr(args, "otw_format=")) {
fprintf(stderr, "Wrong over the wire format. Valid formats: sc12, sc16\n");
return -1;
}
/* If device type or name not given in args, choose a B200 */
if (args[0]=='\0') {
if (find_string(devices_str, "type=b200") && !strstr(args, "recv_frame_size")) {
@ -379,15 +411,13 @@ int rf_uhd_open_multi(char *args, void **h, uint32_t nof_channels)
}
// Set external clock reference
if (strstr(args, "clock=external")) {
if (clock_src == EXTERNAL) {
uhd_usrp_set_clock_source(handler->usrp, "external", 0);
} else if (strstr(args, "clock=gpsdo")) {
printf("Using GPSDO clock\n");
uhd_usrp_set_clock_source(handler->usrp, "gpsdo", 0);
} else if (clock_src == GPSDO) {
uhd_usrp_set_clock_source(handler->usrp, "gpsdo", 0);
}
handler->has_rssi = get_has_rssi(handler);
handler->has_rssi = get_has_rssi(handler);
if (handler->has_rssi) {
uhd_sensor_value_make_from_realnum(&handler->rssi_value, "rssi", 0, "dBm", "%f");
}
@ -395,7 +425,7 @@ int rf_uhd_open_multi(char *args, void **h, uint32_t nof_channels)
size_t channel[4] = {0, 1, 2, 3};
uhd_stream_args_t stream_args = {
.cpu_format = "fc32",
.otw_format = "sc16",
.otw_format = otw_format,
.args = "",
.channel_list = channel,
.n_channels = nof_channels,
@ -405,9 +435,11 @@ int rf_uhd_open_multi(char *args, void **h, uint32_t nof_channels)
handler->nof_tx_channels = nof_channels;
/* Set default rate to avoid decimation warnings */
uhd_usrp_set_rx_rate(handler->usrp, 1.92e6, 0);
uhd_usrp_set_tx_rate(handler->usrp, 1.92e6, 0);
for (int i=0;i<nof_channels;i++) {
uhd_usrp_set_rx_rate(handler->usrp, 1.92e6, i);
uhd_usrp_set_tx_rate(handler->usrp, 1.92e6, i);
}
/* Initialize rx and tx stremers */
uhd_rx_streamer_make(&handler->rx_stream);
error = uhd_usrp_get_rx_stream(handler->usrp, &stream_args, handler->rx_stream);
@ -626,9 +658,10 @@ int rf_uhd_recv_with_time_multi(void *h,
if (error_code == UHD_RX_METADATA_ERROR_CODE_OVERFLOW) {
log_overflow(handler);
} else if (error_code == UHD_RX_METADATA_ERROR_CODE_LATE_COMMAND) {
log_late(handler);
log_late(handler, true);
} else if (error_code == UHD_RX_METADATA_ERROR_CODE_TIMEOUT) {
fprintf(stderr, "Error timed out while receiving asynchronoous messages from UHD.\n");
fprintf(stderr, "Error timed out while receiving samples from UHD.\n");
return -1;
} else if (error_code != UHD_RX_METADATA_ERROR_CODE_NONE ) {
fprintf(stderr, "Error code 0x%x was returned during streaming. Aborting.\n", error_code);
}
@ -677,11 +710,11 @@ int rf_uhd_send_timed_multi(void *h,
}
size_t txd_samples;
if (has_time_spec) {
uhd_tx_metadata_set_time_spec(&handler->tx_md, secs, frac_secs);
}
int trials = 0;
int trials = 0;
if (blocking) {
if (has_time_spec) {
uhd_tx_metadata_set_time_spec(&handler->tx_md, secs, frac_secs);
}
int n = 0;
cf_t *data_c[4];
for (int i = 0; i < 4; i++) {
@ -689,8 +722,8 @@ int rf_uhd_send_timed_multi(void *h,
}
do {
size_t tx_samples = handler->tx_nof_samples;
// First packet is start of burst if so defined, others are never
// First packet is start of burst if so defined, others are never
if (n == 0) {
uhd_tx_metadata_set_start(&handler->tx_md, is_start_of_burst);
} else {
@ -727,9 +760,15 @@ int rf_uhd_send_timed_multi(void *h,
for (int i = 0; i < 4; i++) {
buffs_ptr[i] = data[i];
}
uhd_tx_metadata_set_has_time_spec(&handler->tx_md, is_start_of_burst);
uhd_tx_metadata_set_start(&handler->tx_md, is_start_of_burst);
uhd_tx_metadata_set_end(&handler->tx_md, is_end_of_burst);
return uhd_tx_streamer_send(handler->tx_stream, buffs_ptr, nsamples, &handler->tx_md, 0.0, &txd_samples);
uhd_error error = uhd_tx_streamer_send(handler->tx_stream, buffs_ptr, nsamples, &handler->tx_md, 3.0, &txd_samples);
if (error) {
fprintf(stderr, "Error sending to UHD: %d\n", error);
return -1;
}
return txd_samples;
}
}

View File

@ -38,6 +38,12 @@ void uhd_tx_metadata_set_start(uhd_tx_metadata_handle *md, bool is_start_of_burs
(*md)->tx_metadata_cpp.start_of_burst = is_start_of_burst;
}
void uhd_tx_metadata_set_has_time_spec(uhd_tx_metadata_handle *md, bool has_time_spec)
{
(*md)->tx_metadata_cpp.has_time_spec = has_time_spec;
}
void uhd_tx_metadata_set_end(uhd_tx_metadata_handle *md, bool is_end_of_burst)
{
(*md)->tx_metadata_cpp.end_of_burst = is_end_of_burst;

View File

@ -32,5 +32,6 @@
SRSLTE_API void rf_uhd_register_msg_handler_c(void (*new_handler)(const char*));
SRSLTE_API void uhd_tx_metadata_set_time_spec(uhd_tx_metadata_handle *md, time_t secs, double frac_secs);
SRSLTE_API void uhd_tx_metadata_set_start(uhd_tx_metadata_handle *md, bool is_start_of_burst);
SRSLTE_API void uhd_tx_metadata_set_has_time_spec(uhd_tx_metadata_handle *md, bool has_time_spec);
SRSLTE_API void uhd_tx_metadata_set_end(uhd_tx_metadata_handle *md, bool is_end_of_burst);
SRSLTE_API void uhd_tx_metadata_add_time_spec(uhd_tx_metadata_handle *md, double frac_secs);

View File

@ -297,7 +297,7 @@ int srslte_ue_cellsearch_scan_N_id_2(srslte_ue_cellsearch_t * q,
ret = srslte_ue_sync_zerocopy_multi(&q->ue_sync, q->sf_buffer);
if (ret < 0) {
fprintf(stderr, "Error calling srslte_ue_sync_work()\n");
break;
return -1;
} else if (ret == 1) {
/* This means a peak was found and ue_sync is now in tracking state */
ret = srslte_sync_get_cell_id(&q->ue_sync.strack);

View File

@ -64,9 +64,11 @@ int srslte_ue_dl_init(srslte_ue_dl_t *q,
ret = SRSLTE_ERROR;
bzero(q, sizeof(srslte_ue_dl_t));
q->pkt_errors = 0;
q->pkts_total = 0;
q->pdsch_pkt_errors = 0;
q->pdsch_pkts_total = 0;
q->pmch_pkt_errors = 0;
q->pmch_pkts_total = 0;
q->pending_ul_dci_rnti = 0;
q->sample_offset = 0;
q->nof_rx_antennas = nof_rx_antennas;
@ -75,6 +77,13 @@ int srslte_ue_dl_init(srslte_ue_dl_t *q,
fprintf(stderr, "Error initiating FFT\n");
goto clean_exit;
}
if (srslte_ofdm_rx_init_mbsfn(&q->fft_mbsfn, SRSLTE_CP_EXT, max_prb)) {
fprintf(stderr, "Error initiating FFT for MBSFN subframes \n");
goto clean_exit;
}
srslte_ofdm_set_non_mbsfn_region(&q->fft_mbsfn, 2); // Set a default to init
if (srslte_chest_dl_init(&q->chest, max_prb)) {
fprintf(stderr, "Error initiating channel estimator\n");
goto clean_exit;
@ -97,6 +106,11 @@ int srslte_ue_dl_init(srslte_ue_dl_t *q,
fprintf(stderr, "Error creating PDSCH object\n");
goto clean_exit;
}
if (srslte_pmch_init_multi(&q->pmch, max_prb, nof_rx_antennas)) {
fprintf(stderr, "Error creating PMCH object\n");
goto clean_exit;
}
for (int i = 0; i < SRSLTE_MAX_TB; i++) {
q->softbuffers[i] = srslte_vec_malloc(sizeof(srslte_softbuffer_rx_t));
if (!q->softbuffers[i]) {
@ -115,7 +129,7 @@ int srslte_ue_dl_init(srslte_ue_dl_t *q,
}
srslte_cfo_set_tol(&q->sfo_correct, 1e-5f/q->fft.symbol_sz);
for (int j=0;j<nof_rx_antennas;j++) {
for (int j = 0; j < SRSLTE_MAX_PORTS; j++) {
q->sf_symbols_m[j] = srslte_vec_malloc(MAX_SFLEN_RE * sizeof(cf_t));
if (!q->sf_symbols_m[j]) {
perror("malloc");
@ -127,6 +141,7 @@ int srslte_ue_dl_init(srslte_ue_dl_t *q,
perror("malloc");
goto clean_exit;
}
bzero(q->ce_m[i][j], MAX_SFLEN_RE * sizeof(cf_t));
}
}
@ -150,12 +165,14 @@ clean_exit:
void srslte_ue_dl_free(srslte_ue_dl_t *q) {
if (q) {
srslte_ofdm_rx_free(&q->fft);
srslte_ofdm_rx_free(&q->fft_mbsfn);
srslte_chest_dl_free(&q->chest);
srslte_regs_free(&q->regs);
srslte_pcfich_free(&q->pcfich);
srslte_phich_free(&q->phich);
srslte_pdcch_free(&q->pdcch);
srslte_pdsch_free(&q->pdsch);
srslte_pmch_free(&q->pmch);
srslte_cfo_free(&q->sfo_correct);
for (int i = 0; i < SRSLTE_MAX_TB; i++) {
srslte_softbuffer_rx_free(q->softbuffers[i]);
@ -163,7 +180,7 @@ void srslte_ue_dl_free(srslte_ue_dl_t *q) {
free(q->softbuffers[i]);
}
}
for (int j=0;j<q->nof_rx_antennas;j++) {
for (int j = 0; j < SRSLTE_MAX_PORTS; j++) {
if (q->sf_symbols_m[j]) {
free(q->sf_symbols_m[j]);
}
@ -257,6 +274,34 @@ void srslte_ue_dl_set_rnti(srslte_ue_dl_t *q, uint16_t rnti) {
q->current_rnti = rnti;
}
/* Set the area ID on pmch and chest_dl to generate scrambling sequence and reference
* signals.
*/
int srslte_ue_dl_set_mbsfn_area_id(srslte_ue_dl_t *q,
uint16_t mbsfn_area_id) {
int ret = SRSLTE_ERROR_INVALID_INPUTS;
if(q != NULL) {
ret = SRSLTE_ERROR;
if(srslte_chest_dl_set_mbsfn_area_id(&q->chest, mbsfn_area_id)) {
fprintf(stderr, "Error setting MBSFN area ID \n");
return ret;
}
if(srslte_pmch_set_area_id(&q->pmch, mbsfn_area_id)) {
fprintf(stderr, "Error setting MBSFN area ID \n");
return ret;
}
q->current_mbsfn_area_id = mbsfn_area_id;
ret = SRSLTE_SUCCESS;
}
return ret;
}
void srslte_ue_dl_set_non_mbsfn_region(srslte_ue_dl_t *q,
uint8_t non_mbsfn_region_length) {
srslte_ofdm_set_non_mbsfn_region(&q->fft_mbsfn, non_mbsfn_region_length);
}
void srslte_ue_dl_reset(srslte_ue_dl_t *q) {
for(int i = 0; i < SRSLTE_MAX_CODEWORDS; i++){
@ -278,39 +323,60 @@ void srslte_ue_dl_set_sample_offset(srslte_ue_dl_t * q, float sample_offset) {
*/
int srslte_ue_dl_decode(srslte_ue_dl_t *q, cf_t *input[SRSLTE_MAX_PORTS], uint8_t *data[SRSLTE_MAX_CODEWORDS],
uint32_t tm, uint32_t tti, bool acks[SRSLTE_MAX_CODEWORDS]) {
return srslte_ue_dl_decode_rnti(q, input, data, tm, tti, q->current_rnti, acks);
return srslte_ue_dl_decode_rnti(q, input, data, tm, tti, q->current_rnti, acks);
}
int srslte_ue_dl_decode_fft_estimate(srslte_ue_dl_t *q, cf_t *input[SRSLTE_MAX_PORTS], uint32_t sf_idx, uint32_t *cfi)
int srslte_ue_dl_decode_fft_estimate(srslte_ue_dl_t *q, cf_t *input[SRSLTE_MAX_PORTS], uint32_t sf_idx, uint32_t *cfi){
return srslte_ue_dl_decode_fft_estimate_mbsfn(q, input, sf_idx, cfi, SRSLTE_SF_NORM);
}
int srslte_ue_dl_decode_fft_estimate_mbsfn(srslte_ue_dl_t *q, cf_t *input[SRSLTE_MAX_PORTS], uint32_t sf_idx, uint32_t *cfi, srslte_sf_t sf_type)
{
if (input && q && cfi && sf_idx < SRSLTE_NSUBFRAMES_X_FRAME) {
/* Run FFT for all subframe data */
for (int j=0;j<q->nof_rx_antennas;j++) {
srslte_ofdm_rx_sf(&q->fft, input[j], q->sf_symbols_m[j]);
if(sf_type == SRSLTE_SF_MBSFN ) {
srslte_ofdm_rx_sf(&q->fft_mbsfn, input[j], q->sf_symbols_m[j]);
}else{
srslte_ofdm_rx_sf(&q->fft, input[j], q->sf_symbols_m[j]);
}
/* Correct SFO multiplying by complex exponential in the time domain */
if (q->sample_offset) {
for (int i=0;i<2*SRSLTE_CP_NSYMB(q->cell.cp);i++) {
srslte_cfo_correct(&q->sfo_correct,
int nsym = (sf_type == SRSLTE_SF_MBSFN)?SRSLTE_CP_EXT_NSYMB:SRSLTE_CP_NSYMB(q->cell.cp);
for (int i=0;i<2*nsym;i++) {
srslte_cfo_correct(&q->sfo_correct,
&q->sf_symbols_m[j][i*q->cell.nof_prb*SRSLTE_NRE],
&q->sf_symbols_m[j][i*q->cell.nof_prb*SRSLTE_NRE],
q->sample_offset / q->fft.symbol_sz);
}
}
}
return srslte_ue_dl_decode_estimate(q, sf_idx, cfi);
return srslte_ue_dl_decode_estimate_mbsfn(q, sf_idx, cfi, sf_type);
} else {
return SRSLTE_ERROR_INVALID_INPUTS;
}
}
int srslte_ue_dl_decode_estimate(srslte_ue_dl_t *q, uint32_t sf_idx, uint32_t *cfi) {
return srslte_ue_dl_decode_estimate_mbsfn(q, sf_idx, cfi, SRSLTE_SF_NORM);
}
int srslte_ue_dl_decode_estimate_mbsfn(srslte_ue_dl_t *q, uint32_t sf_idx, uint32_t *cfi, srslte_sf_t sf_type) {
float cfi_corr;
if (q && cfi && sf_idx < SRSLTE_NSUBFRAMES_X_FRAME) {
/* Get channel estimates for each port */
srslte_chest_dl_estimate_multi(&q->chest, q->sf_symbols_m, q->ce_m, sf_idx, q->nof_rx_antennas);
if(sf_type == SRSLTE_SF_MBSFN){
srslte_chest_dl_estimate_multi_mbsfn(&q->chest, q->sf_symbols_m, q->ce_m, sf_idx, q->nof_rx_antennas, q->current_mbsfn_area_id);
}else{
srslte_chest_dl_estimate_multi(&q->chest, q->sf_symbols_m, q->ce_m, sf_idx, q->nof_rx_antennas);
}
/* First decode PCFICH and obtain CFI */
if (srslte_pcfich_decode_multi(&q->pcfich, q->sf_symbols_m, q->ce_m,
@ -357,7 +423,11 @@ int srslte_ue_dl_cfg_grant(srslte_ue_dl_t *q, srslte_ra_dl_grant_t *grant, uint3
}
}
}
return srslte_pdsch_cfg_mimo(&q->pdsch_cfg, q->cell, grant, cfi, sf_idx, rvidx, mimo_type, pmi);
if(SRSLTE_SF_MBSFN == grant->sf_type) {
return srslte_pmch_cfg(&q->pmch_cfg, q->cell, grant, cfi, sf_idx);
} else {
return srslte_pdsch_cfg_mimo(&q->pdsch_cfg, q->cell, grant, cfi, sf_idx, rvidx, mimo_type, pmi);
}
}
int srslte_ue_dl_decode_rnti(srslte_ue_dl_t *q, cf_t *input[SRSLTE_MAX_PORTS],
@ -371,7 +441,7 @@ int srslte_ue_dl_decode_rnti(srslte_ue_dl_t *q, cf_t *input[SRSLTE_MAX_PORTS],
uint32_t cfi;
uint32_t sf_idx = tti%10;
if ((ret = srslte_ue_dl_decode_fft_estimate(q, input, sf_idx, &cfi)) < 0) {
if ((ret = srslte_ue_dl_decode_fft_estimate_mbsfn(q, input, sf_idx, &cfi, SRSLTE_SF_NORM)) < 0) {
return ret;
}
@ -475,12 +545,13 @@ int srslte_ue_dl_decode_rnti(srslte_ue_dl_t *q, cf_t *input[SRSLTE_MAX_PORTS],
noise_estimate,
rnti, data, acks);
for (int tb = 0; tb < SRSLTE_MAX_TB; tb++) {
if (grant.tb_en[tb]) {
if (!acks[tb]) {
q->pkt_errors++;
q->pdsch_pkt_errors++;
}
q->pkts_total++;
q->pdsch_pkts_total++;
}
}
@ -509,6 +580,69 @@ int srslte_ue_dl_decode_rnti(srslte_ue_dl_t *q, cf_t *input[SRSLTE_MAX_PORTS],
}
}
int srslte_ue_dl_decode_mbsfn(srslte_ue_dl_t * q,
cf_t *input[SRSLTE_MAX_PORTS],
uint8_t *data,
uint32_t tti)
{
srslte_ra_dl_grant_t grant;
int ret = SRSLTE_ERROR;
uint32_t cfi;
uint32_t sf_idx = tti%10;
if ((ret = srslte_ue_dl_decode_fft_estimate_mbsfn(q, input, sf_idx, &cfi, SRSLTE_SF_MBSFN)) < 0) {
return ret;
}
float noise_estimate = srslte_chest_dl_get_noise_estimate(&q->chest);
// Uncoment next line to do ZF by default in pdsch_ue example
//float noise_estimate = 0;
grant.sf_type = SRSLTE_SF_MBSFN;
grant.nof_tb = 1;
grant.mcs[0].idx = 2;
grant.nof_prb = q->pmch.cell.nof_prb;
srslte_dl_fill_ra_mcs(&grant.mcs[0], grant.nof_prb);
srslte_softbuffer_rx_reset_tbs(q->softbuffers[0], (uint32_t) grant.mcs[0].tbs);
for(int j = 0; j < 2; j++){
for(int f = 0; f < grant.nof_prb; f++){
grant.prb_idx[j][f] = true;
}
}
grant.Qm[0] = srslte_mod_bits_x_symbol(grant.mcs[0].mod);
// redundancy version is set to 0 for the PMCH
if (srslte_ue_dl_cfg_grant(q, &grant, cfi, sf_idx, SRSLTE_PMCH_RV, SRSLTE_MIMO_TYPE_SINGLE_ANTENNA)) {
return SRSLTE_ERROR;
}
if (q->pmch_cfg.grant.mcs[0].mod > 0 && q->pmch_cfg.grant.mcs[0].tbs >= 0) {
ret = srslte_pmch_decode_multi(&q->pmch, &q->pmch_cfg, q->softbuffers[0],
q->sf_symbols_m, q->ce_m,
noise_estimate,
q->current_mbsfn_area_id, data);
if (ret == SRSLTE_ERROR) {
q->pmch_pkt_errors++;
} else if (ret == SRSLTE_ERROR_INVALID_INPUTS) {
fprintf(stderr, "Error calling srslte_pmch_decode()\n");
}
}
printf("q->pmch_pkts_total %d \n", q->pmch_pkts_total);
printf("qq->pmch_pkt_errors %d \n", q->pmch_pkt_errors);
q->pmch_pkts_total++;
if (ret == SRSLTE_SUCCESS) {
return q->pmch_cfg.grant.mcs[0].tbs;
} else {
return 0;
}
}
/* Compute the Rank Indicator (RI) and Precoder Matrix Indicator (PMI) by computing the Signal to Interference plus
* Noise Ratio (SINR), valid for TM4 */
int srslte_ue_dl_ri_pmi_select(srslte_ue_dl_t *q, uint8_t *ri, uint8_t *pmi, float *current_sinr) {
@ -516,10 +650,10 @@ int srslte_ue_dl_ri_pmi_select(srslte_ue_dl_t *q, uint8_t *ri, uint8_t *pmi, flo
float best_sinr = -INFINITY;
uint8_t best_pmi = 0, best_ri = 0;
if (q->cell.nof_ports < 2 || q->nof_rx_antennas < 2) {
if (q->cell.nof_ports < 2) {
/* Do nothing */
return SRSLTE_SUCCESS;
} else if (q->cell.nof_ports == 2 && q->nof_rx_antennas == 2) {
} else {
if (srslte_pdsch_pmi_select(&q->pdsch, &q->pdsch_cfg, q->ce_m, noise_estimate,
SRSLTE_SF_LEN_RE(q->cell.nof_prb, q->cell.cp), q->pmi, q->sinr)) {
ERROR("SINR calculation error");
@ -527,7 +661,7 @@ int srslte_ue_dl_ri_pmi_select(srslte_ue_dl_t *q, uint8_t *ri, uint8_t *pmi, flo
}
/* Select the best Rank indicator (RI) and Precoding Matrix Indicator (PMI) */
for (uint32_t nof_layers = 1; nof_layers <= 2; nof_layers++) {
for (uint32_t nof_layers = 1; nof_layers <= SRSLTE_MAX_LAYERS; nof_layers++) {
float _sinr = q->sinr[nof_layers - 1][q->pmi[nof_layers - 1]] * nof_layers * nof_layers;
if (_sinr > best_sinr + 0.1) {
best_sinr = _sinr;
@ -535,37 +669,34 @@ int srslte_ue_dl_ri_pmi_select(srslte_ue_dl_t *q, uint8_t *ri, uint8_t *pmi, flo
best_ri = (uint8_t) (nof_layers - 1);
}
}
}
/* Set RI */
if (ri != NULL) {
*ri = best_ri;
}
/* Print Trace */
if (ri != NULL && pmi != NULL && current_sinr != NULL) {
INFO("PDSCH Select RI=%d; PMI=%d; Current SINR=%.1fdB (nof_layers=%d, codebook_idx=%d)\n", *ri, *pmi,
10*log10(*current_sinr), q->pdsch_cfg.nof_layers, q->pdsch_cfg.codebook_idx);
}
/* Set PMI */
if (pmi != NULL) {
*pmi = best_pmi;
}
/* Set RI */
if (ri != NULL) {
*ri = best_ri;
}
/* Set current SINR */
if (current_sinr != NULL && q->pdsch_cfg.mimo_type == SRSLTE_MIMO_TYPE_SPATIAL_MULTIPLEX) {
if (q->pdsch_cfg.nof_layers == 1) {
*current_sinr = q->sinr[0][q->pdsch_cfg.codebook_idx];
} else if (q->pdsch_cfg.nof_layers == 2) {
*current_sinr = q->sinr[1][q->pdsch_cfg.codebook_idx - 1];
} else {
ERROR("Not implemented number of layers (%d)", q->pdsch_cfg.nof_layers);
return SRSLTE_ERROR;
}
}
/* Set PMI */
if (pmi != NULL) {
*pmi = best_pmi;
}
/* Print Trace */
if (ri != NULL && pmi != NULL && current_sinr != NULL) {
INFO("PDSCH Select RI=%d; PMI=%d; Current SINR=%.1fdB (nof_layers=%d, codebook_idx=%d)\n", *ri, *pmi,
10*log10(*current_sinr), q->pdsch_cfg.nof_layers, q->pdsch_cfg.codebook_idx);
/* Set current SINR */
if (current_sinr != NULL && q->pdsch_cfg.mimo_type == SRSLTE_MIMO_TYPE_SPATIAL_MULTIPLEX) {
if (q->pdsch_cfg.nof_layers == 1) {
*current_sinr = q->sinr[0][q->pdsch_cfg.codebook_idx];
} else if (q->pdsch_cfg.nof_layers == 2) {
*current_sinr = q->sinr[1][q->pdsch_cfg.codebook_idx - 1];
} else {
ERROR("Not implemented number of layers (%d)", q->pdsch_cfg.nof_layers);
return SRSLTE_ERROR;
}
} else {
ERROR("Not implemented configuration");
return SRSLTE_ERROR_INVALID_INPUTS;
}
return SRSLTE_SUCCESS;
@ -776,13 +907,7 @@ bool srslte_ue_dl_decode_phich(srslte_ue_dl_t *q, uint32_t sf_idx, uint32_t n_pr
sf_idx, n_prb_lowest, n_dmrs, ngroup, nseq,
srslte_phich_ngroups(&q->phich), srslte_phich_nsf(&q->phich));
cf_t *ce0[SRSLTE_MAX_PORTS];
for (int i=0;i<SRSLTE_MAX_PORTS;i++) {
ce0[i] = q->ce_m[i][0];
}
if (!srslte_phich_decode(&q->phich, q->sf_symbols_m[0], ce0, 0, ngroup, nseq, sf_idx, &ack_bit, &distance)) {
if (!srslte_phich_decode(&q->phich, q->sf_symbols_m, q->ce_m, 0, ngroup, nseq, sf_idx, &ack_bit, &distance)) {
INFO("Decoded PHICH %d with distance %f\n", ack_bit, distance);
} else {
fprintf(stderr, "Error decoding PHICH\n");
@ -815,16 +940,16 @@ void srslte_ue_dl_save_signal(srslte_ue_dl_t *q, srslte_softbuffer_rx_t *softbuf
srslte_vec_save_file("pdcch_llr", q->pdcch.llr, q->pdcch.nof_cce*72*sizeof(float));
srslte_vec_save_file("pdsch_symbols", q->pdsch.d, q->pdsch_cfg.nbits[0].nof_re*sizeof(cf_t));
srslte_vec_save_file("llr", q->pdsch.e, q->pdsch_cfg.nbits[0].nof_bits*sizeof(cf_t));
srslte_vec_save_file("pdsch_symbols", q->pdsch.d[0], q->pdsch_cfg.nbits[0].nof_re*sizeof(cf_t));
srslte_vec_save_file("llr", q->pdsch.e[0], q->pdsch_cfg.nbits[0].nof_bits*sizeof(cf_t));
int cb_len = q->pdsch_cfg.cb_segm[0].K1;
for (int i=0;i<q->pdsch_cfg.cb_segm[0].C;i++) {
char tmpstr[64];
snprintf(tmpstr,64,"rmout_%d.dat",i);
srslte_vec_save_file(tmpstr, softbuffer->buffer_f[i], (3*cb_len+12)*sizeof(int16_t));
}
printf("Saved files for tti=%d, sf=%d, cfi=%d, mcs=%d, rv=%d, rnti=0x%x\n", tti, tti%10, cfi,
q->pdsch_cfg.grant.mcs[0].idx, rv_idx, rnti);
printf("Saved files for tti=%d, sf=%d, cfi=%d, mcs=%d, tbs=%d, rv=%d, rnti=0x%x\n", tti, tti%10, cfi,
q->pdsch_cfg.grant.mcs[0].idx, q->pdsch_cfg.grant.mcs[0].tbs, rv_idx, rnti);
}

View File

@ -271,7 +271,7 @@ int srslte_ue_mib_sync_decode(srslte_ue_mib_sync_t * q,
ret = srslte_ue_sync_zerocopy_multi(&q->ue_sync, q->sf_buffer);
if (ret < 0) {
fprintf(stderr, "Error calling srslte_ue_sync_work()\n");
break;
return -1;
} else if (srslte_ue_sync_get_sfidx(&q->ue_sync) == 0) {
if (ret == 1) {
mib_ret = srslte_ue_mib_decode(&q->ue_mib, q->sf_buffer[0], bch_payload, nof_tx_ports, sfn_offset);

View File

@ -513,7 +513,7 @@ static int track_peak_ok(srslte_ue_sync_t *q, uint32_t track_idx) {
discard the offseted samples to align next frame */
if (q->next_rf_sample_offset > 0 && q->next_rf_sample_offset < MAX_TIME_OFFSET) {
DEBUG("Positive time offset %d samples.\n", q->next_rf_sample_offset);
if (q->recv_callback(q->stream, dummy_offset_buffer, (uint32_t) q->next_rf_sample_offset, &q->last_timestamp) < 0) {
if (q->recv_callback(q->stream, dummy_offset_buffer, (uint32_t) q->next_rf_sample_offset, NULL) < 0) {
fprintf(stderr, "Error receiving from USRP\n");
return SRSLTE_ERROR;
}
@ -676,6 +676,7 @@ int srslte_ue_sync_zerocopy_multi(srslte_ue_sync_t *q, cf_t *input_buffer[SRSLTE
/* Track PSS/SSS around the expected PSS position
* In tracking phase, the subframe carrying the PSS is always the last one of the frame
*/
switch(srslte_sync_find(&q->strack, input_buffer[0],
q->frame_len - q->sf_len/2 - q->fft_size - q->strack.max_offset/2,
&track_idx))

View File

@ -30,6 +30,7 @@ extern "C" {
}
#include "srslte/radio/radio.h"
#include <string.h>
#include <unistd.h>
namespace srslte {
@ -60,7 +61,14 @@ bool radio::init(char *args, char *devname)
} else {
printf("\nWarning burst preamble is not calibrated for device %s. Set a value manually\n\n", srslte_rf_name(&rf_device));
}
if (args) {
strncpy(saved_args, args, 128);
}
if (devname) {
strncpy(saved_devname, devname, 128);
}
return true;
}
@ -69,6 +77,16 @@ void radio::stop()
srslte_rf_close(&rf_device);
}
void radio::reset()
{
printf("Resetting Radio...\n");
srslte_rf_close(&rf_device);
sleep(3);
if (srslte_rf_open_devname(&rf_device, saved_devname, saved_args)) {
fprintf(stderr, "Error opening RF device\n");
}
}
void radio::set_manual_calibration(rf_cal_t* calibration)
{
srslte_rf_cal_t tx_cal;
@ -102,11 +120,6 @@ void radio::set_tx_adv_neg(bool tx_adv_is_neg) {
tx_adv_negative = tx_adv_is_neg;
}
void radio::tx_offset(int offset_)
{
offset = offset_;
}
bool radio::start_agc(bool tx_gain_same_rx)
{
if (srslte_rf_start_gain_thread(&rf_device, tx_gain_same_rx)) {
@ -167,6 +180,12 @@ bool radio::has_rssi()
return srslte_rf_has_rssi(&rf_device);
}
bool radio::is_first_of_burst() {
return is_start_of_burst;
}
#define BLOCKING_TX true
bool radio::tx(void* buffer, uint32_t nof_samples, srslte_timestamp_t tx_time)
{
void *iq_samples[4] = {(void *) zeros, (void *) zeros, (void *) zeros, (void *) zeros};
@ -185,7 +204,7 @@ bool radio::tx(void* buffer, uint32_t nof_samples, srslte_timestamp_t tx_time)
save_trace(1, &tx_time_pad);
srslte_rf_send_timed_multi(&rf_device, iq_samples, burst_preamble_samples, tx_time_pad.full_secs, tx_time_pad.frac_secs, true, true, false);
is_start_of_burst = false;
}
}
}
// Save possible end of burst time
@ -194,9 +213,10 @@ bool radio::tx(void* buffer, uint32_t nof_samples, srslte_timestamp_t tx_time)
save_trace(0, &tx_time);
iq_samples[0] = buffer;
int ret = srslte_rf_send_timed_multi(&rf_device, (void**) iq_samples, nof_samples+offset, tx_time.full_secs, tx_time.frac_secs, true, is_start_of_burst, false);
offset = 0;
is_start_of_burst = false;
int ret = srslte_rf_send_timed_multi(&rf_device, (void**) iq_samples, nof_samples,
tx_time.full_secs, tx_time.frac_secs,
BLOCKING_TX, is_start_of_burst, false);
is_start_of_burst = false;
if (ret > 0) {
return true;
} else {
@ -204,16 +224,6 @@ bool radio::tx(void* buffer, uint32_t nof_samples, srslte_timestamp_t tx_time)
}
}
uint32_t radio::get_tti_len()
{
return sf_len;
}
void radio::set_tti_len(uint32_t sf_len_)
{
sf_len = sf_len_;
}
void radio::tx_end()
{
if (!is_start_of_burst) {

View File

@ -29,7 +29,14 @@ bool radio_multi::init_multi(uint32_t nof_rx_antennas, char* args, char* devname
} else {
printf("\nWarning burst preamble is not calibrated for device %s. Set a value manually\n\n", srslte_rf_name(&rf_device));
}
if (args) {
strncpy(saved_args, args, 128);
}
if (devname) {
strncpy(saved_devname, devname, 128);
}
return true;
}

View File

@ -65,6 +65,15 @@ void pdcp::reset()
/*******************************************************************************
RRC/GW interface
*******************************************************************************/
bool pdcp::is_drb_enabled(uint32_t lcid)
{
if(lcid >= SRSLTE_N_RADIO_BEARERS) {
pdcp_log->error("Radio bearer id must be in [0:%d] - %d\n", SRSLTE_N_RADIO_BEARERS, lcid);
return false;
}
return pdcp_array[lcid].is_active();
}
void pdcp::write_sdu(uint32_t lcid, byte_buffer_t *sdu)
{
if(valid_lcid(lcid))

View File

@ -65,7 +65,10 @@ void rlc::reset_metrics()
void rlc::stop()
{
reset();
for(uint32_t i=0; i<SRSLTE_N_RADIO_BEARERS; i++) {
if(rlc_array[i].active())
rlc_array[i].stop();
}
}
void rlc::get_metrics(rlc_metrics_t &m)

View File

@ -93,6 +93,12 @@ void rlc_am::empty_queue() {
}
}
void rlc_am::stop()
{
reset();
pthread_mutex_destroy(&mutex);
}
void rlc_am::reset()
{
// Empty tx_sdu_queue before locking the mutex

View File

@ -76,6 +76,11 @@ void rlc_entity::reset()
rlc = NULL;
}
void rlc_entity::stop()
{
rlc->stop();
rlc = NULL;
}
void rlc_entity::empty_queue()
{

View File

@ -66,6 +66,11 @@ void rlc_tm::reset()
empty_queue();
}
void rlc_tm::stop()
{
reset();
}
rlc_mode_t rlc_tm::get_mode()
{
return RLC_MODE_TM;

View File

@ -62,7 +62,8 @@ void rlc_um::init(srslte::log *log_,
pdcp = pdcp_;
rrc = rrc_;
mac_timers = mac_timers_;
reordering_timeout_id = mac_timers->get_unique_id();
reordering_timer_id = mac_timers->timer_get_unique_id();
reordering_timer = mac_timers->timer_get(reordering_timer_id);
}
void rlc_um::configure(srslte_rlc_config_t cnfg_)
@ -102,6 +103,12 @@ void rlc_um::empty_queue() {
}
}
void rlc_um::stop()
{
reset();
mac_timers->timer_release_id(reordering_timer_id);
}
void rlc_um::reset()
{
@ -119,7 +126,7 @@ void rlc_um::reset()
if(tx_sdu)
tx_sdu->reset();
if(mac_timers)
mac_timers->get(reordering_timeout_id)->stop();
reordering_timer->stop();
// Drop all messages in RX window
std::map<uint32_t, rlc_umd_pdu_t>::iterator it;
@ -203,7 +210,7 @@ void rlc_um::write_pdu(uint8_t *payload, uint32_t nof_bytes)
void rlc_um::timer_expired(uint32_t timeout_id)
{
if(reordering_timeout_id == timeout_id)
if(reordering_timer_id == timeout_id)
{
pthread_mutex_lock(&mutex);
@ -221,11 +228,11 @@ void rlc_um::timer_expired(uint32_t timeout_id)
reassemble_rx_sdus();
log->debug("Finished reassemble from timeout id=%d\n", timeout_id);
}
mac_timers->get(reordering_timeout_id)->stop();
reordering_timer->stop();
if(RX_MOD_BASE(vr_uh) > RX_MOD_BASE(vr_ur))
{
mac_timers->get(reordering_timeout_id)->set(this, cfg.t_reordering);
mac_timers->get(reordering_timeout_id)->run();
reordering_timer->set(this, cfg.t_reordering);
reordering_timer->run();
vr_ux = vr_uh;
}
@ -236,7 +243,7 @@ void rlc_um::timer_expired(uint32_t timeout_id)
bool rlc_um::reordering_timeout_running()
{
return mac_timers->get(reordering_timeout_id)->is_running();
return reordering_timer->is_running();
}
/****************************************************************************
@ -398,20 +405,20 @@ void rlc_um::handle_data_pdu(uint8_t *payload, uint32_t nof_bytes)
log->debug("Finished reassemble from received PDU\n");
// Update reordering variables and timers
if(mac_timers->get(reordering_timeout_id)->is_running())
if(reordering_timer->is_running())
{
if(RX_MOD_BASE(vr_ux) <= RX_MOD_BASE(vr_ur) ||
(!inside_reordering_window(vr_ux) && vr_ux != vr_uh))
{
mac_timers->get(reordering_timeout_id)->stop();
reordering_timer->stop();
}
}
if(!mac_timers->get(reordering_timeout_id)->is_running())
if(!reordering_timer->is_running())
{
if(RX_MOD_BASE(vr_uh) > RX_MOD_BASE(vr_ur))
{
mac_timers->get(reordering_timeout_id)->set(this, cfg.t_reordering);
mac_timers->get(reordering_timeout_id)->run();
reordering_timer->set(this, cfg.t_reordering);
reordering_timer->run();
vr_ux = vr_uh;
}
}
@ -506,11 +513,20 @@ void rlc_um::reassemble_rx_sdus()
}
// Handle last segment
memcpy(&rx_sdu->msg[rx_sdu->N_bytes], rx_window[vr_ur].buf->msg, rx_window[vr_ur].buf->N_bytes);
rx_sdu->N_bytes += rx_window[vr_ur].buf->N_bytes;
log->debug("Writting last segment in SDU buffer. Updating vr_ur=%d, Buffer size=%d, segment size=%d\n",
vr_ur, rx_sdu->N_bytes, rx_window[vr_ur].buf->N_bytes);
vr_ur_in_rx_sdu = vr_ur;
// Handle last segment
if (rx_sdu->N_bytes < SRSLTE_MAX_BUFFER_SIZE_BYTES ||
rx_window[vr_ur].buf->N_bytes < SRSLTE_MAX_BUFFER_SIZE_BYTES ||
rx_window[vr_ur].buf->N_bytes + rx_sdu->N_bytes < SRSLTE_MAX_BUFFER_SIZE_BYTES) {
memcpy(&rx_sdu->msg[rx_sdu->N_bytes], rx_window[vr_ur].buf->msg, rx_window[vr_ur].buf->N_bytes);
rx_sdu->N_bytes += rx_window[vr_ur].buf->N_bytes;
log->debug("Writting last segment in SDU buffer. Updating vr_ur=%d, Buffer size=%d, segment size=%d\n",
vr_ur, rx_sdu->N_bytes, rx_window[vr_ur].buf->N_bytes);
} else {
log->error("Out of bounds while reassembling SDU buffer in UM: sdu_len=%d, window_buffer_len=%d, vr_ur=%d\n",
rx_sdu->N_bytes, rx_window[vr_ur].buf->N_bytes, vr_ur);
}
vr_ur_in_rx_sdu = vr_ur;
if(rlc_um_end_aligned(rx_window[vr_ur].header.fi))
{
if(pdu_lost && !rlc_um_start_aligned(rx_window[vr_ur].header.fi)) {

View File

@ -38,11 +38,12 @@ class mac_dummy_timers
:public srslte::mac_interface_timers
{
public:
srslte::timers::timer* get(uint32_t timer_id)
srslte::timers::timer* timer_get(uint32_t timer_id)
{
return &t;
}
uint32_t get_unique_id(){return 0;}
uint32_t timer_get_unique_id(){return 0;}
void timer_release_id(uint32_t id){}
private:
srslte::timers::timer t;

View File

@ -38,16 +38,16 @@ class mac_dummy_timers
:public srslte::mac_interface_timers
{
public:
srslte::timers::timer* get(uint32_t timer_id)
srslte::timers::timer* timer_get(uint32_t timer_id)
{
return &t;
}
uint32_t get_unique_id(){return 0;}
uint32_t timer_get_unique_id(){return 0;}
void step()
{
t.step();
}
void timer_release_id(uint32_t timer_id) {}
private:
srslte::timers::timer t;
};
@ -205,8 +205,8 @@ void loss_test()
}
// Step the reordering timer until expiry
while(!timers.get(1)->is_expired())
timers.get(1)->step();
while(!timers.timer_get(1)->is_expired())
timers.timer_get(1)->step();
assert(NBUFS-1 == tester.n_sdus);
}

View File

@ -58,8 +58,8 @@ drb_config = drb.conf
#####################################################################
[rf]
dl_earfcn = 3400
tx_gain = 80
rx_gain = 50
tx_gain = 70
rx_gain = 40
#device_name = auto
#device_args = auto
@ -98,8 +98,9 @@ filename = /tmp/enb.pcap
# Logging layers: phy, mac, rlc, pdcp, rrc, nas, gtpu, usim, all
# Logging levels: debug, info, warning, error, none
#
# filename: File path to use for log output
#####################################################################
# filename: File path to use for log output. Can be set to stdout
# to print logs to standard output
git c#####################################################################
[log]
all_level = info
all_hex_limit = 32

View File

@ -138,8 +138,6 @@ typedef struct {
Main UE class
*******************************************************************************/
//#define LOG_STDOUT
class enb
:public enb_metrics_interface {
public:
@ -180,11 +178,10 @@ private:
srsenb::gtpu gtpu;
srsenb::s1ap s1ap;
#ifdef LOG_STDOUT
srslte::logger_stdout logger;
#else
srslte::logger_file logger;
#endif
srslte::logger_stdout logger_stdout;
srslte::logger_file logger_file;
srslte::logger *logger;
srslte::log_filter rf_log;
std::vector<void*> phy_log;
srslte::log_filter mac_log;

View File

@ -102,28 +102,15 @@ public:
int rlc_buffer_state(uint16_t rnti, uint32_t lc_id, uint32_t tx_queue, uint32_t retx_queue);
bool process_pdus();
void timer_expired(uint32_t timer_id);
srslte::timers::timer* get(uint32_t timer_id);
u_int32_t get_unique_id();
// Interface for upper-layer timers
srslte::timers::timer* timer_get(uint32_t timer_id);
void timer_release_id(uint32_t timer_id);
u_int32_t timer_get_unique_id();
uint32_t get_current_tti();
void get_metrics(mac_metrics_t metrics[ENB_METRICS_MAX_USERS]);
enum {
HARQ_RTT,
TIME_ALIGNMENT,
CONTENTION_TIMER,
BSR_TIMER_PERIODIC,
BSR_TIMER_RETX,
PHR_TIMER_PERIODIC,
PHR_TIMER_PROHIBIT,
NOF_MAC_TIMERS
} mac_timers_t;
static const int MAC_NOF_UPPER_TIMERS = 20;
private:
void log_step_ul(uint32_t tti);
@ -192,21 +179,18 @@ private:
/* Class to run upper-layer timers with normal priority */
class upper_timers : public thread {
public:
upper_timers() : timers_db(MAC_NOF_UPPER_TIMERS),ttisync(10240) {start();}
class timer_thread : public thread {
public:
timer_thread(srslte::timers *t) : ttisync(10240),timers(t),running(false) {start();}
void tti_clock();
void stop();
void reset();
srslte::timers::timer* get(uint32_t timer_id);
uint32_t get_unique_id();
private:
void run_thread();
srslte::timers timers_db;
srslte::tti_sync_cv ttisync;
srslte::timers *timers;
bool running;
};
upper_timers upper_timers_thread;
timer_thread timers_thread;
/* Class to process MAC PDUs from DEMUX unit */
class pdu_process : public thread {

View File

@ -75,7 +75,7 @@ public:
void stop();
// gtpu_interface_rrc
void add_bearer(uint16_t rnti, uint32_t lcid, uint32_t teid_out, uint32_t *teid_in);
void add_bearer(uint16_t rnti, uint32_t lcid, uint32_t addr, uint32_t teid_out, uint32_t *teid_in);
void rem_bearer(uint16_t rnti, uint32_t lcid);
void rem_user(uint16_t rnti);
@ -86,7 +86,7 @@ public:
private:
static const int THREAD_PRIO = 7;
static const int GTPU_PORT = 2152;
srslte::byte_buffer_pool *pool;
srslte::byte_buffer_pool *pool;
bool running;
bool run_enable;
@ -98,11 +98,13 @@ private:
typedef struct{
uint32_t teids_in[SRSENB_N_RADIO_BEARERS];
uint32_t teids_out[SRSENB_N_RADIO_BEARERS];
uint32_t spgw_addrs[SRSENB_N_RADIO_BEARERS];
}bearer_map;
std::map<uint16_t, bearer_map> rnti_bearers;
srslte_netsink_t snk;
srslte_netsource_t src;
// Socket file descriptors
int snk_fd;
int src_fd;
void run_thread();

View File

@ -195,6 +195,9 @@ public:
bool setup_erabs(LIBLTE_S1AP_E_RABTOBESETUPLISTCTXTSUREQ_STRUCT *e);
bool setup_erabs(LIBLTE_S1AP_E_RABTOBESETUPLISTBEARERSUREQ_STRUCT *e);
void setup_erab(uint8_t id, LIBLTE_S1AP_E_RABLEVELQOSPARAMETERS_STRUCT *qos,
LIBLTE_S1AP_TRANSPORTLAYERADDRESS_STRUCT *addr, uint32_t teid_out,
LIBLTE_S1AP_NAS_PDU_STRUCT *nas_pdu);
bool release_erabs();
void notify_s1ap_ue_ctxt_setup_complete();

View File

@ -26,6 +26,7 @@
#include <boost/algorithm/string.hpp>
#include <boost/thread/mutex.hpp>
#include <enb.h>
#include "enb.h"
namespace srsenb {
@ -68,30 +69,32 @@ bool enb::init(all_args_t *args_)
{
args = args_;
#ifndef LOG_STDOUT
logger.init(args->log.filename);
#endif
rf_log.init("RF ", &logger);
if (!args->log.filename.compare("stdout")) {
logger = &logger_stdout;
} else {
logger_file.init(args->log.filename);
logger_file.log("\n\n");
logger = &logger_file;
}
rf_log.init("RF ", logger);
// Create array of pointers to phy_logs
for (int i=0;i<args->expert.phy.nof_phy_threads;i++) {
srslte::log_filter *mylog = new srslte::log_filter;
char tmp[16];
sprintf(tmp, "PHY%d",i);
mylog->init(tmp, &logger, true);
mylog->init(tmp, logger, true);
phy_log.push_back((void*) mylog);
}
mac_log.init("MAC ", &logger, true);
rlc_log.init("RLC ", &logger);
pdcp_log.init("PDCP", &logger);
rrc_log.init("RRC ", &logger);
gtpu_log.init("GTPU", &logger);
s1ap_log.init("S1AP", &logger);
mac_log.init("MAC ", logger, true);
rlc_log.init("RLC ", logger);
pdcp_log.init("PDCP", logger);
rrc_log.init("RRC ", logger);
gtpu_log.init("GTPU", logger);
s1ap_log.init("S1AP", logger);
// Init logs
#ifndef LOG_STDOUT
logger.log("\n\n");
#endif
rf_log.set_level(srslte::LOG_LEVEL_INFO);
for (int i=0;i<args->expert.phy.nof_phy_threads;i++) {
((srslte::log_filter*) phy_log[i])->set_level(level(args->log.phy_level));
@ -225,15 +228,15 @@ void enb::stop()
{
if(started)
{
mac.stop();
gtpu.stop();
phy.stop();
usleep(1e5);
mac.stop();
usleep(100000);
rlc.stop();
pdcp.stop();
gtpu.stop();
rrc.stop();
usleep(1e5);
if(args->pcap.enable)
{

View File

@ -42,7 +42,8 @@
namespace srsenb {
mac::mac() : timers_db((uint32_t) NOF_MAC_TIMERS),
mac::mac() : timers_db(128),
timers_thread(&timers_db),
rar_pdu_msg(sched_interface::MAX_RAR_LIST),
pdu_process_thread(this)
{
@ -99,7 +100,7 @@ void mac::stop()
srslte_softbuffer_tx_free(&pcch_softbuffer_tx);
srslte_softbuffer_tx_free(&rar_softbuffer_tx);
started = false;
upper_timers_thread.stop();
timers_thread.stop();
pdu_process_thread.stop();
}
@ -109,8 +110,7 @@ void mac::reset()
Info("Resetting MAC\n");
timers_db.stop_all();
upper_timers_thread.reset();
tti = 0;
last_rnti = 70;
@ -119,18 +119,6 @@ void mac::reset()
}
uint32_t mac::get_unique_id()
{
return upper_timers_thread.get_unique_id();
}
/* Front-end to upper-layer timers */
srslte::timers::timer* mac::get(uint32_t timer_id)
{
return upper_timers_thread.get(timer_id);
}
void mac::start_pcap(srslte::mac_pcap* pcap_)
{
pcap = pcap_;
@ -453,8 +441,7 @@ int mac::get_dl_sched(uint32_t tti, dl_sched_t *dl_sched_res)
dl_sched_res->sched_grants[n].data = ue_db[rnti]->generate_pdu(sched_result.data[i].pdu,
sched_result.data[i].nof_pdu_elems,
sched_result.data[i].tbs);
srslte_softbuffer_tx_reset_tbs(dl_sched_res->sched_grants[n].softbuffer, sched_result.data[i].tbs);
if (pcap) {
pcap->write_dl_crnti(dl_sched_res->sched_grants[n].data, sched_result.data[i].tbs, rnti, true, tti);
}
@ -474,7 +461,6 @@ int mac::get_dl_sched(uint32_t tti, dl_sched_t *dl_sched_res)
// Set softbuffer (there are no retx in RAR but a softbuffer is required)
dl_sched_res->sched_grants[n].softbuffer = &rar_softbuffer_tx;
srslte_softbuffer_tx_reset_tbs(&rar_softbuffer_tx, sched_result.rar[i].tbs); // TBS is usually 54-bit
// Assemble PDU
dl_sched_res->sched_grants[n].data = assemble_rar(sched_result.rar[i].grants, sched_result.rar[i].nof_grants, i, sched_result.rar[i].tbs);
@ -497,9 +483,6 @@ int mac::get_dl_sched(uint32_t tti, dl_sched_t *dl_sched_res)
// Set softbuffer
if (sched_result.bc[i].type == sched_interface::dl_sched_bc_t::BCCH) {
dl_sched_res->sched_grants[n].softbuffer = &bcch_softbuffer_tx[sched_result.bc[i].index];
if (sched_result.bc[i].dci.rv_idx == 0) {
srslte_softbuffer_tx_reset_tbs(dl_sched_res->sched_grants[n].softbuffer, sched_result.bc[i].tbs*8);
}
dl_sched_res->sched_grants[n].data = assemble_si(sched_result.bc[i].index);
#ifdef WRITE_SIB_PCAP
if (pcap) {
@ -508,7 +491,6 @@ int mac::get_dl_sched(uint32_t tti, dl_sched_t *dl_sched_res)
#endif
} else {
dl_sched_res->sched_grants[n].softbuffer = &pcch_softbuffer_tx;
srslte_softbuffer_tx_reset_tbs(dl_sched_res->sched_grants[n].softbuffer, sched_result.bc[i].tbs*8);
dl_sched_res->sched_grants[n].data = pcch_payload_buffer;
rlc_h->read_pdu_pcch(pcch_payload_buffer, pcch_payload_buffer_len);
@ -640,46 +622,59 @@ void mac::log_step_dl(uint32_t tti)
void mac::tti_clock()
{
upper_timers_thread.tti_clock();
timers_thread.tti_clock();
}
/********************************************************
*
* Class to run upper-layer timers with normal priority
* Interface for upper layer timers
*
*******************************************************/
void mac::upper_timers::run_thread()
uint32_t mac::timer_get_unique_id()
{
return timers_db.get_unique_id();
}
void mac::timer_release_id(uint32_t timer_id)
{
timers_db.release_id(timer_id);
}
/* Front-end to upper-layer timers */
srslte::timers::timer* mac::timer_get(uint32_t timer_id)
{
return timers_db.get(timer_id);
}
/********************************************************
*
* Class to run timers with normal priority
*
*******************************************************/
void mac::timer_thread::run_thread()
{
running=true;
ttisync.set_producer_cntr(0);
ttisync.resync();
while(running) {
ttisync.wait();
timers_db.step_all();
timers->step_all();
}
}
srslte::timers::timer* mac::upper_timers::get(uint32_t timer_id)
{
return timers_db.get(timer_id%MAC_NOF_UPPER_TIMERS);
}
uint32_t mac::upper_timers::get_unique_id()
{
return timers_db.get_unique_id();
}
void mac::upper_timers::stop()
void mac::timer_thread::stop()
{
running=false;
ttisync.increase();
wait_thread_finish();
}
void mac::upper_timers::reset()
{
timers_db.stop_all();
}
void mac::upper_timers::tti_clock()
void mac::timer_thread::tti_clock()
{
ttisync.increase();
}

View File

@ -635,7 +635,7 @@ uint32_t sched_ue::get_required_prb_ul(uint32_t req_bytes)
return 0;
}
for (n=1;n<=cell.nof_prb && nbytes < req_bytes + 4;n++) {
for (n=1;n<cell.nof_prb && nbytes < req_bytes + 4;n++) {
uint32_t nof_re = (2*(SRSLTE_CP_NSYMB(cell.cp)-1) - N_srs)*n*SRSLTE_NRE;
int tbs = 0;
if (fixed_mcs_ul < 0) {
@ -647,8 +647,8 @@ uint32_t sched_ue::get_required_prb_ul(uint32_t req_bytes)
nbytes = tbs;
}
}
while (!srslte_dft_precoding_valid_prb(n)) {
while (!srslte_dft_precoding_valid_prb(n) && n<=cell.nof_prb) {
n++;
}
@ -705,7 +705,7 @@ uint32_t sched_ue::get_aggr_level(uint32_t nof_bits)
do {
coderate = srslte_pdcch_coderate(nof_bits, l);
l++;
} while(l<3 && coderate > max_coderate);
} while(l<3 && 1.5*coderate > max_coderate);
Debug("SCHED: CQI=%d, l=%d, nof_bits=%d, coderate=%.2f, max_coderate=%.2f\n", dl_cqi, l, nof_bits, coderate, max_coderate);
return l;
}
@ -815,7 +815,7 @@ int sched_ue::alloc_tbs(uint32_t nof_prb,
// TODO: Compute real spectral efficiency based on PUSCH-UCI configuration
if (has_pucch && is_ul) {
cqi-=2;
cqi-=3;
}
int tbs = cqi_to_tbs(cqi, nof_prb, nof_re, max_mcs, max_Qm, &sel_mcs)/8;

View File

@ -434,8 +434,6 @@ int phch_worker::decode_pusch(srslte_enb_ul_pusch_t *grants, uint32_t nof_pusch,
ue_db[rnti].phich_info.n_prb_lowest = enb_ul.pusch_cfg.grant.n_prb_tilde[0];
ue_db[rnti].phich_info.n_dmrs = phy_grant.ncs_dmrs;
char cqi_str[64];
if (cqi_enabled) {
srslte_cqi_value_unpack(uci_data.uci_cqi, &cqi_value);
@ -689,10 +687,12 @@ int phch_worker::encode_pdsch(srslte_enb_dl_pdsch_t *grants, uint32_t nof_grants
rnti, phy_grant.nof_prb, grant_str, grants[i].grant.harq_process,
phy_grant.mcs[0].tbs/8, phy_grant.mcs[0].idx, grants[i].grant.rv_idx, tti_tx);
}
srslte_softbuffer_tx_t *sb[SRSLTE_MAX_CODEWORDS] = {grants[i].softbuffer, NULL};
uint8_t *d[SRSLTE_MAX_CODEWORDS] = {grants[i].data, NULL};
int rv[SRSLTE_MAX_CODEWORDS] = {grants[i].grant.rv_idx, 0};
if (srslte_enb_dl_put_pdsch(&enb_dl, &phy_grant, sb, rnti, rv, sf_idx, d, SRSLTE_MIMO_TYPE_SINGLE_ANTENNA, 0))
{
fprintf(stderr, "Error putting PDSCH %d\n",i);

View File

@ -26,6 +26,9 @@
#include "upper/gtpu.h"
#include <unistd.h>
#include <sys/socket.h>
#include <fcntl.h>
#include <errno.h>
using namespace srslte;
@ -42,16 +45,51 @@ bool gtpu::init(std::string gtp_bind_addr_, std::string mme_addr_, srsenb::pdcp_
pool = byte_buffer_pool::get_instance();
if(0 != srslte_netsource_init(&src, gtp_bind_addr.c_str(), GTPU_PORT, SRSLTE_NETSOURCE_UDP)) {
gtpu_log->error("Failed to create source socket on %s:%d", gtp_bind_addr.c_str(), GTPU_PORT);
// Set up sink socket
snk_fd = socket(AF_INET, SOCK_DGRAM, 0);
if (snk_fd < 0) {
gtpu_log->error("Failed to create sink socket\n");
return false;
}
if(0 != srslte_netsink_init(&snk, mme_addr.c_str(), GTPU_PORT, SRSLTE_NETSINK_UDP)) {
gtpu_log->error("Failed to create sink socket on %s:%d", mme_addr.c_str(), GTPU_PORT);
if (fcntl(snk_fd, F_SETFL, O_NONBLOCK)) {
gtpu_log->error("Failed to set non-blocking sink socket\n");
return false;
}
int enable = 1;
#if defined (SO_REUSEADDR)
if (setsockopt(snk_fd, SOL_SOCKET, SO_REUSEADDR, &enable, sizeof(int)) < 0)
gtpu_log->error("setsockopt(SO_REUSEADDR) failed\n");
#endif
#if defined (SO_REUSEPORT)
if (setsockopt(snk_fd, SOL_SOCKET, SO_REUSEPORT, &enable, sizeof(int)) < 0)
gtpu_log->error("setsockopt(SO_REUSEPORT) failed\n");
#endif
// Set up source socket
src_fd = socket(AF_INET, SOCK_DGRAM, 0);
if (src_fd < 0) {
gtpu_log->error("Failed to create source socket\n");
return false;
}
#if defined (SO_REUSEADDR)
if (setsockopt(src_fd, SOL_SOCKET, SO_REUSEADDR, &enable, sizeof(int)) < 0)
gtpu_log->error("setsockopt(SO_REUSEADDR) failed\n");
#endif
#if defined (SO_REUSEPORT)
if (setsockopt(src_fd, SOL_SOCKET, SO_REUSEPORT, &enable, sizeof(int)) < 0)
gtpu_log->error("setsockopt(SO_REUSEPORT) failed\n");
#endif
struct sockaddr_in bindaddr;
bindaddr.sin_family = AF_INET;
bindaddr.sin_addr.s_addr = inet_addr(gtp_bind_addr.c_str());
bindaddr.sin_port = htons(GTPU_PORT);
if (bind(src_fd, (struct sockaddr *)&bindaddr, sizeof(struct sockaddr_in))) {
gtpu_log->error("Failed to bind on address %s, port %d\n", gtp_bind_addr, GTPU_PORT);
return false;
}
srslte_netsink_set_nonblocking(&snk);
// Setup a thread to receive packets from the src socket
start(THREAD_PRIO);
@ -61,7 +99,7 @@ bool gtpu::init(std::string gtp_bind_addr_, std::string mme_addr_, srsenb::pdcp_
void gtpu::stop()
{
if(run_enable) {
if (run_enable) {
run_enable = false;
// Wait thread to exit gracefully otherwise might leave a mutex locked
int cnt=0;
@ -75,8 +113,12 @@ void gtpu::stop()
wait_thread_finish();
}
srslte_netsink_free(&snk);
srslte_netsource_free(&src);
if (snk_fd) {
close(snk_fd);
}
if (src_fd) {
close(src_fd);
}
}
// gtpu_interface_pdcp
@ -89,28 +131,35 @@ void gtpu::write_pdu(uint16_t rnti, uint32_t lcid, srslte::byte_buffer_t* pdu)
header.length = pdu->N_bytes;
header.teid = rnti_bearers[rnti].teids_out[lcid];
struct sockaddr_in servaddr;
servaddr.sin_family = AF_INET;
servaddr.sin_addr.s_addr = htonl(rnti_bearers[rnti].spgw_addrs[lcid]);
servaddr.sin_port = htons(GTPU_PORT);
gtpu_write_header(&header, pdu);
srslte_netsink_write(&snk, pdu->msg, pdu->N_bytes);
sendto(snk_fd, pdu->msg, pdu->N_bytes, MSG_EOR, (struct sockaddr*)&servaddr, sizeof(struct sockaddr_in));
pool->deallocate(pdu);
}
// gtpu_interface_rrc
void gtpu::add_bearer(uint16_t rnti, uint32_t lcid, uint32_t teid_out, uint32_t *teid_in)
void gtpu::add_bearer(uint16_t rnti, uint32_t lcid, uint32_t addr, uint32_t teid_out, uint32_t *teid_in)
{
// Allocate a TEID for the incoming tunnel
rntilcid_to_teidin(rnti, lcid, teid_in);
gtpu_log->info("Adding bearer for rnti: 0x%x, lcid: %d, teid_out: 0x%x, teid_in: 0x%x\n", rnti, lcid, teid_out, *teid_in);
gtpu_log->info("Adding bearer for rnti: 0x%x, lcid: %d, addr: 0x%x, teid_out: 0x%x, teid_in: 0x%x\n", rnti, lcid, addr, teid_out, *teid_in);
// Initialize maps if it's a new RNTI
if(rnti_bearers.count(rnti) == 0) {
for(int i=0;i<SRSENB_N_RADIO_BEARERS;i++) {
rnti_bearers[rnti].teids_in[i] = 0;
rnti_bearers[rnti].teids_out[i] = 0;
rnti_bearers[rnti].spgw_addrs[i] = 0;
}
}
rnti_bearers[rnti].teids_in[lcid] = *teid_in;
rnti_bearers[rnti].teids_out[lcid] = teid_out;
rnti_bearers[rnti].spgw_addrs[lcid] = addr;
}
void gtpu::rem_bearer(uint16_t rnti, uint32_t lcid)
@ -146,10 +195,16 @@ void gtpu::run_thread()
running=true;
while(run_enable) {
pdu->reset();
gtpu_log->debug("Waiting for read...\n");
pdu->N_bytes = srslte_netsource_read(&src, pdu->msg, SRSENB_MAX_BUFFER_SIZE_BYTES - SRSENB_BUFFER_HEADER_OFFSET);
do{
pdu->N_bytes = recv(src_fd, pdu->msg, SRSENB_MAX_BUFFER_SIZE_BYTES - SRSENB_BUFFER_HEADER_OFFSET, 0);
}while (pdu->N_bytes == -1 && errno == EAGAIN);
if (pdu->N_bytes == -1) {
gtpu_log->error("Failed to read from socket\n");
}
gtpu_header_t header;
gtpu_read_header(pdu, &header);

View File

@ -223,7 +223,8 @@ void rrc::rem_user(uint16_t rnti)
rrc_log->console("Disconnecting rnti=0x%x.\n", rnti);
rrc_log->info("Disconnecting rnti=0x%x.\n", rnti);
/* **Caution** order of removal here is imporant: from bottom to top */
mac->ue_rem(rnti); // MAC handles PHY
mac->ue_rem(rnti); // MAC handles PHY
usleep(50000);
rlc->rem_user(rnti);
pdcp->rem_user(rnti);
gtpu->rem_user(rnti);
@ -945,20 +946,16 @@ bool rrc::ue::setup_erabs(LIBLTE_S1AP_E_RABTOBESETUPLISTCTXTSUREQ_STRUCT *e)
if(erab->iE_Extensions_present) {
parent->rrc_log->warning("Not handling LIBLTE_S1AP_E_RABTOBESETUPITEMCTXTSUREQ_STRUCT extensions\n");
}
uint8_t id = erab->e_RAB_ID.E_RAB_ID;
erabs[id].id = id;
memcpy(&erabs[id].qos_params, &erab->e_RABlevelQoSParameters, sizeof(LIBLTE_S1AP_E_RABLEVELQOSPARAMETERS_STRUCT));
memcpy(&erabs[id].address, &erab->transportLayerAddress, sizeof(LIBLTE_S1AP_TRANSPORTLAYERADDRESS_STRUCT));
uint8_to_uint32(erab->gTP_TEID.buffer, &erabs[id].teid_out);
uint8_t lcid = id - 2; // Map e.g. E-RAB 5 to LCID 3 (==DRB1)
parent->gtpu->add_bearer(rnti, lcid, erabs[id].teid_out, &(erabs[id].teid_in));
if(erab->nAS_PDU_present) {
memcpy(parent->erab_info.msg, erab->nAS_PDU.buffer, erab->nAS_PDU.n_octets);
parent->erab_info.N_bytes = erab->nAS_PDU.n_octets;
if(erab->transportLayerAddress.n_bits > 32) {
parent->rrc_log->error("IPv6 addresses not currently supported\n");
return false;
}
uint32_t teid_out;
uint8_to_uint32(erab->gTP_TEID.buffer, &teid_out);
LIBLTE_S1AP_NAS_PDU_STRUCT *nas_pdu = erab->nAS_PDU_present ? &erab->nAS_PDU : NULL;
setup_erab(erab->e_RAB_ID.E_RAB_ID, &erab->e_RABlevelQoSParameters,
&erab->transportLayerAddress, teid_out, nas_pdu);
}
return true;
}
@ -973,25 +970,43 @@ bool rrc::ue::setup_erabs(LIBLTE_S1AP_E_RABTOBESETUPLISTBEARERSUREQ_STRUCT *e)
if(erab->iE_Extensions_present) {
parent->rrc_log->warning("Not handling LIBLTE_S1AP_E_RABTOBESETUPITEMCTXTSUREQ_STRUCT extensions\n");
}
if(erab->transportLayerAddress.n_bits > 32) {
parent->rrc_log->error("IPv6 addresses not currently supported\n");
return false;
}
uint8_t id = erab->e_RAB_ID.E_RAB_ID;
erabs[id].id = id;
memcpy(&erabs[id].qos_params, &erab->e_RABlevelQoSParameters, sizeof(LIBLTE_S1AP_E_RABLEVELQOSPARAMETERS_STRUCT));
memcpy(&erabs[id].address, &erab->transportLayerAddress, sizeof(LIBLTE_S1AP_TRANSPORTLAYERADDRESS_STRUCT));
uint8_to_uint32(erab->gTP_TEID.buffer, &erabs[id].teid_out);
uint8_t lcid = id - 2; // Map e.g. E-RAB 5 to LCID 3 (==DRB1)
parent->gtpu->add_bearer(rnti, lcid, erabs[id].teid_out, &(erabs[id].teid_in));
memcpy(parent->erab_info.msg, erab->nAS_PDU.buffer, erab->nAS_PDU.n_octets);
parent->erab_info.N_bytes = erab->nAS_PDU.n_octets;
uint32_t teid_out;
uint8_to_uint32(erab->gTP_TEID.buffer, &teid_out);
setup_erab(erab->e_RAB_ID.E_RAB_ID, &erab->e_RABlevelQoSParameters,
&erab->transportLayerAddress, teid_out, &erab->nAS_PDU);
}
// Work in progress
notify_s1ap_ue_erab_setup_response(e);
send_connection_reconf_new_bearer(e);
return true;
}
void rrc::ue::setup_erab(uint8_t id, LIBLTE_S1AP_E_RABLEVELQOSPARAMETERS_STRUCT *qos,
LIBLTE_S1AP_TRANSPORTLAYERADDRESS_STRUCT *addr, uint32_t teid_out,
LIBLTE_S1AP_NAS_PDU_STRUCT *nas_pdu)
{
erabs[id].id = id;
memcpy(&erabs[id].qos_params, qos, sizeof(LIBLTE_S1AP_E_RABLEVELQOSPARAMETERS_STRUCT));
memcpy(&erabs[id].address, addr, sizeof(LIBLTE_S1AP_TRANSPORTLAYERADDRESS_STRUCT));
erabs[id].teid_out = teid_out;
uint8_t* bit_ptr = addr->buffer;
uint32_t addr_ = liblte_bits_2_value(&bit_ptr, addr->n_bits);
uint8_t lcid = id - 2; // Map e.g. E-RAB 5 to LCID 3 (==DRB1)
parent->gtpu->add_bearer(rnti, lcid, addr_, erabs[id].teid_out, &(erabs[id].teid_in));
if(nas_pdu) {
memcpy(parent->erab_info.msg, nas_pdu->buffer, nas_pdu->n_octets);
parent->erab_info.N_bytes = nas_pdu->n_octets;
}
}
bool rrc::ue::release_erabs()
{
typedef std::map<uint8_t, erab_t>::iterator it_t;

View File

@ -42,7 +42,7 @@ class demux : public srslte::pdu_queue::process_callback
{
public:
demux(uint8_t nof_harq_proc_);
void init(phy_interface_mac_common* phy_h_, rlc_interface_mac *rlc, srslte::log* log_h_, srslte::timers* timers_db_);
void init(phy_interface_mac_common* phy_h_, rlc_interface_mac *rlc, srslte::log* log_h_, srslte::timers::timer* time_alignment_timer);
bool process_pdus();
uint8_t* request_buffer(uint32_t pid, uint32_t len);
@ -74,7 +74,7 @@ private:
phy_interface_mac_common *phy_h;
srslte::log *log_h;
srslte::timers *timers_db;
srslte::timers::timer *time_alignment_timer;
rlc_interface_mac *rlc;
uint8_t nof_harq_proc;

View File

@ -35,7 +35,6 @@
#include "srslte/common/log.h"
#include "srslte/common/timers.h"
#include "mac/demux.h"
#include "mac/mac_common.h"
#include "mac/dl_sps.h"
#include "srslte/common/mac_pcap.h"
@ -58,9 +57,9 @@ public:
pcap = NULL;
}
bool init(srslte::log *log_h_, srslte::timers *timers_, demux *demux_unit_)
bool init(srslte::log *log_h_, srslte::timers::timer *timer_aligment_timer_, demux *demux_unit_)
{
timers_db = timers_;
timer_aligment_timer = timer_aligment_timer_;
demux_unit = demux_unit_;
si_window_start = 0;
log_h = log_h_;
@ -102,7 +101,7 @@ public:
} else {
if (grant.is_sps_release) {
dl_sps_assig.clear();
if (timers_db->get(TIME_ALIGNMENT)->is_running()) {
if (timer_aligment_timer->is_running()) {
//phy_h->send_sps_ack();
Warning("PHY Send SPS ACK not implemented\n");
}
@ -168,12 +167,14 @@ private:
void new_grant_dl(Tgrant grant, Taction *action) {
/* Fill action structure */
bzero(action, sizeof(Taction));
action->default_ack = false;
action->generate_ack = true;
action->decode_enabled = false;
action->rnti = grant.rnti;
/* For each subprocess... */
for (uint32_t tb = 0; tb < SRSLTE_MAX_TB; tb++) {
action->default_ack[tb] = false;
action->decode_enabled[tb] = false;
action->phy_grant.dl.tb_en[tb] = grant.tb_en[tb];
if (grant.tb_en[tb]) {
subproc[tb].new_grant_dl(grant, action);
}
@ -210,6 +211,7 @@ private:
return false;
} else {
pid = pid_;
is_first_tb = true;
is_initiated = true;
harq_entity = parent;
log_h = harq_entity->log_h;
@ -218,6 +220,7 @@ private:
}
void reset(void) {
is_first_tb = true;
ack = false;
payload_buffer_ptr = NULL;
bzero(&cur_grant, sizeof(Tgrant));
@ -239,7 +242,12 @@ private:
}
}
calc_is_new_transmission(grant);
if (is_new_transmission) {
// If this is a new transmission or the size of the TB has changed
if (is_new_transmission || (cur_grant.n_bytes[tid] != grant.n_bytes[tid])) {
if (!is_new_transmission) {
Warning("DL PID %d: Size of grant changed during a retransmission %d!=%d\n", pid,
cur_grant.n_bytes[tid], grant.n_bytes[tid]);
}
ack = false;
srslte_softbuffer_rx_reset_tbs(&softbuffer, cur_grant.n_bytes[tid] * 8);
n_retx = 0;
@ -258,23 +266,22 @@ private:
cur_grant.n_bytes[tid]);
action->payload_ptr[tid] = payload_buffer_ptr;
if (!action->payload_ptr) {
action->decode_enabled = false;
action->decode_enabled[tid] = false;
Error("Can't get a buffer for TBS=%d\n", cur_grant.n_bytes[tid]);
return;
}
action->decode_enabled = true;
action->decode_enabled[tid]= true;
action->rv[tid] = cur_grant.rv[tid];
action->rnti = cur_grant.rnti;
action->softbuffers[tid] = &softbuffer;
memcpy(&action->phy_grant, &cur_grant.phy_grant, sizeof(Tphygrant));
n_retx++;
} else {
action->default_ack[tid] = true;
Warning("DL PID %d: Received duplicate TB. Discarting and retransmitting ACK\n", pid);
action->phy_grant.dl.tb_en[tid] = false;
}
if (pid == HARQ_BCCH_PID || harq_entity->timers_db->get(TIME_ALIGNMENT)->is_expired()) {
if (pid == HARQ_BCCH_PID || harq_entity->timer_aligment_timer->is_expired()) {
// Do not generate ACK
Debug("Not generating ACK\n");
action->generate_ack = false;
@ -336,17 +343,14 @@ private:
int get_current_tbs(void) { return cur_grant.n_bytes[tid] * 8; }
private:
// Determine if it's a new transmission 5.3.2.2
bool calc_is_new_transmission(Tgrant grant) {
bool is_new_tb = true;
if ((srslte_tti_interval(grant.tti, cur_grant.tti) <= 8 && (grant.n_bytes[tid] == cur_grant.n_bytes[tid])) ||
pid == HARQ_BCCH_PID) {
is_new_tb = false;
}
if ((grant.ndi[tid] != cur_grant.ndi[tid] && !is_new_tb) || // NDI toggled for same TB
is_new_tb || // is new TB
(pid == HARQ_BCCH_PID && grant.rv[tid] == 0)) // Broadcast PID and 1st TX (RV=0)
if ((grant.ndi[tid] != cur_grant.ndi[tid]) || // 1st condition (NDI has changed)
(pid == HARQ_BCCH_PID && grant.rv[tid] == 0) || // 2nd condition (Broadcast and 1st transmission)
is_first_tb) // 3rd condition (first TB)
{
is_first_tb = false;
is_new_transmission = true;
Debug("Set HARQ for new transmission\n");
} else {
@ -361,6 +365,7 @@ private:
dl_harq_entity *harq_entity;
srslte::log *log_h;
bool is_first_tb;
bool is_new_transmission;
uint32_t pid; /* HARQ Proccess ID */
@ -391,7 +396,7 @@ private:
std::vector<dl_harq_process> proc;
srslte::timers *timers_db;
srslte::timers::timer *timer_aligment_timer;
demux *demux_unit;
srslte::log *log_h;
srslte::mac_pcap *pcap;

View File

@ -48,9 +48,9 @@ namespace srsue {
class mac
:public mac_interface_phy
,public mac_interface_rrc
,public srslte::timer_callback
,public srslte::mac_interface_timers
,public thread
,public srslte::timer_callback
{
public:
mac();
@ -90,17 +90,20 @@ public:
void set_contention_id(uint64_t uecri);
void get_rntis(ue_rnti_t *rntis);
void timer_expired(uint32_t timer_id);
void start_pcap(srslte::mac_pcap* pcap);
srslte::timers::timer* get(uint32_t timer_id);
u_int32_t get_unique_id();
// Timer callback interface
void timer_expired(uint32_t timer_id);
uint32_t get_current_tti();
static const int MAC_NOF_UPPER_TIMERS = 20;
// Interface for upper-layer timers
srslte::timers::timer* timer_get(uint32_t timer_id);
void timer_release_id(uint32_t timer_id);
uint32_t timer_get_unique_id();
private:
void run_thread();
@ -144,13 +147,17 @@ private:
/* Buffers for PCH reception (not included in DL HARQ) */
const static uint32_t pch_payload_buffer_sz = 8*1024;
srslte_softbuffer_rx_t pch_softbuffer;
uint8_t pch_payload_buffer[pch_payload_buffer_sz];
uint8_t pch_payload_buffer[pch_payload_buffer_sz];
/* Functions for MAC Timers */
srslte::timers timers_db;
uint32_t timer_alignment;
uint32_t contention_resolution_timer;
void setup_timers();
void timeAlignmentTimerExpire();
void timer_alignment_expire();
srslte::timers timers;
// pointer to MAC PCAP object
srslte::mac_pcap* pcap;
bool is_first_ul_grant;
@ -158,22 +165,6 @@ private:
mac_metrics_t metrics;
/* Class to run upper-layer timers with normal priority */
class upper_timers : public periodic_thread {
public:
upper_timers();
void reset();
srslte::timers::timer* get(uint32_t timer_id);
uint32_t get_unique_id();
private:
void run_period();
srslte::timers timers_db;
};
upper_timers upper_timers_thread;
/* Class to process MAC PDUs from DEMUX unit */
class pdu_process : public thread {
public:

View File

@ -1,45 +0,0 @@
/**
*
* \section COPYRIGHT
*
* Copyright 2013-2015 Software Radio Systems Limited
*
* \section LICENSE
*
* This file is part of the srsUE library.
*
* srsUE is free software: you can redistribute it and/or modify
* it under the terms of the GNU Affero General Public License as
* published by the Free Software Foundation, either version 3 of
* the License, or (at your option) any later version.
*
* srsUE 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 Affero General Public License for more details.
*
* A copy of the GNU Affero General Public License can be found in
* the LICENSE file in the top-level directory of this distribution
* and at http://www.gnu.org/licenses/.
*
*/
#ifndef MAC_COMMON_H
#define MAC_COMMON_H
namespace srsue {
typedef enum {
HARQ_RTT,
TIME_ALIGNMENT,
CONTENTION_TIMER,
BSR_TIMER_PERIODIC,
BSR_TIMER_RETX,
PHR_TIMER_PERIODIC,
PHR_TIMER_PROHIBIT,
NOF_MAC_TIMERS
} mac_timers_t;
} // namespace srsue
#endif // MAC_COMMON_H

View File

@ -81,6 +81,9 @@ private:
bool generate_bsr(bsr_t *bsr, uint32_t nof_padding_bytes);
char* bsr_type_tostring(triggered_bsr_type_t type);
char* bsr_format_tostring(bsr_format_t format);
uint32_t timer_periodic_id;
uint32_t timer_retx_id;
};
} // namespace srsue

View File

@ -49,7 +49,9 @@ public:
bool generate_phr_on_ul_grant(float *phr);
void timer_expired(uint32_t timer_id);
void start_timer();
private:
bool pathloss_changed();
@ -59,11 +61,15 @@ private:
phy_interface_mac* phy_h;
srslte::timers* timers_db;
bool initiated;
int timer_prohibit;
int timer_periodic;
int timer_prohibit_value;
int timer_periodic_value;
int dl_pathloss_change;
int last_pathloss_db;
bool phr_is_triggered;
uint32_t timer_periodic_id;
uint32_t timer_prohibit_id;
};
} // namespace srsue

View File

@ -59,8 +59,7 @@ class ra_proc : public srslte::timer_callback
phy_h = NULL;
log_h = NULL;
mac_cfg = NULL;
timers_db = NULL;
mux_unit = NULL;
mux_unit = NULL;
demux_unit = NULL;
rrc = NULL;
transmitted_contention_id = 0;
@ -69,7 +68,10 @@ class ra_proc : public srslte::timer_callback
started_by_pdcch = false;
rar_grant_nbytes = 0;
rar_grant_tti = 0;
msg3_flushed = false;
msg3_flushed = false;
time_alignment_timer = NULL;
contention_resolution_timer = NULL;
};
~ra_proc();
@ -78,8 +80,9 @@ class ra_proc : public srslte::timer_callback
rrc_interface_mac *rrc_,
srslte::log *log_h,
mac_interface_rrc::ue_rnti_t *rntis,
mac_interface_rrc::mac_cfg_t *mac_cfg,
srslte::timers *timers_db,
mac_interface_rrc::mac_cfg_t *mac_cfg,
srslte::timers::timer* time_alignment_timer_,
srslte::timers::timer* contention_resolution_timer_,
mux *mux_unit,
demux *demux_unit);
void reset();
@ -101,9 +104,9 @@ class ra_proc : public srslte::timer_callback
void start_pcap(srslte::mac_pcap* pcap);
private:
static bool uecrid_callback(void *arg, uint64_t uecri);
bool contention_resolution_id_received(uint64_t uecri);
void process_timeadv_cmd(uint32_t ta_cmd);
void process_timeadv_cmd(uint32_t ta_cmd);
void step_initialization();
void step_resource_selection();
void step_preamble_transmission();
@ -114,14 +117,14 @@ private:
void step_contention_resolution();
void step_completition();
// Buffer to receive RAR PDU
// Buffer to receive RAR PDU
static const uint32_t MAX_RAR_PDU_LEN = 2048;
uint8_t rar_pdu_buffer[MAX_RAR_PDU_LEN];
srslte::rar_pdu rar_pdu_msg;
srslte::rar_pdu rar_pdu_msg;
// Random Access parameters provided by higher layers defined in 5.1.1
uint32_t configIndex;
uint32_t nof_preambles;
uint32_t nof_preambles;
uint32_t nof_groupA_preambles;
uint32_t nof_groupB_preambles;
uint32_t messagePowerOffsetGroupB;
@ -130,26 +133,25 @@ private:
uint32_t powerRampingStep;
uint32_t preambleTransMax;
uint32_t iniReceivedTargetPower;
int delta_preamble_db;
uint32_t contentionResolutionTimer;
uint32_t maskIndex;
int preambleIndex;
uint32_t new_ra_msg_len;
int delta_preamble_db;
uint32_t contentionResolutionTimer;
uint32_t maskIndex;
int preambleIndex;
uint32_t new_ra_msg_len;
// Internal variables
uint32_t preambleTransmissionCounter;
uint32_t backoff_param_ms;
uint32_t sel_maskIndex;
uint32_t sel_preamble;
uint32_t preambleTransmissionCounter;
uint32_t backoff_param_ms;
uint32_t sel_maskIndex;
uint32_t sel_preamble;
uint32_t backoff_interval_start;
uint32_t backoff_inteval;
int received_target_power_dbm;
uint32_t ra_rnti;
uint32_t current_ta;
srslte_softbuffer_rx_t softbuffer_rar;
int received_target_power_dbm;
uint32_t ra_rnti;
uint32_t current_ta;
srslte_softbuffer_rx_t softbuffer_rar;
enum {
IDLE = 0,
INITIALIZATION, // Section 5.1.1
@ -163,36 +165,38 @@ private:
COMPLETION, // Section 5.1.6
COMPLETION_DONE,
RA_PROBLEM // Section 5.1.5 last part
} state;
} state;
typedef enum {RA_GROUP_A, RA_GROUP_B} ra_group_t;
ra_group_t last_msg3_group;
bool msg3_transmitted;
bool first_rar_received;
ra_group_t last_msg3_group;
bool msg3_transmitted;
bool first_rar_received;
void read_params();
phy_interface_mac *phy_h;
srslte::log *log_h;
srslte::timers *timers_db;
mux *mux_unit;
demux *demux_unit;
srslte::mac_pcap *pcap;
rrc_interface_mac *rrc;
srslte::timers::timer *time_alignment_timer;
srslte::timers::timer *contention_resolution_timer;
mac_interface_rrc::ue_rnti_t *rntis;
mac_interface_rrc::mac_cfg_t *mac_cfg;
uint64_t transmitted_contention_id;
uint16_t transmitted_crnti;
uint16_t transmitted_crnti;
enum {
PDCCH_CRNTI_NOT_RECEIVED = 0,
PDCCH_CRNTI_UL_GRANT,
PDCCH_CRNTI_DL_GRANT
PDCCH_CRNTI_NOT_RECEIVED = 0,
PDCCH_CRNTI_UL_GRANT,
PDCCH_CRNTI_DL_GRANT
} pdcch_to_crnti_received;
bool started_by_pdcch;
bool started_by_pdcch;
uint32_t rar_grant_nbytes;
uint32_t rar_grant_tti;
bool msg3_flushed;

View File

@ -35,7 +35,6 @@
#include "srslte/interfaces/ue_interfaces.h"
#include "srslte/common/log.h"
#include "mac/mux.h"
#include "mac/mac_common.h"
#include "mac/ul_sps.h"
#include "srslte/common/mac_pcap.h"
#include "srslte/common/timers.h"
@ -55,9 +54,10 @@ public:
ul_harq_entity() : proc(N)
{
pcap = NULL;
timers_db = NULL;
mux_unit = NULL;
contention_timer = NULL;
pcap = NULL;
mux_unit = NULL;
log_h = NULL;
params = NULL;
rntis = NULL;
@ -68,14 +68,14 @@ public:
bool init(srslte::log *log_h_,
mac_interface_rrc_common::ue_rnti_t *rntis_,
mac_interface_rrc_common::ul_harq_params_t *params_,
srslte::timers* timers_db_,
srslte::timers::timer* contention_timer_,
mux *mux_unit_)
{
log_h = log_h_;
mux_unit = mux_unit_;
params = params_;
rntis = rntis_;
timers_db = timers_db_;
contention_timer = contention_timer_;
for (uint32_t i=0;i<N;i++) {
if (!proc[i].init(i, this)) {
return false;
@ -350,7 +350,7 @@ private:
// On every Msg3 retransmission, restart mac-ContentionResolutionTimer as defined in Section 5.1.5
if (is_msg3) {
harq_entity->timers_db->get(CONTENTION_TIMER)->reset();
harq_entity->contention_timer->reset();
}
harq_entity->mux_unit->pusch_retx(tti_tx, pid);
@ -368,6 +368,7 @@ private:
current_tx_nb = 0;
current_irv = 0;
is_msg3 = is_msg3_;
Info("UL %d: New TX%s, RV=%d, TBS=%d, RNTI=%d\n",
pid, is_msg3?" for Msg3":"", get_rv(), cur_grant.n_bytes[0],
is_msg3?harq_entity->rntis->temp_rnti:cur_grant.rnti);
@ -415,7 +416,7 @@ private:
ul_sps ul_sps_assig;
srslte::timers *timers_db;
srslte::timers::timer *contention_timer;
mux *mux_unit;
std::vector<ul_harq_process> proc;
srslte::log *log_h;

64
srsue/hdr/metrics_csv.h Normal file
View File

@ -0,0 +1,64 @@
/**
*
* \section COPYRIGHT
*
* Copyright 2013-2015 Software Radio Systems Limited
*
* \section LICENSE
*
* This file is part of the srsUE library.
*
* srsUE is free software: you can redistribute it and/or modify
* it under the terms of the GNU Affero General Public License as
* published by the Free Software Foundation, either version 3 of
* the License, or (at your option) any later version.
*
* srsUE 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 Affero General Public License for more details.
*
* A copy of the GNU Affero General Public License can be found in
* the LICENSE file in the top-level directory of this distribution
* and at http://www.gnu.org/licenses/.
*
*/
/******************************************************************************
* File: metrics_csv.h
* Description: Metrics class writing to CSV file.
*****************************************************************************/
#ifndef METRICS_CSV_H
#define METRICS_CSV_H
#include <pthread.h>
#include <stdint.h>
#include <string>
#include <iostream>
#include <fstream>
#include "srslte/common/metrics_hub.h"
#include "ue_metrics_interface.h"
namespace srsue {
class metrics_csv : public srslte::metrics_listener<ue_metrics_t>
{
public:
metrics_csv(std::string filename);
void set_metrics(ue_metrics_t &m, float report_period_secs);
void set_ue_handle(ue_metrics_interface *ue_);
private:
std::string float_to_string(float f, int digits, bool add_semicolon = true);
std::ofstream file;
ue_metrics_interface* ue;
uint32_t n_reports;
};
} // namespace srsue
#endif // METRICS_CSV_H

View File

@ -36,36 +36,28 @@
#include <stdint.h>
#include <string>
#include "srslte/common/metrics_hub.h"
#include "ue_metrics_interface.h"
namespace srsue {
class metrics_stdout
class metrics_stdout : public srslte::metrics_listener<ue_metrics_t>
{
public:
metrics_stdout();
bool init(ue_metrics_interface *u, float report_period_secs=1.0);
void stop();
void toggle_print(bool b);
static void* metrics_thread_start(void *m);
void metrics_thread_run();
void set_metrics(ue_metrics_t &m, float report_period_secs);
void set_ue_handle(ue_metrics_interface *ue_);
private:
void print_metrics();
void print_disconnect();
std::string float_to_string(float f, int digits);
std::string float_to_eng_string(float f, int digits);
std::string int_to_eng_string(int f, int digits);
ue_metrics_interface *ue_;
bool started;
bool do_print;
pthread_t metrics_thread;
ue_metrics_t metrics;
float metrics_report_period; // seconds
uint8_t n_reports;
bool do_print;
uint8_t n_reports;
ue_metrics_interface* ue;
};
} // namespace srsue

View File

@ -27,6 +27,9 @@
#ifndef UEPHYWORKERCOMMON_H
#define UEPHYWORKERCOMMON_H
#define TX_MODE_CONTINUOUS 1
#include <pthread.h>
#include <string.h>
#include <vector>
@ -36,8 +39,6 @@
#include "srslte/common/log.h"
#include "phy/phy_metrics.h"
//#define CONTINUOUS_TX
namespace srsue {
@ -47,8 +48,8 @@ namespace srsue {
/* Common variables used by all phy workers */
phy_interface_rrc::phy_cfg_t *config;
phy_args_t *args;
srslte::log *log_h;
phy_args_t *args;
rrc_interface_phy *rrc;
mac_interface_phy *mac;
srslte_ue_ul_t ue_ul;
@ -69,7 +70,8 @@ namespace srsue {
void init(phy_interface_rrc::phy_cfg_t *config,
phy_args_t *args,
srslte::log *_log,
srslte::radio *_radio,
srslte::radio *_radio,
rrc_interface_phy *rrc,
mac_interface_phy *_mac);
/* For RNTI searches, -1 means now or forever */
@ -116,7 +118,8 @@ namespace srsue {
bool is_first_of_burst;
srslte::radio *radio_h;
float cfo;
srslte::log *log_h;
bool ul_rnti_active(uint32_t tti);
bool dl_rnti_active(uint32_t tti);

View File

@ -52,13 +52,12 @@ public:
void stop();
void set_agc_enable(bool enable);
void resync_sfn();
void set_earfcn(std::vector<uint32_t> earfcn);
bool stop_sync();
void reset_sync();
void cell_search_start();
void cell_search_next();
void cell_search_stop();
void cell_search_next(bool reset = false);
bool cell_select(uint32_t earfcn, srslte_cell_t cell);
uint32_t get_current_tti();
@ -68,26 +67,42 @@ public:
void set_time_adv_sec(float time_adv_sec);
void get_current_cell(srslte_cell_t *cell);
const static int MUTEX_X_WORKER = 4;
const static int MUTEX_X_WORKER = 4;
// public variables needed by callback function
uint32_t current_sflen;
srslte::radio_multi *radio_h;
int next_offset;
private:
std::vector<uint32_t> earfcn;
void reset();
void radio_error();
bool wait_radio_reset();
void set_ue_sync_opts(srslte_ue_sync_t *q);
void run_thread();
void set_sampling_rate();
bool set_frequency();
void resync_sfn(bool is_connected = false);
bool stop_sync();
void cell_search_inc();
bool init_cell();
void free_cell();
bool init_cell();
void free_cell();
void stop_rx();
void start_rx();
bool radio_is_rx;
bool radio_is_resetting;
bool running;
srslte::radio_multi *radio_h;
mac_interface_phy *mac;
rrc_interface_phy *rrc;
srslte::log *log_h;
@ -114,6 +129,7 @@ private:
IDLE = 0,
CELL_SEARCH,
CELL_SELECT,
CELL_RESELECT,
CELL_MEASURE,
CELL_CAMP
} phy_state;
@ -123,6 +139,7 @@ private:
enum {
SRATE_NONE=0, SRATE_FIND, SRATE_CAMP
} srate_mode;
float current_srate;
srslte_cell_t cell;
bool cell_is_set;
@ -148,12 +165,11 @@ private:
float measure_rsrp;
srslte_ue_dl_t ue_dl_measure;
const static int RSRP_MEASURE_NOF_FRAMES = 5;
int cell_sync_sfn();
int cell_meas_rsrp();
bool cell_search(int force_N_id_2 = -1);
int cell_search(int force_N_id_2 = -1);
bool set_cell();
};

View File

@ -45,14 +45,14 @@ public:
~phch_worker();
void reset();
void set_common(phch_common *phy);
bool init(uint32_t max_prb);
bool init(uint32_t max_prb, srslte::log *log);
bool set_cell(srslte_cell_t cell);
/* Functions used by main PHY thread */
cf_t* get_buffer(uint32_t antenna_idx);
void set_tti(uint32_t tti, uint32_t tx_tti);
void set_tx_time(srslte_timestamp_t tx_time);
void set_tx_time(srslte_timestamp_t tx_time, uint32_t next_offset);
void set_cfo(float cfo);
void set_sample_offset(float sample_offset);
@ -113,6 +113,7 @@ private:
/* Common objects */
phch_common *phy;
srslte::log *log_h;
srslte_cell_t cell;
bool mem_initiated;
bool cell_initiated;
@ -122,7 +123,9 @@ private:
bool pregen_enabled;
uint32_t last_dl_pdcch_ncce;
bool rnti_is_set;
uint32_t next_offset;
/* Objects for DL */
srslte_ue_dl_t ue_dl;
uint32_t cfi;

View File

@ -52,8 +52,8 @@ public:
phy();
bool init(srslte::radio_multi *radio_handler,
mac_interface_phy *mac,
rrc_interface_phy *rrc,
srslte::log *log_h,
rrc_interface_phy *rrc,
std::vector<void*> log_vec,
phy_args_t *args = NULL);
void stop();
@ -79,19 +79,19 @@ public:
/********** RRC INTERFACE ********************/
void reset();
void sync_reset();
void configure_ul_params(bool pregen_disabled = false);
void resync_sfn();
void cell_search_start();
void cell_search_stop();
void cell_search_next();
bool cell_select(uint32_t earfcn, srslte_cell_t phy_cell);
/********** MAC INTERFACE ********************/
/* Functions to synchronize with a cell */
bool sync_status(); // this is also RRC interface
bool sync_stop();
/* Sets a C-RNTI allowing the PHY to pregenerate signals if necessary */
void set_crnti(uint16_t rnti);
void set_crnti(uint16_t rnti);
/* Instructs the PHY to configure using the parameters written by set_param() */
void configure_prach_params();
@ -148,6 +148,7 @@ private:
const static int WORKERS_THREAD_PRIO = 0;
srslte::radio_multi *radio_handler;
std::vector<void*> log_vec;
srslte::log *log_h;
srsue::mac_interface_phy *mac;
srsue::rrc_interface_phy *rrc;

View File

@ -45,7 +45,7 @@
#include "srslte/upper/pdcp.h"
#include "upper/rrc.h"
#include "upper/nas.h"
#include "srslte/upper/gw.h"
#include "upper/gw.h"
#include "upper/usim.h"
#include "srslte/common/buffer_pool.h"
@ -57,8 +57,6 @@
namespace srsue {
//#define LOG_STDOUT
/*******************************************************************************
Main UE class
*******************************************************************************/
@ -82,9 +80,6 @@ public:
void pregenerate_signals(bool enable);
// Testing
void test_con_restablishment();
private:
virtual ~ue();
@ -97,16 +92,15 @@ private:
srslte::pdcp pdcp;
srsue::rrc rrc;
srsue::nas nas;
srslte::gw gw;
srsue::gw gw;
srsue::usim usim;
#ifdef LOG_STDOUT
srslte::logger_stdout logger;
#else
srslte::logger_file logger;
#endif
srslte::log_filter rf_log;
srslte::log_filter phy_log;
srslte::logger_stdout logger_stdout;
srslte::logger_file logger_file;
srslte::logger *logger;
// rf_log is on ue_base
std::vector<void*> phy_log;
srslte::log_filter mac_log;
srslte::log_filter rlc_log;
srslte::log_filter pdcp_log;
@ -119,8 +113,7 @@ private:
all_args_t *args;
bool started;
rf_metrics_t rf_metrics;
bool check_srslte_version();
};

View File

@ -107,6 +107,8 @@ typedef struct {
float metrics_period_secs;
bool pregenerate_signals;
std::string ue_cateogry;
bool metrics_csv_enable;
std::string metrics_csv_filename;
}expert_args_t;
typedef struct {

View File

@ -29,7 +29,8 @@
#include <stdint.h>
#include "srslte/upper/gw_metrics.h"
#include "srslte/common/metrics_hub.h"
#include "upper/gw_metrics.h"
#include "srslte/upper/rlc_metrics.h"
#include "mac/mac_metrics.h"
#include "phy/phy_metrics.h"
@ -48,14 +49,15 @@ typedef struct {
phy_metrics_t phy;
mac_metrics_t mac;
srslte::rlc_metrics_t rlc;
srslte::gw_metrics_t gw;
gw_metrics_t gw;
}ue_metrics_t;
// UE interface
class ue_metrics_interface
class ue_metrics_interface : public srslte::metrics_interface<ue_metrics_t>
{
public:
virtual bool get_metrics(ue_metrics_t &m) = 0;
virtual bool is_attached() = 0;
};
} // namespace srsue

Some files were not shown because too many files have changed in this diff Show More