Skip to content

Commit

Permalink
move examples from repo cese-edu-ciaa
Browse files Browse the repository at this point in the history
  • Loading branch information
epernia committed Jul 5, 2018
0 parents commit 50c7d1d
Show file tree
Hide file tree
Showing 454 changed files with 50,532 additions and 0 deletions.
54 changes: 54 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
# Prerequisites
*.d

# Object files
*.o
*.ko
*.obj
*.elf

# Linker output
*.ilk
*.map
*.exp

# Precompiled Headers
*.gch
*.pch

# Libraries
*.lib
*.a
*.la
*.lo

# Shared objects (inc. Windows DLLs)
*.dll
*.so
*.so.*
*.dylib

# Executables
*.exe
*.out
*.app
*.i*86
*.x86_64
*.hex

# Debug files
*.dSYM/
*.su
*.idb
*.pdb

# Kernel Module Compile Results
*.mod*
*.cmd
.tmp_versions/
modules.order
Module.symvers
Mkfile.old
dkms.conf

out/
29 changes: 29 additions & 0 deletions LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
BSD 3-Clause License

Copyright (c) 2018, Eric Pernia - Martin Ribelotta
All rights reserved.

Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:

* Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.

* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.

* Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived from
this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
149 changes: 149 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,149 @@
# CESE, FI-UBA projects templates for EDU-CIAA-NXP

CESE, FI-UBA: http://laboratorios.fi.uba.ar/lse/cursos.html

Available libraries:
- LPCOpen v3.01
- sAPI r0.5.0.
- FreeRTOS Kernel V10.0.1

## IMPORTANT

**This environment is under construction!!**

**Always use the [released versions](../../releases) because in these all examples are tested and the API documentation is consistent. The master branch may contain inconsistencies because this environment is currently under development.**

## Supported boards
- CIAA-NXP (LPC4337).
- EDU-CIAA-NXP (LPC4337).

## Supported toolchains
- gcc-arm-none-eabi

## Usage
* Make sure you have an ```arm-none-eabi-*``` toolchain configured in your ```PATH```. If you don't have it, download [GCC ARM Embedded](https://developer.arm.com/open-source/gnu-toolchain/gnu-rm).
* ```git clone https://github.com/pridolfi/workspace.git && cd workspace```
* Define ```PROJECT_NAME``` and ```PROJECT_PATH``` variables in ```project.mk``` according to the project you want to compile (PROJECT_PATH is relative to this folder, leave void if the project is in this folder).
* Compile with ```make```.
* Clean with ```make clean```. Clean for all targets with ```make clean_all```.
* Download to target via OpenOCD with ```make download```.

## Create a new project

Each project consist in a folder (with a non-spaces name) that includes inside 2 folders, one named ```src``` (here go, .c, .cpp or .s source code files), and another one named ```inc``` (here go, .h or .hpp source header files) and one file named ```config.mk```, where you may configure which libraries you include and compiler options.

## Add a new library

The ```libs``` folder allow you to include 2 types of libraries:

- Simplie library. Consist in a folder (with a non-spaces name) that includes inside 2 folders, one named ```src``` (here go .c, .cpp or .s source code files), and another one named ```inc``` (here go .h or .hpp header files). This kind of library compiles automaticaly by the Makefile.
- Advanced library. Consist in a library whit a complex folder and files strcuture, i.e. LibUSB. This case reuire make your own makefile. You can inspire from sAPI makefile to do that.


## Examples

Included examples are:

**Bare-metal with sAPI library examples**

- GPIO:
- gpio_01_switches_leds: each switch drives the upper led.
- gpio_02_blinky: the simply led blinky with a blocking delay.
- gpio_03_blinky_switch: led blinky with a with a non-blocking delay, to allow you to respond to a switch at the same time.
- gpio_04_led_sequences: led sequences by using a non-blocking delay.
- keypad_7segment_01: Drives a keypad and 7 segment display.
- lcd_01: Drives an LCD display.
- UART:
- uart_01_echo: UART echo, it respond the same that you send from PC.
- uart_02_receive_string_blocking: Waits until receive a certain pattern String in a UART or timeout expire (blocking code).
- uart_03_receive_string: Waits until receive a certain pattern String in a UART or timeout expire (non-blocking code).
- Printf
- stdio_01_printf_sprintf: printf() and other similar standard C libray functions.
- ADC, DAC:
- adc_dac_01: ADC and DAC example.
- TIMER, RTC:
- cycles_counter_01: clock cycles counter functions, only work in debug mode. Allows execution time trazability.
- tick_01_tickHook: Periodic tick function (interrupt-based) with periodic callback.
- rtc_01: RTC peripheral to have date and time clock.
- pwm_01: PWM applied to LEDs.
- pwm_02_rgb_controller_uart: RGB LED example.
- servo_01: Servomotor PWM control example.
- External peripherals:
- I2C Magnetometers. In Chinese GY-273 module you can have one of this magnetometers, that have the same pinout but different register map. To difference them see the chip, ignore the board serigraphy:
- i2c_01_hmc5883l: HMC5883L magnetometer.
- i2c_02_qmc5883l: QMC5883L magnetometer.
- dht11_01: Humidity an Temperature sensor.
- ultrasonicSensor_HCSR04_01: HC-SR04 utrasonic distance sensor.
- spi_01_sdCard_fatFileSystem: ADC logging in a SD/MicroSD Card (SPI connected) by using a FAT File System (ChanFS).
- WiFi ESP01 (ESP8266) module:
- 01_uart_bridge: Use this to send AT commands directly to ESP01 module.
- 02_http_server: Embedded web Server to see sensor values.
- 03_thingspeak: Send data to thingspeak dashboards.

**Embedded Operating Systems with sAPI library examples**

- Cooperative O.S. (see M.J. Pont's book at https://www.safetty.net/publications/pttes )
- scheduler_01_seos: Cooperative O.S. introduction.
- scheduler_02_seos_background_foreground: Cooperative O.S., foreground-background.
- seos_Pont2014_01: SEOS Cooperative O.S. from M.J. Pont (2014).
- seos_pont_02_microwave: SEOS Cooperative O.S. from M.J. Pont (2014), microwave example.
- FreeOSEK
- freeOSEK_01_blinky: Blinky led with freeOSEK RTOS.
- FreeRTOS
- freeRTOS_01_blinky: Blinky led with freeRTOS RTOS and sAPI.
- freeRTOS_02_Queue: Queue management with freeRTOS and sAPI.
- freeRTOS_03_ChanFatFS_SPI_SdCard_ADC_log: ADC logging in a SD/MicroSD Card (SPI connected) by using a FAT File System (ChanFS), freeRTOS and sAPI.
- freeRTOS_book: Richard Barry's book examples with FreeRTOS and sAPI:
- EXAMPLE001: Creating tasks
- EXAMPLE002: Using the task parameter
- EXAMPLE003: Experimenting with priorities
- EXAMPLE004: Using the Blocked state to create delay
- EXAMPLE005: Converting the example tasks to use vTaskDelayUntil()
- EXAMPLE006: Combining blocking and non-blocking tasks
- EXAMPLE007: Defining an idle task hook function
- EXAMPLE008: Changing task priorities
- EXAMPLE009: Deleting tasks
- EXAMPLE010: Blocking when receiving from a queue
- EXAMPLE011: Blocking when sending to a queue or sending structures on a queue
- EXAMPLE012: Using a queue set
- EXAMPLE013: Creating one-shot and auto-reload timers
- EXAMPLE014: Using the callback function parameter and the software timer ID
- EXAMPLE015: Resetting a software timer
- EXAMPLE016: Using a binary semaphore to synchronize a task with an interrupt
- EXAMPLE017: Using a counting semaphore to synchronize a task with an interrupt
- EXAMPLE018: Centralized deferred interrupt processing
- EXAMPLE019: Sending and receiving on a queue from within an interrupt
- EXAMPLE020: Re-writing vPrintString() to use a semaphore
- EXAMPLE021: Re-writing vPrintString() to use a gatekeeper task
- EXAMPLE022: Experimenting with event groups
- EXAMPLE023: Synchronizing tasks
- EXAMPLE024: Using a task notification in place of a semaphore, method 1
- EXAMPLE025: Using a task notification in place of a semaphore, method 2

**Statecharts with sAPI library examples**

**LPC Open examples**

- LPC4337 LPC Open:
- adc_fir_dac
- asm
- blinky
- blinky_ram
- blinky_rit
- blinky_input
- boot: LPCBootloader example
- mpu
- start_m0
- trilat
- i2c
- pwm
- sd_spi
- usb_cdc
- usb_msc_host
- usb_rom_cdc
- statechart
- tcpecho
- LPC4337 LPC Open and RTOS:
- freertos_blinky
- blinky_osek
- multicore
48 changes: 48 additions & 0 deletions asm/asm_c_adc_fir_dac/Makefile
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
# Copyright 2016, Pablo Ridolfi
# All rights reserved.
#
# This file is part of Workspace.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# 1. Redistributions of source code must retain the above copyright notice,
# this list of conditions and the following disclaimer.
#
# 2. Redistributions in binary form must reproduce the above copyright notice,
# this list of conditions and the following disclaimer in the documentation
# and/or other materials provided with the distribution.
#
# 3. Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived from this
# software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

# application name
PROJECT_NAME := $(notdir $(PROJECT))

# Modules needed by the application
PROJECT_MODULES := modules/$(TARGET)/base \
modules/$(TARGET)/board \
modules/$(TARGET)/chip

# source files folder
PROJECT_SRC_FOLDERS := $(PROJECT)/src

# header files folder
PROJECT_INC_FOLDERS := $(PROJECT)/inc

# source files
PROJECT_C_FILES := $(wildcard $(PROJECT)/src/*.c)
PROJECT_ASM_FILES := $(wildcard $(PROJECT)/src/*.S)
18 changes: 18 additions & 0 deletions asm/asm_c_adc_fir_dac/inc/adc.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
/*
* adc.h
*
* Created on: Sep 4, 2013
* Author: Pablo
*/

#ifndef ADC_H_
#define ADC_H_

#include "board.h"

extern int adcFlag;

void adcInit(void);


#endif /* ADC_H_ */
40 changes: 40 additions & 0 deletions asm/asm_c_adc_fir_dac/inc/bandpass.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/*
* bandpass.h
*
* Created on: Sep 7, 2013
* Author: Pablo
*/

#ifndef BANDPASS_H_
#define BANDPASS_H_

/*
FIR filter designed with
http://t-filter.appspot.com
sampling frequency: 22000 Hz
fixed point precision: 31 bits
* 0 Hz - 500 Hz
gain = 0
desired attenuation = -40 dB
actual attenuation = -50.91 dB
* 900 Hz - 1100 Hz
gain = 1
desired ripple = 5 dB
actual ripple = 1.17 dB
* 1500 Hz - 11000 Hz
gain = 0
desired attenuation = -40 dB
actual attenuation = -50.91 dB
*/

#define BANDPASS_TAP_NUM 95
extern const int bandpass_taps[BANDPASS_TAP_NUM];

#endif /* BANDPASS_H_ */
14 changes: 14 additions & 0 deletions asm/asm_c_adc_fir_dac/inc/dac.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
/*
* dac.h
*
* Created on: Sep 4, 2013
* Author: Pablo
*/

#ifndef DAC_H_
#define DAC_H_

void dacInit(void);
void dacWrite(uint32_t v);

#endif /* DAC_H_ */
19 changes: 19 additions & 0 deletions asm/asm_c_adc_fir_dac/inc/fir_q31.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
#ifndef _FIR_H_
#define _FIR_H_

typedef struct
{
unsigned int last_index;
int num_taps;
const int * kernel;
int * history;
}fir_q31_t;

void fir_q31_init(fir_q31_t * f, int * history, const int * kernel, int num_taps);
void fir_q31_put(fir_q31_t * f, int input);
int fir_q31_get(fir_q31_t * f);

extern void asm_fir_q31_put(fir_q31_t * f, int input);
extern int asm_fir_q31_get(fir_q31_t * f);

#endif
Loading

0 comments on commit 50c7d1d

Please sign in to comment.