Initial commit (work in progress)

main
Mikael Nousiainen 2020-08-26 22:57:35 +03:00
commit c56bfc16cb
120 zmienionych plików z 43793 dodań i 0 usunięć

5
.gitignore vendored 100644
Wyświetl plik

@ -0,0 +1,5 @@
/.idea
/cmake-build-debug
/build
/samples
*~

12
CMakeLists.txt 100644
Wyświetl plik

@ -0,0 +1,12 @@
cmake_minimum_required(VERSION 3.6)
SET(CMAKE_SYSTEM_NAME "Generic")
SET(CMAKE_SYSTEM_VERSION 1)
SET(UNIX 1)
include_directories(src)
link_directories(src)
add_subdirectory(src)
add_subdirectory(tests)

339
LICENSE.md 100644
Wyświetl plik

@ -0,0 +1,339 @@
GNU GENERAL PUBLIC LICENSE
Version 2, June 1991
Copyright (C) 1989, 1991 Free Software Foundation, Inc., <http://fsf.org/>
51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
Preamble
The licenses for most software are designed to take away your
freedom to share and change it. By contrast, the GNU General Public
License is intended to guarantee your freedom to share and change free
software--to make sure the software is free for all its users. This
General Public License applies to most of the Free Software
Foundation's software and to any other program whose authors commit to
using it. (Some other Free Software Foundation software is covered by
the GNU Lesser General Public License instead.) You can apply it to
your programs, too.
When we speak of free software, we are referring to freedom, not
price. Our General Public Licenses are designed to make sure that you
have the freedom to distribute copies of free software (and charge for
this service if you wish), that you receive source code or can get it
if you want it, that you can change the software or use pieces of it
in new free programs; and that you know you can do these things.
To protect your rights, we need to make restrictions that forbid
anyone to deny you these rights or to ask you to surrender the rights.
These restrictions translate to certain responsibilities for you if you
distribute copies of the software, or if you modify it.
For example, if you distribute copies of such a program, whether
gratis or for a fee, you must give the recipients all the rights that
you have. You must make sure that they, too, receive or can get the
source code. And you must show them these terms so they know their
rights.
We protect your rights with two steps: (1) copyright the software, and
(2) offer you this license which gives you legal permission to copy,
distribute and/or modify the software.
Also, for each author's protection and ours, we want to make certain
that everyone understands that there is no warranty for this free
software. If the software is modified by someone else and passed on, we
want its recipients to know that what they have is not the original, so
that any problems introduced by others will not reflect on the original
authors' reputations.
Finally, any free program is threatened constantly by software
patents. We wish to avoid the danger that redistributors of a free
program will individually obtain patent licenses, in effect making the
program proprietary. To prevent this, we have made it clear that any
patent must be licensed for everyone's free use or not licensed at all.
The precise terms and conditions for copying, distribution and
modification follow.
GNU GENERAL PUBLIC LICENSE
TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION
0. This License applies to any program or other work which contains
a notice placed by the copyright holder saying it may be distributed
under the terms of this General Public License. The "Program", below,
refers to any such program or work, and a "work based on the Program"
means either the Program or any derivative work under copyright law:
that is to say, a work containing the Program or a portion of it,
either verbatim or with modifications and/or translated into another
language. (Hereinafter, translation is included without limitation in
the term "modification".) Each licensee is addressed as "you".
Activities other than copying, distribution and modification are not
covered by this License; they are outside its scope. The act of
running the Program is not restricted, and the output from the Program
is covered only if its contents constitute a work based on the
Program (independent of having been made by running the Program).
Whether that is true depends on what the Program does.
1. You may copy and distribute verbatim copies of the Program's
source code as you receive it, in any medium, provided that you
conspicuously and appropriately publish on each copy an appropriate
copyright notice and disclaimer of warranty; keep intact all the
notices that refer to this License and to the absence of any warranty;
and give any other recipients of the Program a copy of this License
along with the Program.
You may charge a fee for the physical act of transferring a copy, and
you may at your option offer warranty protection in exchange for a fee.
2. You may modify your copy or copies of the Program or any portion
of it, thus forming a work based on the Program, and copy and
distribute such modifications or work under the terms of Section 1
above, provided that you also meet all of these conditions:
a) You must cause the modified files to carry prominent notices
stating that you changed the files and the date of any change.
b) You must cause any work that you distribute or publish, that in
whole or in part contains or is derived from the Program or any
part thereof, to be licensed as a whole at no charge to all third
parties under the terms of this License.
c) If the modified program normally reads commands interactively
when run, you must cause it, when started running for such
interactive use in the most ordinary way, to print or display an
announcement including an appropriate copyright notice and a
notice that there is no warranty (or else, saying that you provide
a warranty) and that users may redistribute the program under
these conditions, and telling the user how to view a copy of this
License. (Exception: if the Program itself is interactive but
does not normally print such an announcement, your work based on
the Program is not required to print an announcement.)
These requirements apply to the modified work as a whole. If
identifiable sections of that work are not derived from the Program,
and can be reasonably considered independent and separate works in
themselves, then this License, and its terms, do not apply to those
sections when you distribute them as separate works. But when you
distribute the same sections as part of a whole which is a work based
on the Program, the distribution of the whole must be on the terms of
this License, whose permissions for other licensees extend to the
entire whole, and thus to each and every part regardless of who wrote it.
Thus, it is not the intent of this section to claim rights or contest
your rights to work written entirely by you; rather, the intent is to
exercise the right to control the distribution of derivative or
collective works based on the Program.
In addition, mere aggregation of another work not based on the Program
with the Program (or with a work based on the Program) on a volume of
a storage or distribution medium does not bring the other work under
the scope of this License.
3. You may copy and distribute the Program (or a work based on it,
under Section 2) in object code or executable form under the terms of
Sections 1 and 2 above provided that you also do one of the following:
a) Accompany it with the complete corresponding machine-readable
source code, which must be distributed under the terms of Sections
1 and 2 above on a medium customarily used for software interchange; or,
b) Accompany it with a written offer, valid for at least three
years, to give any third party, for a charge no more than your
cost of physically performing source distribution, a complete
machine-readable copy of the corresponding source code, to be
distributed under the terms of Sections 1 and 2 above on a medium
customarily used for software interchange; or,
c) Accompany it with the information you received as to the offer
to distribute corresponding source code. (This alternative is
allowed only for noncommercial distribution and only if you
received the program in object code or executable form with such
an offer, in accord with Subsection b above.)
The source code for a work means the preferred form of the work for
making modifications to it. For an executable work, complete source
code means all the source code for all modules it contains, plus any
associated interface definition files, plus the scripts used to
control compilation and installation of the executable. However, as a
special exception, the source code distributed need not include
anything that is normally distributed (in either source or binary
form) with the major components (compiler, kernel, and so on) of the
operating system on which the executable runs, unless that component
itself accompanies the executable.
If distribution of executable or object code is made by offering
access to copy from a designated place, then offering equivalent
access to copy the source code from the same place counts as
distribution of the source code, even though third parties are not
compelled to copy the source along with the object code.
4. You may not copy, modify, sublicense, or distribute the Program
except as expressly provided under this License. Any attempt
otherwise to copy, modify, sublicense or distribute the Program is
void, and will automatically terminate your rights under this License.
However, parties who have received copies, or rights, from you under
this License will not have their licenses terminated so long as such
parties remain in full compliance.
5. You are not required to accept this License, since you have not
signed it. However, nothing else grants you permission to modify or
distribute the Program or its derivative works. These actions are
prohibited by law if you do not accept this License. Therefore, by
modifying or distributing the Program (or any work based on the
Program), you indicate your acceptance of this License to do so, and
all its terms and conditions for copying, distributing or modifying
the Program or works based on it.
6. Each time you redistribute the Program (or any work based on the
Program), the recipient automatically receives a license from the
original licensor to copy, distribute or modify the Program subject to
these terms and conditions. You may not impose any further
restrictions on the recipients' exercise of the rights granted herein.
You are not responsible for enforcing compliance by third parties to
this License.
7. If, as a consequence of a court judgment or allegation of patent
infringement or for any other reason (not limited to patent issues),
conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License. If you cannot
distribute so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you
may not distribute the Program at all. For example, if a patent
license would not permit royalty-free redistribution of the Program by
all those who receive copies directly or indirectly through you, then
the only way you could satisfy both it and this License would be to
refrain entirely from distribution of the Program.
If any portion of this section is held invalid or unenforceable under
any particular circumstance, the balance of the section is intended to
apply and the section as a whole is intended to apply in other
circumstances.
It is not the purpose of this section to induce you to infringe any
patents or other property right claims or to contest validity of any
such claims; this section has the sole purpose of protecting the
integrity of the free software distribution system, which is
implemented by public license practices. Many people have made
generous contributions to the wide range of software distributed
through that system in reliance on consistent application of that
system; it is up to the author/donor to decide if he or she is willing
to distribute software through any other system and a licensee cannot
impose that choice.
This section is intended to make thoroughly clear what is believed to
be a consequence of the rest of this License.
8. If the distribution and/or use of the Program is restricted in
certain countries either by patents or by copyrighted interfaces, the
original copyright holder who places the Program under this License
may add an explicit geographical distribution limitation excluding
those countries, so that distribution is permitted only in or among
countries not thus excluded. In such case, this License incorporates
the limitation as if written in the body of this License.
9. The Free Software Foundation may publish revised and/or new versions
of the General Public License from time to time. Such new versions will
be similar in spirit to the present version, but may differ in detail to
address new problems or concerns.
Each version is given a distinguishing version number. If the Program
specifies a version number of this License which applies to it and "any
later version", you have the option of following the terms and conditions
either of that version or of any later version published by the Free
Software Foundation. If the Program does not specify a version number of
this License, you may choose any version ever published by the Free Software
Foundation.
10. If you wish to incorporate parts of the Program into other free
programs whose distribution conditions are different, write to the author
to ask for permission. For software which is copyrighted by the Free
Software Foundation, write to the Free Software Foundation; we sometimes
make exceptions for this. Our decision will be guided by the two goals
of preserving the free status of all derivatives of our free software and
of promoting the sharing and reuse of software generally.
NO WARRANTY
11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY
FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN
OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES
PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED
OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS
TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE
PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING,
REPAIR OR CORRECTION.
12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR
REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES,
INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING
OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED
TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY
YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER
PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE
POSSIBILITY OF SUCH DAMAGES.
END OF TERMS AND CONDITIONS
How to Apply These Terms to Your New Programs
If you develop a new program, and you want it to be of the greatest
possible use to the public, the best way to achieve this is to make it
free software which everyone can redistribute and change under these terms.
To do so, attach the following notices to the program. It is safest
to attach them to the start of each source file to most effectively
convey the exclusion of warranty; and each file should have at least
the "copyright" line and a pointer to where the full notice is found.
{description}
Copyright (C) {year} {fullname}
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License along
with this program; if not, write to the Free Software Foundation, Inc.,
51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
Also add information on how to contact you by electronic and paper mail.
If the program is interactive, make it output a short notice like this
when it starts in an interactive mode:
Gnomovision version 69, Copyright (C) year name of author
Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
This is free software, and you are welcome to redistribute it
under certain conditions; type `show c' for details.
The hypothetical commands `show w' and `show c' should show the appropriate
parts of the General Public License. Of course, the commands you use may
be called something other than `show w' and `show c'; they could even be
mouse-clicks or menu items--whatever suits your program.
You should also get your employer (if you work as a programmer) or your
school, if any, to sign a "copyright disclaimer" for the program, if
necessary. Here is a sample; alter the names:
Yoyodyne, Inc., hereby disclaims all copyright interest in the program
`Gnomovision' (which makes passes at compilers) written by James Hacker.
{signature of Ty Coon}, 1 April 1989
Ty Coon, President of Vice
This General Public License does not permit incorporating your program into
proprietary programs. If your program is a subroutine library, you may
consider it more useful to permit linking proprietary applications with the
library. If this is what you want to do, use the GNU Lesser General
Public License instead of this License.

49
README.md 100644
Wyświetl plik

@ -0,0 +1,49 @@
# RS41ng
**NOTE:** This is a work in progress and most features do not work correctly yet!
This is a custom firmware for Vaisala RS41 radiosondes. Some of the code is based
on an earlier RS41 firmware project called [RS41HUP](https://github.com/df8oe/RS41HUP),
but most of it has been rewritten from scratch.
The motivation to develop this firmware is to provide cleaner, customizable and
more modular codebase for developing RS41 radiosonde-based experiments.
The main features this firmware aims to implement are:
* DMA/Timer-based modulation of APRS and some other digital modes via JTEncode library
* Support for HF/VHF transmissions via an external Si5351 chip connected to the external I²C bus
* Support for custom sensors via the external I²C bus
## Features (work in progress)
* APRS on 70cm amateur radio band via Si4032 radio chip
** Bell 202 timing is done via DMA transfers to achieve greater accuracy, but I have not been able to get the timings working correctly
* Digital mode beacons on HF frequencies via a Si5351 radio chip connected to the external I²C bus of the RS41 radiosonde
** The JTEncode library provides JT65/JT9/JT4/FT8/WSPR/FSQ beacon transmissions. I've decoded FT8 and WSPR successfully.
The implementation is missing correct scheduling of transmissions via GPS clock.
* Support for additional sensors via the external I²C bus
** There is a driver for Bosch BMP280 barometric pressure / temperature / humidity sensor included
### Bell FSK modulation hack for APRS
The idea behind the APRS / Bell 202 modulation implementation is based on RS41HUP project and its "ancestors"
and I'm describing it here, since it has not been documented elsewhere.
The Si4032 chip seems to support only a very specific type of FSK, where one can define two frequencies
(on a 625 Hz granularity) that can be toggled by a register change. Because of the granularity, this mechanism cannot be directly
used to generate Bell 202 tones.
The way Bell 202 AFSK is implemented for Si4032 is kind of a hack, where the code toggles these two frequencies at
a rate of 1200 and 2200 Hz, which produces the two Bell 202 tones even though the actual frequencies are something else.
Additionally, the timing of 1200/2200 Hz was done in RS41HUP by using experimentally determined delays
and by disabling all interrupts, so they won't interfere with the timings.
I have attempted to implement Bell 202 frequency generation using DMA / Timers, but have failed to generate correct
frequencies that other APRS equipment are able to decode. I have tried to decode the DMA-based modulation with
some tools intended for debugging APRS and while some bytes are decoded correctly every once in a while,
the timings are mostly off for some unknown reason.
# Authors
Mikael Nousiainen OH3BHX <oh3bhx@sral.fi>

Plik binarny nie jest wyświetlany.

Plik binarny nie jest wyświetlany.

Plik binarny nie jest wyświetlany.

Wyświetl plik

@ -0,0 +1,23 @@
# APRS debugging
## Direwolf
```bash
rx_fm -f 434250000 -M fm -s 250000 -r 32000 -g 22 -d driver=rtlsdr - | direwolf -n 1 -D 1 -r 32000 -b 16 -
```
```bash
rtl_fm -f 434250000 -M fm -s 250k -r 32000 -g 22 - | direwolf -n 1 -D 1 -r 32000 -b 16 -
```
## SigPlay
See: https://bk.gnarf.org/creativity/sigplay/
```bash
rx_fm -f 434250000 -M fm -s 250000 -r 48000 -g 22 -d driver=rtlsdr - | ./aprs -
```
```bash
rtl_fm -f 434250000 -M fm -s 250k -r 32000 -g 22 - | ./aprs -
```

Wyświetl plik

@ -0,0 +1,82 @@
DF8OEs investigations about sensor access
------------------------------------------
Temperature and humidity sensor directly goes to STM. There is no interface
chip to handle them - all is done by software.
Pinout of sensor boom:
----------------------
1 - GND
2 - temperature sensor (1)
3 - GND
4 - humidity sensor1 (1)
5 - GND
6 - humidity sensor1 (2)
7 - GND
8 - heater humidity sensor
9 - heater humidity sensor
10 - GND
11 - humidity sensor2 (1)
12 - GND
13 - temperature sensor (2) and humidity sensor2 (2)
14 - GND
15 - GND
16 - GND
17 - GND
18 - GND
19 - GND
20 - GND
Counted from left to right if you position flexsensor in front of you, pins near
to you, sensor away from you, copper upside
All connections leading to sensor boom do have corresponding test points on PCB:
--------------------------------------------------------------------------------
Position PCB in front of you, flatconnector upside, sensor boom showing away from
you, TX antenna leading to you. I draw connector as a row of "+++". Testpoints are
small round copper isles (numbers correspond to sensor boom, G == GND, ? == unknown):
11
+++++++++++++++++++++++
G 4
8 6 2
13 ? 9
Investigations about temperature sensor:
----------------------------------------
Temperature sensor is resistance-based. If you insert a resistor between
pin2 and pin13 of flatconnector, the following telemetry is transmitted:
330R --> -168°
560R --> -113°
820R --> -52°
1K --> -4.1°
1.5K --> 121°
2.2K --> 319°
Pressure sensor module:
-----------------------
This module is connected to SPI2 of STM. It uses SPI_NSS and only data output
from module - SPI output from STM is not connected to module. So I think it is
a kind of polling.
2 be continued

Wyświetl plik

@ -0,0 +1,26 @@
Created by DF8OE
----------------
view into port from outside
______________________| |______________________
| |
| 1 2 3 4 5 |
| |
| 6 7 8 9 10 |
|_______________________________________________________|
1 - SWDIO (PA13)
2 - RST
3 - MCU switched 3.3V out to external device / Vcc (Boost out) 5.0V (powers the device via 3.3V)
4 - I2C2_SCL (PB10) / UART3 TX
5 - GND
6 - GND
7 - SWCLK (PA14)
8 - +U_Battery / VBAT 3.3V
9 - +VDD_MCU / PB1 * (10k + cap + 10k)
10 - I2C2_SDA (PB11) / UART3 RX

Plik binarny nie jest wyświetlany.

57
openocd_rs41.cfg 100644
Wyświetl plik

@ -0,0 +1,57 @@
# Copied and adapted from random internet sources.
# Unlocking is not needed, but every 1k block of Flash Ram is write protected
# - see: http://openocd.org/doc/html/Flash-Commands.html#flashprotect
# Typical usages:
# openocd -f ./openocd_rs41.cfg -c "init; halt; flash protect 0 0 64 off; exit"
# to unlock 64k of Flash for programming
# openocd -f ./openocd_rs41.cfg -c "program RS41ng.elf verify reset exit"
# to program the connected rs41
# openocd -f ./openocd_rs41.cfg -c "init; reset; exit"
# will reset the connected rs41
#
# Debugging with semihosting, use GDB commands:
# target remote localhost:3333
# monitor arm semihosting enable
# load build/src/RS41ng.elf
# monitor reset halt
# continue
# Normal use is with cheap STLINKv2 clone
source [find interface/stlink-v2.cfg]
# Alternative is to connect directly to a Raspberry Pi3
# Find AdaFruit tutorial to build and run OpenOCD on RPi:
# source [find interface/raspberrypi2-native.cfg]
# bcm2835gpio_swd_nums 25 24
# bcm2835gpio_speed_coeffs 194938 48
# bcm2835gpio_srst_num 18
# reset_config srst_only srst_push_pull
set WORKAREASIZE 0x2000
# RS41 uses stm32f1 cortex m3
source [find target/stm32f1x.cfg]
# example script:
proc RS41 {will_fail} {
init
sleep 200
reset
halt
wait_halt
stm32f1x unlock $will_fail
sleep 10
shutdown
}
#
# Uncommon usage:
# openocd -f ./openocd_rs41.cfg -c "init; halt; stm32f1x options_read 0; exit"
# check setings before changing them
# openocd -f ./openocd_rs41.cfg -c "init; halt; stm32f1x unlock 0; exit"
# is not needed just to re-program RS41
# openocd -f ./openocd_rs41.cfg -c "RS41 0"
# to run a macro written above
#

59
src/CMakeLists.txt 100644
Wyświetl plik

@ -0,0 +1,59 @@
project(RS41ng C CXX)
if (UNIX)
set(TOOLCHAIN_PATH /usr/bin)
set(CMAKE_C_COMPILER ${TOOLCHAIN_PATH}/arm-none-eabi-gcc)
set(CMAKE_CXX_COMPILER ${TOOLCHAIN_PATH}/arm-none-eabi-g++)
set(CMAKE_OBJCOPY ${TOOLCHAIN_PATH}/arm-none-eabi-objcopy)
else ()
set(TOOLCHAIN_PATH C:\\)
set(CMAKE_C_COMPILER ${TOOLCHAIN_PATH}/arm-none-eabi-gcc.exe)
set(CMAKE_CXX_COMPILER ${TOOLCHAIN_PATH}/arm-none-eabi-g++.exe)
set(CMAKE_OBJCOPY ${TOOLCHAIN_PATH}/arm-none-eabi-objcopy.exe)
endif ()
add_definitions(-DSTM32F100C8)
add_definitions(-DSTM32F10X_MD_VL)
add_definitions(-DUSE_STDPERIPH_DRIVER)
add_definitions(-DSUPPORT_CPLUSPLUS)
add_definitions(-D__ASSEMBLY__)
SET(LINKER_SCRIPT arm-gcc-link.ld)
SET(COMMON_FLAGS " -mcpu=cortex-m3 -mthumb -Wall -ffunction-sections -g -O3 -nostartfiles ")
SET(CMAKE_CXX_FLAGS "${COMMON_FLAGS} -std=c++11")
SET(CMAKE_C_FLAGS "${COMMON_FLAGS} -std=gnu99")
SET(CMAKE_EXE_LINKER_FLAGS "-Wl,-Map=${CMAKE_BINARY_DIR}/${PROJECT_NAME}.map -lstdc++ -O3 -Wl,--gc-sections --specs=nano.specs -T ${LINKER_SCRIPT}")
# -u _printf_float
#SET(CMAKE_EXE_LINKER_FLAGS "-Wl,-Map=${CMAKE_BINARY_DIR}/${PROJECT_NAME}.map -lstdc++ -O3 -Wl,--gc-sections --specs=rdimon.specs -lc -lrdimon -T ${LINKER_SCRIPT}")
file(GLOB_RECURSE USER_SOURCES "*.c")
file(GLOB_RECURSE USER_SOURCES_CXX "*.cpp")
file(GLOB_RECURSE USER_HEADERS "*.h")
include_directories(hal/cmsis
hal/cmsis_boot
hal/stm_lib/inc
..)
add_executable(${PROJECT_NAME}.elf ${USER_SOURCES} ${USER_SOURCES_CXX} ${USER_HEADERS} ${HAL_SOURCES} ${LINKER_SCRIPT})
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,-Map=${CMAKE_BINARY_DIR}/${PROJECT_NAME}.map")
set(HEX_FILE ${CMAKE_BINARY_DIR}/${PROJECT_NAME}.hex)
set(BIN_FILE ${CMAKE_BINARY_DIR}/${PROJECT_NAME}.bin)
add_custom_command(TARGET ${PROJECT_NAME}.elf POST_BUILD
COMMAND ${CMAKE_OBJCOPY} -Oihex $<TARGET_FILE:${PROJECT_NAME}.elf> ${HEX_FILE}
COMMAND ${CMAKE_OBJCOPY} -Obinary $<TARGET_FILE:${PROJECT_NAME}.elf> ${BIN_FILE}
COMMENT "Building ${HEX_FILE} \nBuilding ${BIN_FILE}"
COMMAND ${TOOLCHAIN_PATH}/arm-none-eabi-size ${PROJECT_NAME}.elf)
set(CMAKE_CXX_STANDARD 11)
add_custom_target(program
DEPENDS ${PROJECT_NAME}.elf
if (UNIX)
#TODO
else ()
COMMAND C:/Programs/stlink-1.3.0-win64/bin/st-flash --reset write ${BIN_FILE} 0x08000000
endif ()
COMMENT "flashing ${BIN_FILE}")

132
src/arm-gcc-link.ld 100644
Wyświetl plik

@ -0,0 +1,132 @@
OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
/* Internal Memory Map*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 0x00010000
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00002000
}
_eram = 0x20000000 + 0x00002000;
SECTIONS
{
.text :
{
KEEP(*(.isr_vector))
*(.text*)
KEEP(*(.init))
KEEP(*(.fini))
/* .ctors */
*crtbegin.o(.ctors)
*crtbegin?.o(.ctors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
*(SORT(.ctors.*))
*(.ctors)
/* .dtors */
*crtbegin.o(.dtors)
*crtbegin?.o(.dtors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
*(SORT(.dtors.*))
*(.dtors)
*(.rodata*)
KEEP(*(.eh_fram e*))
} > rom
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > rom
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > rom
__exidx_end = .;
__etext = .;
/* _sidata is used in coide startup code */
_sidata = __etext;
.data : AT (__etext)
{
__data_start__ = .;
/* _sdata is used in coide startup code */
_sdata = __data_start__;
*(vtable)
*(.data*)
. = ALIGN(8);
/* preinit data */
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP(*(.preinit_array))
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(8);
/* init data */
PROVIDE_HIDDEN (__init_array_start = .);
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(8);
/* finit data */
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP(*(SORT(.fini_array.*)))
KEEP(*(.fini_array))
PROVIDE_HIDDEN (__fini_array_end = .);
KEEP(*(.jcr*))
. = ALIGN(8);
/* All data end */
__data_end__ = .;
/* _edata is used in coide startup code */
_edata = __data_end__;
} > ram
.bss :
{
. = ALIGN(8);
__bss_start__ = .;
_sbss = __bss_start__;
*(.bss*)
*(COMMON)
. = ALIGN(8);
__bss_end__ = .;
_ebss = __bss_end__;
} > ram
.heap (COPY):
{
__end__ = .;
_end = __end__;
end = __end__;
*(.heap*)
__HeapLimit = .;
} > ram
/* .stack_dummy section doesn't contains any symbols. It is only
* used for linker to calculate size of stack sections, and assign
* values to stack symbols later */
.co_stack (NOLOAD):
{
. = ALIGN(8);
*(.co_stack .co_stack.*)
} > ram
/* Set stack top to end of ram , and stack limit move down by
* size of stack_dummy section */
__StackTop = ORIGIN(ram ) + LENGTH(ram );
__StackLimit = __StackTop - SIZEOF(.co_stack);
PROVIDE(__stack = __StackTop);
/* Check if data + heap + stack exceeds ram limit */
ASSERT(__StackLimit >= __HeapLimit, "region ram overflowed with stack")
}

Wyświetl plik

@ -0,0 +1,55 @@
#include "drivers/bmp280/bmp280.h"
#include "bmp280_handler.h"
bmp280 bmp280_dev;
bool bmp280_handler_init()
{
bmp280_dev.port = &DEFAULT_I2C_PORT;
bmp280_dev.addr = BMP280_I2C_ADDRESS_1;
bmp280_params_t bmp280_params = {
.mode = BMP280_MODE_NORMAL,
.filter = BMP280_FILTER_16,
.oversampling_pressure = BMP280_ULTRA_HIGH_RES,
.oversampling_temperature = BMP280_ULTRA_HIGH_RES,
.oversampling_humidity = BMP280_ULTRA_HIGH_RES,
.standby = BMP280_STANDBY_250,
};
bool bmp280_init_success = bmp280_init(&bmp280_dev, &bmp280_params);
if (!bmp280_init_success) {
// TODO
}
return bmp280_init_success;
}
bool bmp280_read(int32_t *temperature_celsius_100, uint32_t *pressure_mbar_100, uint32_t *humidity_percentage_100)
{
int32_t temperature_raw;
uint32_t pressure_raw;
uint32_t humidity_raw;
bool success = bmp280_read_fixed(&bmp280_dev, &temperature_raw, &pressure_raw, &humidity_raw);
if (!success) {
return false;
}
if (temperature_celsius_100) {
*temperature_celsius_100 = temperature_raw;
}
if (pressure_mbar_100) {
*pressure_mbar_100 = (uint32_t) (((float) pressure_raw) * 100.0f / 256.0f);
}
if (humidity_percentage_100) {
*humidity_percentage_100 = (uint32_t) (((float) humidity_raw) * 100.0f / 1024.0f);
}
return true;
}
bool bmp280_read_telemetry(telemetry_data *data)
{
return bmp280_read(&data->temperature_celsius_100, &data->pressure_mbar_100, &data->humidity_percentage_100);
}

Wyświetl plik

@ -0,0 +1,11 @@
#ifndef __BMP280_HANDLER_H
#define __BMP280_HANDLER_H
#include <stdbool.h>
#include "telemetry.h"
bool bmp280_handler_init();
bool bmp280_read(int32_t *temperature_celsius_100, uint32_t *pressure_mbar_100, uint32_t *humidity_percentage_100);
bool bmp280_read_telemetry(telemetry_data *data);
#endif

9
src/cmake-clean 100644
Wyświetl plik

@ -0,0 +1,9 @@
#!/bin/bash
rm -f CMakeCache.txt
rm -f RS41HUP.bin
rm -f RS41HUP.hex
rm -f RS41HUP.map
rm -f cmake_install.cmake
rm -f Makefile
rm -rf CMakeFiles/*

Wyświetl plik

@ -0,0 +1,64 @@
#include <stdio.h>
#include <stdlib.h>
#include "aprs.h"
/*
* Examples:
2019-11-27 04:37:21 EET: OH2NJR>APRS,WIDE1-1,qAR,OH2HCY-2:;434.700-C*111111z6030.65N/02444.84Er434.700MHz T118 -200 R50k OH2RUC Nurmijarvi
2019-11-27 04:52:08 EET: OH2NJR>APX210,TCPIP*,qAC,APRSFI-I3:=6030.35N/02443.91E_154/001g002t034r000P000p000b10029
TODO: speed and bearing before altitude!
2019-11-27 13:39:45 EET: OH3EUJ>APRARX,SONDEGATE,TCPIP,qAR,OH3EUJ:;R1920638 *113959h6051.11N/02331.80EO063/021/A=011240 Clb=6.6m/s t=-13.2C 402.970 MHz Type=RS41-SG Radiosonde http://bit.ly/2Bj4Sfk !woM!
2019-11-27 13:40:00 EET: OH3EUJ>APRARX,SONDEGATE,TCPIP,qAR,OH3EUJ:;R1920638 *114015h6051.17N/02331.98EO056/026/A=011536 Clb=5.0m/s t=-13.8C 402.970 MHz Type=RS41-SG Radiosonde http://bit.ly/2Bj4Sfk !wja!
*/
// TODO: add function to generate weather report
volatile uint16_t aprs_packet_counter = 0;
static void convert_degrees_to_dmh(long x, int8_t *degrees, uint8_t *minutes, uint8_t *h_minutes)
{
uint8_t sign = (uint8_t) (x > 0 ? 1 : 0);
if (!sign) {
x = -(x);
}
*degrees = (int8_t) (x / 1000000);
x = x - (*degrees * 1000000);
x = (x) * 60 / 10000;
*minutes = (uint8_t) (x / 100);
*h_minutes = (uint8_t) (x - (*minutes * 100));
if (!sign) {
*degrees = -*degrees;
}
}
#include <stdio.h>
size_t aprs_generate_position_without_timestamp(uint8_t *payload, size_t length, telemetry_data *data, char symbol, char *comment)
{
int8_t la_degrees, lo_degrees;
uint8_t la_minutes, la_h_minutes, lo_minutes, lo_h_minutes;
convert_degrees_to_dmh(data->gps.lat_raw / 10, &la_degrees, &la_minutes, &la_h_minutes);
convert_degrees_to_dmh(data->gps.lon_raw / 10, &lo_degrees, &lo_minutes, &lo_h_minutes);
aprs_packet_counter++;
// TODO: speed + bearing
return snprintf((char *) payload,
length,
("!%02d%02d.%02u%c/%03d%02u.%02u%c%c/A=%06ld/P%dS%dT%dV%d%s"),
abs(la_degrees), la_minutes, la_h_minutes,
la_degrees > 0 ? 'N' : 'S',
abs(lo_degrees), lo_minutes, lo_h_minutes,
lo_degrees > 0 ? 'E' : 'W',
symbol,
(data->gps.alt_raw / 1000) * 3280 / 1000,
aprs_packet_counter,
data->gps.sats_raw,
(int16_t) data->temperature_celsius_100,
data->battery_voltage_millivolts, // TODO: unit?
comment
);
}

Wyświetl plik

@ -0,0 +1,12 @@
#ifndef __APRS_H
#define __APRS_H
#include <stddef.h>
#include <stdint.h>
#include "gps.h"
#include "telemetry.h"
size_t aprs_generate_position_without_timestamp(uint8_t *payload, size_t length, telemetry_data *data, char symbol, char *comment);
#endif

Wyświetl plik

@ -0,0 +1,123 @@
#include <string.h>
#include <stdbool.h>
#include "ax25.h"
static inline uint16_t ax25_calculate_crc_for_bit(uint16_t crc, bool bit)
{
uint16_t result = crc;
uint16_t temp;
// XOR lsb of CRC with the latest bit
temp = crc ^ (bit ? 1U : 0U);
// Shift 16-bit CRC one bit to the right
result >>= 1U;
// If XOR result from above has lsb set
if (temp & 0x0001U) {
// Shift 16-bit CRC one bit to the right
result ^= 0x8408U;
}
return result;
}
static inline uint16_t ax25_calculate_crc_for_byte(uint16_t crc, uint8_t byte)
{
uint8_t temp = byte;
for (int i = 0; i < 8; i++, byte >>= 1U) {
bool bit = ((temp & 1U) == 1U) ? true : false;
crc = ax25_calculate_crc_for_bit(crc, bit);
}
return crc;
}
static uint16_t ax25_calculate_crc(size_t length, uint8_t *data)
{
uint16_t crc = 0xFFFF;
for (size_t i = 0; i < length; i++) {
uint8_t byte = data[i];
crc = ax25_calculate_crc_for_byte(crc, byte);
}
return crc;
}
static size_t ax25_encode_digipeater_path(char *input, char *packet_data)
{
size_t digipeaters_length = (size_t) strlen(input);
size_t packet_data_index = 0;
for (size_t index = 0; index < digipeaters_length; index++) {
if (input[index] == ',' || index == digipeaters_length - 1) {
if (input[index] != ',') {
packet_data[packet_data_index] = input[index] == '-' ? ' ' : input[index];
packet_data_index++;
}
size_t fill_count = 7 - (packet_data_index % 7);
while (fill_count > 0 && fill_count < 7) {
packet_data[packet_data_index] = ' ';
fill_count--;
packet_data_index++;
}
continue;
}
packet_data[packet_data_index] = input[index] == '-' ? ' ' : input[index];
packet_data_index++;
}
return packet_data_index;
}
size_t ax25_encode_packet_aprs(char *source, uint8_t source_ssid, char *destination, uint8_t destination_ssid,
char *digipeater_addresses, char *information_field, size_t length, uint8_t *packet_data)
{
// TODO: use length to limit packet size
ax25_packet_header *header = (ax25_packet_header *) packet_data;
header->flag = AX25_PACKET_FLAG;
memset(header->source, ' ', sizeof(header->source));
memcpy(header->source, source, 6);
header->source_ssid = (uint8_t) (source_ssid > '@' ? source_ssid - 6 : source_ssid);;
memset(header->destination, ' ', sizeof(header->destination));
memcpy(header->destination, destination, 6);
header->destination_ssid = destination_ssid;
char *digipeater_addresses_start = ((char *) header) + 1 + 14;
size_t digipeater_addresses_length = ax25_encode_digipeater_path(digipeater_addresses, digipeater_addresses_start);
// Perform bit-shifting for all addresses
uint8_t *actual_data_start = ((uint8_t *) header) + 1;
for (int i = 0; i < 14 + digipeater_addresses_length; i++) {
actual_data_start[i] = actual_data_start[i] << 1U;
}
actual_data_start[13 + digipeater_addresses_length] |= 1U;
ax25_packet_header_end *header_end = (ax25_packet_header_end *) (((uint8_t *) header) + 1 + 14 +
digipeater_addresses_length);
header_end->control_field = AX25_CONTROL_FIELD_UI_FRAME;
header_end->protocol_id = AX25_PROTOCOL_ID_NO_LAYER_3;
size_t info_length = strlen(information_field);
strcpy(header_end->information_field, information_field);
uint16_t crc = ax25_calculate_crc(14 + digipeater_addresses_length + 2 + info_length, actual_data_start);
ax25_packet_footer *footer = (ax25_packet_footer *) (((uint8_t *) header_end->information_field) + info_length);
// CRC is stored MSB first
footer->frame_check_sequence[0] = (crc & 0xFFU) ^ 0xFFU;
footer->frame_check_sequence[1] = (crc >> 8U) ^ 0xFFU;
footer->flag = AX25_PACKET_FLAG;
return 1 + 14 + digipeater_addresses_length + 2 + info_length + 2 + 1;
}

Wyświetl plik

@ -0,0 +1,33 @@
#ifndef __AX25_H
#define __AX25_H
#include <stdint.h>
#define AX25_PACKET_FLAG 0x7E
#define AX25_CONTROL_FIELD_UI_FRAME 0x03
#define AX25_PROTOCOL_ID_NO_LAYER_3 0xF0
typedef struct _ax25_packet_header {
uint8_t flag;
char destination[6];
uint8_t destination_ssid;
char source[6];
char source_ssid;
} ax25_packet_header;
typedef struct _ax25_packet_header_end {
uint8_t control_field;
uint8_t protocol_id;
char information_field[];
} ax25_packet_header_end;
typedef struct _ax25_packet_footer {
uint8_t frame_check_sequence[2];
uint8_t flag;
} ax25_packet_footer;
size_t ax25_encode_packet_aprs(char *source, uint8_t source_ssid, char *destination, uint8_t destination_ssid,
char *digipeater_addresses, char *information_field, size_t length, uint8_t *packet_data);
#endif

Wyświetl plik

@ -0,0 +1,177 @@
#include <stdbool.h>
#include <stdlib.h>
#include "codecs/ax25/ax25.h"
#include "bell.h"
#define FSK_TONE_INDEX_BELL_SPACE 0
#define FSK_TONE_INDEX_BELL_MARK 1
#define BELL_TONE_COUNT 2
typedef struct _bell_encoder {
uint32_t symbol_rate;
uint16_t flag_field_count;
fsk_tone *tones;
uint16_t data_length;
uint8_t *data;
size_t current_byte_index;
uint8_t current_bit_index;
uint8_t current_byte;
uint8_t bit_stuffing_counter;
uint16_t current_flag_field_count;
int8_t current_tone_index;
} bell_encoder;
fsk_tone bell202_tones[] = {
{
.index = FSK_TONE_INDEX_BELL_SPACE,
.frequency_hz_100 = 2200 * 100,
},
{
.index = FSK_TONE_INDEX_BELL_MARK,
.frequency_hz_100 = 1200 * 100,
},
};
fsk_tone bell103_tones[] = {
{
.index = FSK_TONE_INDEX_BELL_SPACE,
.frequency_hz_100 = 1070 * 100,
},
{
.index = FSK_TONE_INDEX_BELL_MARK,
.frequency_hz_100 = 1270 * 100,
},
};
void bell_encoder_new(fsk_encoder *encoder, uint32_t symbol_rate, uint16_t flag_field_count, fsk_tone *tones)
{
encoder->priv = malloc(sizeof(bell_encoder));
memset(encoder->priv, 0, sizeof(bell_encoder));
bell_encoder *bell = (bell_encoder *) encoder->priv;
bell->symbol_rate = symbol_rate;
bell->flag_field_count = flag_field_count;
bell->tones = tones;
}
void bell_encoder_destroy(fsk_encoder *encoder)
{
if (encoder->priv != NULL) {
free(encoder->priv);
encoder->priv = NULL;
}
}
void bell_encoder_set_data(fsk_encoder *encoder, uint16_t data_length, uint8_t *data)
{
bell_encoder *bell = (bell_encoder *) encoder->priv;
bell->data = data;
bell->data_length = data_length;
bell->current_tone_index = FSK_TONE_INDEX_BELL_MARK;
bell->current_byte_index = 0;
bell->current_bit_index = 0;
bell->current_byte = data[0];
bell->bit_stuffing_counter = 0;
bell->current_flag_field_count = 0;
}
void bell_encoder_get_tones(fsk_encoder *encoder, int8_t *tone_count, fsk_tone **tones)
{
bell_encoder *bell = (bell_encoder *) encoder->priv;
*tone_count = BELL_TONE_COUNT;
*tones = bell->tones;
}
uint32_t bell_encoder_get_tone_spacing(fsk_encoder *encoder)
{
return 0;
}
uint32_t bell_encoder_get_symbol_rate(fsk_encoder *encoder)
{
bell_encoder *bell = (bell_encoder *) encoder->priv;
return bell->symbol_rate;
}
uint32_t bell_encoder_get_symbol_delay(fsk_encoder *encoder)
{
return 0;
}
static inline void bell_encoder_toggle_tone(fsk_encoder *encoder)
{
bell_encoder *bell = (bell_encoder *) encoder->priv;
bell->current_tone_index =
(bell->current_tone_index == FSK_TONE_INDEX_BELL_MARK)
? FSK_TONE_INDEX_BELL_SPACE
: FSK_TONE_INDEX_BELL_MARK;
}
int8_t bell_encoder_next_tone(fsk_encoder *encoder)
{
bell_encoder *bell = (bell_encoder *) encoder->priv;
if (bell->current_byte_index >= bell->data_length) {
return -1;
}
bool is_flag = bell->current_byte == AX25_PACKET_FLAG;
if (is_flag) {
bell->bit_stuffing_counter = 0;
}
bool bit = (bell->current_byte >> bell->current_bit_index) & 1U;
bool stuff_bit = false;
if (bit) {
if (bell->bit_stuffing_counter == 5) {
bell_encoder_toggle_tone(encoder);
bell->bit_stuffing_counter = 0;
stuff_bit = true;
} else {
bell->bit_stuffing_counter++;
}
} else {
bell_encoder_toggle_tone(encoder);
bell->bit_stuffing_counter = 0;
}
if (stuff_bit) {
return bell->current_tone_index;
}
bell->current_bit_index = (bell->current_bit_index + 1) % 8;
if (bell->current_bit_index == 0) {
if (bell->current_byte_index == 0 && bell->current_flag_field_count < bell->flag_field_count) {
bell->current_flag_field_count++;
} else {
// return -1;
bell->current_byte_index++;
}
if (bell->current_byte_index < bell->data_length) {
bell->current_byte = bell->data[bell->current_byte_index];
}
}
return bell->current_tone_index;
}
fsk_encoder_api bell_fsk_encoder_api = {
.get_tones = bell_encoder_get_tones,
.get_tone_spacing = bell_encoder_get_tone_spacing,
.get_symbol_rate = bell_encoder_get_symbol_rate,
.get_symbol_delay = bell_encoder_get_symbol_delay,
.set_data = bell_encoder_set_data,
.next_tone = bell_encoder_next_tone,
};

Wyświetl plik

@ -0,0 +1,23 @@
#ifndef __BELL_H
#define __BELL_H
#include <stdint.h>
#include <string.h>
#include "codecs/fsk/fsk.h"
#define BELL_FLAG_FIELD_COUNT_1200 25
#define BELL_FLAG_FIELD_COUNT_300 45
void bell_encoder_new(fsk_encoder *encoder, uint32_t symbol_rate, uint16_t flag_field_count, fsk_tone *tones);
void bell_encoder_destroy(fsk_encoder *encoder);
void bell_encoder_set_data(fsk_encoder *encoder, uint16_t data_length, uint8_t *data);
void bell_encoder_get_tones(fsk_encoder *encoder, int8_t *tone_count, fsk_tone **tones);
uint32_t bell_encoder_get_symbol_rate(fsk_encoder *encoder);
int8_t bell_encoder_next_tone(fsk_encoder *encoder);
extern fsk_tone bell202_tones[];
extern fsk_tone bell103_tones[];
extern fsk_encoder_api bell_fsk_encoder_api;
#endif

Wyświetl plik

@ -0,0 +1,44 @@
#ifndef __FSK_H
#define __FSK_H
typedef struct _fsk_tone {
int8_t index;
uint32_t frequency_hz_100;
} fsk_tone;
typedef struct _fsk_encoder {
void *priv;
} fsk_encoder;
typedef struct _fsk_encoder_api {
/**
* @param encoder
* @param tone_count Set to number of tones in returned array or 0 if not used
* @param tones Set to point to array of FSK tones or NULL if not used
*/
void (*get_tones)(fsk_encoder *encoder, int8_t *tone_count, fsk_tone **tones);
/**
* @param encoder
* @return Tone spacing in 1/100th of Hz or 0 if not used
*/
uint32_t (*get_tone_spacing)(fsk_encoder *encoder);
/**
* @param encoder
* @return Symbol rate in symbols per second or 0 if not used
*/
uint32_t (*get_symbol_rate)(fsk_encoder *encoder);
/**
* @param encoder
* @return Symbol delay in 1/100th of millisecond or 0 if not used
*/
uint32_t (*get_symbol_delay)(fsk_encoder *encoder);
void (*set_data)(fsk_encoder *encoder, uint16_t data_length, uint8_t *data);
int8_t (*next_tone)(fsk_encoder *encoder);
} fsk_encoder_api;
#endif

Wyświetl plik

@ -0,0 +1,260 @@
#include <cstring>
#include <cstdlib>
#include <drivers/si5351/si5351.h>
#include "codecs/fsk/fsk.h"
#include "lib/JTEncode.h"
#include "jtencode.h"
#include "log.h"
// Some of the code is based on JTEncode examples:
//
// Simple JT65/JT9/JT4/FT8/WSPR/FSQ beacon for Arduino, with the Etherkit
// Si5351A Breakout Board, by Jason Milldrum NT7S.
//
// Transmit an abritrary message of up to 13 valid characters
// (a Type 6 message) in JT65, JT9, JT4, a type 0.0 or type 0.5 FT8 message,
// a FSQ message, or a standard Type 1 message in WSPR.
//
// Connect a momentary push button to pin 12 to use as the
// transmit trigger. Get fancy by adding your own code to trigger
// off of the time from a GPS or your PC via virtual serial.
//
// Original code based on Feld Hell beacon for Arduino by Mark
// Vandewettering K6HX, adapted for the Si5351A by Robert
// Liesenfeld AK6L <ak6l@ak6l.org>.
//
// Permission is hereby granted, free of charge, to any person obtaining
// a copy of this software and associated documentation files (the
// "Software"), to deal in the Software without restriction, including
// without limitation the rights to use, copy, modify, merge, publish,
// distribute, sublicense, and/or sell copies of the Software, and to
// permit persons to whom the Software is furnished to do so, subject
// to the following conditions:
//
// The above copyright notice and this permission notice shall be
// included in all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
// EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
// MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
// IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR
// ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF
// CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
// WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
//
// Mode defines
#define JTENCODE_TONE_SPACING_JT9 174 // ~1.74 Hz
#define JTENCODE_TONE_SPACING_JT65 269 // ~2.69 Hz
#define JTENCODE_TONE_SPACING_JT4 437 // ~4.37 Hz
#define JTENCODE_TONE_SPACING_WSPR 146 // ~1.46 Hz
#define JTENCODE_TONE_SPACING_FT8 625 // ~6.25 Hz
#define JTENCODE_TONE_SPACING_FSQ 879 // ~8.79 Hz
#define JTENCODE_TONE_DELAY_JT9 576 * 100 // Delay value for JT9-1
#define JTENCODE_TONE_DELAY_JT65 371 * 100 // Delay value for JT65A
#define JTENCODE_TONE_DELAY_JT4 229 * 100 // Delay value for JT4A
#define JTENCODE_TONE_DELAY_WSPR 683 * 100 // Delay value for WSPR
#define JTENCODE_TONE_DELAY_FT8 159 * 100 // Delay value for FT8
#define JTENCODE_TONE_DELAY_FSQ_2 500 * 100 // Delay value for 2 baud FSQ
#define JTENCODE_TONE_DELAY_FSQ_3 333 * 100 // Delay value for 3 baud FSQ
#define JTENCODE_TONE_DELAY_FSQ_4_5 222 * 100 // Delay value for 4.5 baud FSQ
#define JTENCODE_TONE_DELAY_FSQ_6 167 * 100 // Delay value for 6 baud FSQ
#define JTENCODE_SYMBOL_BUFFER_LENGTH 512
typedef struct _jtencode_mode {
uint16_t symbol_count;
uint32_t tone_delay_ms_100;
uint32_t tone_spacing_hz_100;
} jtencode_mode_descriptor;
jtencode_mode_descriptor jtencode_modes[] = {
{
.symbol_count = JT9_SYMBOL_COUNT,
.tone_delay_ms_100 = JTENCODE_TONE_DELAY_JT9,
.tone_spacing_hz_100 = JTENCODE_TONE_SPACING_JT9,
},
{
.symbol_count = JT65_SYMBOL_COUNT,
.tone_delay_ms_100 = JTENCODE_TONE_DELAY_JT65,
.tone_spacing_hz_100 = JTENCODE_TONE_SPACING_JT65,
},
{
.symbol_count = JT4_SYMBOL_COUNT,
.tone_delay_ms_100 = JTENCODE_TONE_DELAY_JT4,
.tone_spacing_hz_100 = JTENCODE_TONE_SPACING_JT4,
},
{
.symbol_count = WSPR_SYMBOL_COUNT,
.tone_delay_ms_100 = JTENCODE_TONE_DELAY_WSPR,
.tone_spacing_hz_100 = JTENCODE_TONE_SPACING_WSPR,
},
{
.symbol_count = FT8_SYMBOL_COUNT,
.tone_delay_ms_100 = JTENCODE_TONE_DELAY_FT8,
.tone_spacing_hz_100 = JTENCODE_TONE_SPACING_FT8,
},
{
.symbol_count = 0,
.tone_delay_ms_100 = JTENCODE_TONE_DELAY_FSQ_2,
.tone_spacing_hz_100 = JTENCODE_TONE_SPACING_FSQ,
},
{
.symbol_count = 0,
.tone_delay_ms_100 = JTENCODE_TONE_DELAY_FSQ_3,
.tone_spacing_hz_100 = JTENCODE_TONE_SPACING_FSQ,
},
{
.symbol_count = 0,
.tone_delay_ms_100 = JTENCODE_TONE_DELAY_FSQ_4_5,
.tone_spacing_hz_100 = JTENCODE_TONE_SPACING_FSQ,
},
{
.symbol_count = 0,
.tone_delay_ms_100 = JTENCODE_TONE_DELAY_FSQ_6,
.tone_spacing_hz_100 = JTENCODE_TONE_SPACING_FSQ,
},
};
typedef struct _jtencode_encoder {
jtencode_mode_type mode_type;
char *wspr_callsign;
char *wspr_locator;
uint8_t wspr_dbm;
char *fsq_callsign_from;
char *fsq_callsign_to;
char fsq_command;
JTEncode jtencode;
uint16_t symbol_count;
uint32_t tone_spacing;
uint32_t tone_delay;
uint8_t symbol_data[JTENCODE_SYMBOL_BUFFER_LENGTH];
size_t current_byte_index;
} jtencode_encoder;
void jtencode_encoder_new(fsk_encoder *encoder, jtencode_mode_type mode_type, char *wspr_callsign, char *wspr_locator, uint8_t wspr_dbm,
char *fsq_callsign_from, char *fsq_callsign_to, char fsq_command)
{
encoder->priv = malloc(sizeof(jtencode_encoder));
memset(encoder->priv, 0, sizeof(jtencode_encoder));
jtencode_mode_descriptor *mode_descriptor = &jtencode_modes[mode_type];
auto *jte = (jtencode_encoder *) encoder->priv;
jte->mode_type = mode_type;
jte->symbol_count = mode_descriptor->symbol_count;
jte->tone_spacing = mode_descriptor->tone_spacing_hz_100;
jte->tone_delay = mode_descriptor->tone_delay_ms_100;
jte->wspr_callsign = wspr_callsign;
jte->wspr_locator = wspr_locator;
jte->wspr_dbm = wspr_dbm;
jte->fsq_callsign_from = fsq_callsign_from;
jte->fsq_callsign_to = fsq_callsign_to;
jte->fsq_command = fsq_command;
}
void jtencode_encoder_destroy(fsk_encoder *encoder)
{
if (encoder->priv != nullptr) {
free(encoder->priv);
encoder->priv = nullptr;
}
}
void jtencode_encoder_get_tones(fsk_encoder *encoder, int8_t *tone_count, fsk_tone **tones)
{
*tone_count = 0;
*tones = nullptr;
}
uint32_t jtencode_encoder_get_tone_spacing(fsk_encoder *encoder)
{
auto *jte = (jtencode_encoder *) encoder->priv;
return jte->tone_spacing;
}
uint32_t jtencode_encoder_get_symbol_rate(fsk_encoder *encoder)
{
return 0;
}
uint32_t jtencode_encoder_get_symbol_delay(fsk_encoder *encoder)
{
auto *jte = (jtencode_encoder *) encoder->priv;
return jte->tone_delay;
}
void jtencode_encoder_set_data(fsk_encoder *encoder, uint16_t data_length, uint8_t *data)
{
auto *jte = (jtencode_encoder *) encoder->priv;
JTEncode *jtencode = &jte->jtencode;
uint8_t *symbol_data = jte->symbol_data;
jtencode_mode_type mode_type = jte->mode_type;
memset(symbol_data, 0, JTENCODE_SYMBOL_BUFFER_LENGTH);
switch (mode_type) {
case JTENCODE_MODE_JT9:
jtencode->jt9_encode((char *) data, symbol_data);
break;
case JTENCODE_MODE_JT65:
jtencode->jt65_encode((char *) data, symbol_data);
break;
case JTENCODE_MODE_JT4:
jtencode->jt4_encode((char *) data, symbol_data);
break;
case JTENCODE_MODE_WSPR:
jtencode->wspr_encode(jte->wspr_callsign, jte->wspr_locator, jte->wspr_dbm, symbol_data);
break;
case JTENCODE_MODE_FT8:
jtencode->ft8_encode((char *) data, symbol_data);
break;
case JTENCODE_MODE_FSQ_2:
case JTENCODE_MODE_FSQ_3:
case JTENCODE_MODE_FSQ_4_5:
case JTENCODE_MODE_FSQ_6:
jtencode->fsq_dir_encode(jte->fsq_callsign_from, jte->fsq_callsign_to,
jte->fsq_command, (const char *) data, symbol_data);
uint8_t j = 0;
while (symbol_data[j++] != 0xff);
jte->symbol_count = j - 1;
break;
}
jte->current_byte_index = 0;
}
int8_t jtencode_encoder_next_tone(fsk_encoder *encoder)
{
auto *jte = (jtencode_encoder *) encoder->priv;
size_t current_byte_index = jte->current_byte_index;
if (current_byte_index >= jte->symbol_count) {
log_info("last tone: %d\n", current_byte_index);
return -1;
}
int8_t tone_index = jte->symbol_data[current_byte_index];
jte->current_byte_index++;
return tone_index;
}
fsk_encoder_api jtencode_fsk_encoder_api = {
.get_tones = jtencode_encoder_get_tones,
.get_tone_spacing = jtencode_encoder_get_tone_spacing,
.get_symbol_rate = jtencode_encoder_get_symbol_rate,
.get_symbol_delay = jtencode_encoder_get_symbol_delay,
.set_data = jtencode_encoder_set_data,
.next_tone = jtencode_encoder_next_tone,
};

Wyświetl plik

@ -0,0 +1,30 @@
#ifndef __JTENCODE_H
#define __JTENCODE_H
#ifdef __cplusplus
extern "C" {
#endif
typedef enum _jtencode_mode_type {
JTENCODE_MODE_JT9 = 0,
JTENCODE_MODE_JT65,
JTENCODE_MODE_JT4,
JTENCODE_MODE_WSPR,
JTENCODE_MODE_FT8,
JTENCODE_MODE_FSQ_2,
JTENCODE_MODE_FSQ_3,
JTENCODE_MODE_FSQ_4_5,
JTENCODE_MODE_FSQ_6,
} jtencode_mode_type;
void jtencode_encoder_new(fsk_encoder *encoder, jtencode_mode_type mode_type, char *wspr_callsign, char *wspr_locator, uint8_t wspr_dbm,
char *fsq_callsign_from, char *fsq_callsign_to, char fsq_command);
void jtencode_encoder_destroy(fsk_encoder *encoder);
extern fsk_encoder_api jtencode_fsk_encoder_api;
#ifdef __cplusplus
}
#endif
#endif

Wyświetl plik

@ -0,0 +1,621 @@
GNU GENERAL PUBLIC LICENSE
Version 3, 29 June 2007
Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
Preamble
The GNU General Public License is a free, copyleft license for
software and other kinds of works.
The licenses for most software and other practical works are designed
to take away your freedom to share and change the works. By contrast,
the GNU General Public License is intended to guarantee your freedom to
share and change all versions of a program--to make sure it remains free
software for all its users. We, the Free Software Foundation, use the
GNU General Public License for most of our software; it applies also to
any other work released this way by its authors. You can apply it to
your programs, too.
When we speak of free software, we are referring to freedom, not
price. Our General Public Licenses are designed to make sure that you
have the freedom to distribute copies of free software (and charge for
them if you wish), that you receive source code or can get it if you
want it, that you can change the software or use pieces of it in new
free programs, and that you know you can do these things.
To protect your rights, we need to prevent others from denying you
these rights or asking you to surrender the rights. Therefore, you have
certain responsibilities if you distribute copies of the software, or if
you modify it: responsibilities to respect the freedom of others.
For example, if you distribute copies of such a program, whether
gratis or for a fee, you must pass on to the recipients the same
freedoms that you received. You must make sure that they, too, receive
or can get the source code. And you must show them these terms so they
know their rights.
Developers that use the GNU GPL protect your rights with two steps:
(1) assert copyright on the software, and (2) offer you this License
giving you legal permission to copy, distribute and/or modify it.
For the developers' and authors' protection, the GPL clearly explains
that there is no warranty for this free software. For both users' and
authors' sake, the GPL requires that modified versions be marked as
changed, so that their problems will not be attributed erroneously to
authors of previous versions.
Some devices are designed to deny users access to install or run
modified versions of the software inside them, although the manufacturer
can do so. This is fundamentally incompatible with the aim of
protecting users' freedom to change the software. The systematic
pattern of such abuse occurs in the area of products for individuals to
use, which is precisely where it is most unacceptable. Therefore, we
have designed this version of the GPL to prohibit the practice for those
products. If such problems arise substantially in other domains, we
stand ready to extend this provision to those domains in future versions
of the GPL, as needed to protect the freedom of users.
Finally, every program is threatened constantly by software patents.
States should not allow patents to restrict development and use of
software on general-purpose computers, but in those that do, we wish to
avoid the special danger that patents applied to a free program could
make it effectively proprietary. To prevent this, the GPL assures that
patents cannot be used to render the program non-free.
The precise terms and conditions for copying, distribution and
modification follow.
TERMS AND CONDITIONS
0. Definitions.
"This License" refers to version 3 of the GNU General Public License.
"Copyright" also means copyright-like laws that apply to other kinds of
works, such as semiconductor masks.
"The Program" refers to any copyrightable work licensed under this
License. Each licensee is addressed as "you". "Licensees" and
"recipients" may be individuals or organizations.
To "modify" a work means to copy from or adapt all or part of the work
in a fashion requiring copyright permission, other than the making of an
exact copy. The resulting work is called a "modified version" of the
earlier work or a work "based on" the earlier work.
A "covered work" means either the unmodified Program or a work based
on the Program.
To "propagate" a work means to do anything with it that, without
permission, would make you directly or secondarily liable for
infringement under applicable copyright law, except executing it on a
computer or modifying a private copy. Propagation includes copying,
distribution (with or without modification), making available to the
public, and in some countries other activities as well.
To "convey" a work means any kind of propagation that enables other
parties to make or receive copies. Mere interaction with a user through
a computer network, with no transfer of a copy, is not conveying.
An interactive user interface displays "Appropriate Legal Notices"
to the extent that it includes a convenient and prominently visible
feature that (1) displays an appropriate copyright notice, and (2)
tells the user that there is no warranty for the work (except to the
extent that warranties are provided), that licensees may convey the
work under this License, and how to view a copy of this License. If
the interface presents a list of user commands or options, such as a
menu, a prominent item in the list meets this criterion.
1. Source Code.
The "source code" for a work means the preferred form of the work
for making modifications to it. "Object code" means any non-source
form of a work.
A "Standard Interface" means an interface that either is an official
standard defined by a recognized standards body, or, in the case of
interfaces specified for a particular programming language, one that
is widely used among developers working in that language.
The "System Libraries" of an executable work include anything, other
than the work as a whole, that (a) is included in the normal form of
packaging a Major Component, but which is not part of that Major
Component, and (b) serves only to enable use of the work with that
Major Component, or to implement a Standard Interface for which an
implementation is available to the public in source code form. A
"Major Component", in this context, means a major essential component
(kernel, window system, and so on) of the specific operating system
(if any) on which the executable work runs, or a compiler used to
produce the work, or an object code interpreter used to run it.
The "Corresponding Source" for a work in object code form means all
the source code needed to generate, install, and (for an executable
work) run the object code and to modify the work, including scripts to
control those activities. However, it does not include the work's
System Libraries, or general-purpose tools or generally available free
programs which are used unmodified in performing those activities but
which are not part of the work. For example, Corresponding Source
includes interface definition files associated with source files for
the work, and the source code for shared libraries and dynamically
linked subprograms that the work is specifically designed to require,
such as by intimate data communication or control flow between those
subprograms and other parts of the work.
The Corresponding Source need not include anything that users
can regenerate automatically from other parts of the Corresponding
Source.
The Corresponding Source for a work in source code form is that
same work.
2. Basic Permissions.
All rights granted under this License are granted for the term of
copyright on the Program, and are irrevocable provided the stated
conditions are met. This License explicitly affirms your unlimited
permission to run the unmodified Program. The output from running a
covered work is covered by this License only if the output, given its
content, constitutes a covered work. This License acknowledges your
rights of fair use or other equivalent, as provided by copyright law.
You may make, run and propagate covered works that you do not
convey, without conditions so long as your license otherwise remains
in force. You may convey covered works to others for the sole purpose
of having them make modifications exclusively for you, or provide you
with facilities for running those works, provided that you comply with
the terms of this License in conveying all material for which you do
not control copyright. Those thus making or running the covered works
for you must do so exclusively on your behalf, under your direction
and control, on terms that prohibit them from making any copies of
your copyrighted material outside their relationship with you.
Conveying under any other circumstances is permitted solely under
the conditions stated below. Sublicensing is not allowed; section 10
makes it unnecessary.
3. Protecting Users' Legal Rights From Anti-Circumvention Law.
No covered work shall be deemed part of an effective technological
measure under any applicable law fulfilling obligations under article
11 of the WIPO copyright treaty adopted on 20 December 1996, or
similar laws prohibiting or restricting circumvention of such
measures.
When you convey a covered work, you waive any legal power to forbid
circumvention of technological measures to the extent such circumvention
is effected by exercising rights under this License with respect to
the covered work, and you disclaim any intention to limit operation or
modification of the work as a means of enforcing, against the work's
users, your or third parties' legal rights to forbid circumvention of
technological measures.
4. Conveying Verbatim Copies.
You may convey verbatim copies of the Program's source code as you
receive it, in any medium, provided that you conspicuously and
appropriately publish on each copy an appropriate copyright notice;
keep intact all notices stating that this License and any
non-permissive terms added in accord with section 7 apply to the code;
keep intact all notices of the absence of any warranty; and give all
recipients a copy of this License along with the Program.
You may charge any price or no price for each copy that you convey,
and you may offer support or warranty protection for a fee.
5. Conveying Modified Source Versions.
You may convey a work based on the Program, or the modifications to
produce it from the Program, in the form of source code under the
terms of section 4, provided that you also meet all of these conditions:
a) The work must carry prominent notices stating that you modified
it, and giving a relevant date.
b) The work must carry prominent notices stating that it is
released under this License and any conditions added under section
7. This requirement modifies the requirement in section 4 to
"keep intact all notices".
c) You must license the entire work, as a whole, under this
License to anyone who comes into possession of a copy. This
License will therefore apply, along with any applicable section 7
additional terms, to the whole of the work, and all its parts,
regardless of how they are packaged. This License gives no
permission to license the work in any other way, but it does not
invalidate such permission if you have separately received it.
d) If the work has interactive user interfaces, each must display
Appropriate Legal Notices; however, if the Program has interactive
interfaces that do not display Appropriate Legal Notices, your
work need not make them do so.
A compilation of a covered work with other separate and independent
works, which are not by their nature extensions of the covered work,
and which are not combined with it such as to form a larger program,
in or on a volume of a storage or distribution medium, is called an
"aggregate" if the compilation and its resulting copyright are not
used to limit the access or legal rights of the compilation's users
beyond what the individual works permit. Inclusion of a covered work
in an aggregate does not cause this License to apply to the other
parts of the aggregate.
6. Conveying Non-Source Forms.
You may convey a covered work in object code form under the terms
of sections 4 and 5, provided that you also convey the
machine-readable Corresponding Source under the terms of this License,
in one of these ways:
a) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by the
Corresponding Source fixed on a durable physical medium
customarily used for software interchange.
b) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by a
written offer, valid for at least three years and valid for as
long as you offer spare parts or customer support for that product
model, to give anyone who possesses the object code either (1) a
copy of the Corresponding Source for all the software in the
product that is covered by this License, on a durable physical
medium customarily used for software interchange, for a price no
more than your reasonable cost of physically performing this
conveying of source, or (2) access to copy the
Corresponding Source from a network server at no charge.
c) Convey individual copies of the object code with a copy of the
written offer to provide the Corresponding Source. This
alternative is allowed only occasionally and noncommercially, and
only if you received the object code with such an offer, in accord
with subsection 6b.
d) Convey the object code by offering access from a designated
place (gratis or for a charge), and offer equivalent access to the
Corresponding Source in the same way through the same place at no
further charge. You need not require recipients to copy the
Corresponding Source along with the object code. If the place to
copy the object code is a network server, the Corresponding Source
may be on a different server (operated by you or a third party)
that supports equivalent copying facilities, provided you maintain
clear directions next to the object code saying where to find the
Corresponding Source. Regardless of what server hosts the
Corresponding Source, you remain obligated to ensure that it is
available for as long as needed to satisfy these requirements.
e) Convey the object code using peer-to-peer transmission, provided
you inform other peers where the object code and Corresponding
Source of the work are being offered to the general public at no
charge under subsection 6d.
A separable portion of the object code, whose source code is excluded
from the Corresponding Source as a System Library, need not be
included in conveying the object code work.
A "User Product" is either (1) a "consumer product", which means any
tangible personal property which is normally used for personal, family,
or household purposes, or (2) anything designed or sold for incorporation
into a dwelling. In determining whether a product is a consumer product,
doubtful cases shall be resolved in favor of coverage. For a particular
product received by a particular user, "normally used" refers to a
typical or common use of that class of product, regardless of the status
of the particular user or of the way in which the particular user
actually uses, or expects or is expected to use, the product. A product
is a consumer product regardless of whether the product has substantial
commercial, industrial or non-consumer uses, unless such uses represent
the only significant mode of use of the product.
"Installation Information" for a User Product means any methods,
procedures, authorization keys, or other information required to install
and execute modified versions of a covered work in that User Product from
a modified version of its Corresponding Source. The information must
suffice to ensure that the continued functioning of the modified object
code is in no case prevented or interfered with solely because
modification has been made.
If you convey an object code work under this section in, or with, or
specifically for use in, a User Product, and the conveying occurs as
part of a transaction in which the right of possession and use of the
User Product is transferred to the recipient in perpetuity or for a
fixed term (regardless of how the transaction is characterized), the
Corresponding Source conveyed under this section must be accompanied
by the Installation Information. But this requirement does not apply
if neither you nor any third party retains the ability to install
modified object code on the User Product (for example, the work has
been installed in ROM).
The requirement to provide Installation Information does not include a
requirement to continue to provide support service, warranty, or updates
for a work that has been modified or installed by the recipient, or for
the User Product in which it has been modified or installed. Access to a
network may be denied when the modification itself materially and
adversely affects the operation of the network or violates the rules and
protocols for communication across the network.
Corresponding Source conveyed, and Installation Information provided,
in accord with this section must be in a format that is publicly
documented (and with an implementation available to the public in
source code form), and must require no special password or key for
unpacking, reading or copying.
7. Additional Terms.
"Additional permissions" are terms that supplement the terms of this
License by making exceptions from one or more of its conditions.
Additional permissions that are applicable to the entire Program shall
be treated as though they were included in this License, to the extent
that they are valid under applicable law. If additional permissions
apply only to part of the Program, that part may be used separately
under those permissions, but the entire Program remains governed by
this License without regard to the additional permissions.
When you convey a copy of a covered work, you may at your option
remove any additional permissions from that copy, or from any part of
it. (Additional permissions may be written to require their own
removal in certain cases when you modify the work.) You may place
additional permissions on material, added by you to a covered work,
for which you have or can give appropriate copyright permission.
Notwithstanding any other provision of this License, for material you
add to a covered work, you may (if authorized by the copyright holders of
that material) supplement the terms of this License with terms:
a) Disclaiming warranty or limiting liability differently from the
terms of sections 15 and 16 of this License; or
b) Requiring preservation of specified reasonable legal notices or
author attributions in that material or in the Appropriate Legal
Notices displayed by works containing it; or
c) Prohibiting misrepresentation of the origin of that material, or
requiring that modified versions of such material be marked in
reasonable ways as different from the original version; or
d) Limiting the use for publicity purposes of names of licensors or
authors of the material; or
e) Declining to grant rights under trademark law for use of some
trade names, trademarks, or service marks; or
f) Requiring indemnification of licensors and authors of that
material by anyone who conveys the material (or modified versions of
it) with contractual assumptions of liability to the recipient, for
any liability that these contractual assumptions directly impose on
those licensors and authors.
All other non-permissive additional terms are considered "further
restrictions" within the meaning of section 10. If the Program as you
received it, or any part of it, contains a notice stating that it is
governed by this License along with a term that is a further
restriction, you may remove that term. If a license document contains
a further restriction but permits relicensing or conveying under this
License, you may add to a covered work material governed by the terms
of that license document, provided that the further restriction does
not survive such relicensing or conveying.
If you add terms to a covered work in accord with this section, you
must place, in the relevant source files, a statement of the
additional terms that apply to those files, or a notice indicating
where to find the applicable terms.
Additional terms, permissive or non-permissive, may be stated in the
form of a separately written license, or stated as exceptions;
the above requirements apply either way.
8. Termination.
You may not propagate or modify a covered work except as expressly
provided under this License. Any attempt otherwise to propagate or
modify it is void, and will automatically terminate your rights under
this License (including any patent licenses granted under the third
paragraph of section 11).
However, if you cease all violation of this License, then your
license from a particular copyright holder is reinstated (a)
provisionally, unless and until the copyright holder explicitly and
finally terminates your license, and (b) permanently, if the copyright
holder fails to notify you of the violation by some reasonable means
prior to 60 days after the cessation.
Moreover, your license from a particular copyright holder is
reinstated permanently if the copyright holder notifies you of the
violation by some reasonable means, this is the first time you have
received notice of violation of this License (for any work) from that
copyright holder, and you cure the violation prior to 30 days after
your receipt of the notice.
Termination of your rights under this section does not terminate the
licenses of parties who have received copies or rights from you under
this License. If your rights have been terminated and not permanently
reinstated, you do not qualify to receive new licenses for the same
material under section 10.
9. Acceptance Not Required for Having Copies.
You are not required to accept this License in order to receive or
run a copy of the Program. Ancillary propagation of a covered work
occurring solely as a consequence of using peer-to-peer transmission
to receive a copy likewise does not require acceptance. However,
nothing other than this License grants you permission to propagate or
modify any covered work. These actions infringe copyright if you do
not accept this License. Therefore, by modifying or propagating a
covered work, you indicate your acceptance of this License to do so.
10. Automatic Licensing of Downstream Recipients.
Each time you convey a covered work, the recipient automatically
receives a license from the original licensors, to run, modify and
propagate that work, subject to this License. You are not responsible
for enforcing compliance by third parties with this License.
An "entity transaction" is a transaction transferring control of an
organization, or substantially all assets of one, or subdividing an
organization, or merging organizations. If propagation of a covered
work results from an entity transaction, each party to that
transaction who receives a copy of the work also receives whatever
licenses to the work the party's predecessor in interest had or could
give under the previous paragraph, plus a right to possession of the
Corresponding Source of the work from the predecessor in interest, if
the predecessor has it or can get it with reasonable efforts.
You may not impose any further restrictions on the exercise of the
rights granted or affirmed under this License. For example, you may
not impose a license fee, royalty, or other charge for exercise of
rights granted under this License, and you may not initiate litigation
(including a cross-claim or counterclaim in a lawsuit) alleging that
any patent claim is infringed by making, using, selling, offering for
sale, or importing the Program or any portion of it.
11. Patents.
A "contributor" is a copyright holder who authorizes use under this
License of the Program or a work on which the Program is based. The
work thus licensed is called the contributor's "contributor version".
A contributor's "essential patent claims" are all patent claims
owned or controlled by the contributor, whether already acquired or
hereafter acquired, that would be infringed by some manner, permitted
by this License, of making, using, or selling its contributor version,
but do not include claims that would be infringed only as a
consequence of further modification of the contributor version. For
purposes of this definition, "control" includes the right to grant
patent sublicenses in a manner consistent with the requirements of
this License.
Each contributor grants you a non-exclusive, worldwide, royalty-free
patent license under the contributor's essential patent claims, to
make, use, sell, offer for sale, import and otherwise run, modify and
propagate the contents of its contributor version.
In the following three paragraphs, a "patent license" is any express
agreement or commitment, however denominated, not to enforce a patent
(such as an express permission to practice a patent or covenant not to
sue for patent infringement). To "grant" such a patent license to a
party means to make such an agreement or commitment not to enforce a
patent against the party.
If you convey a covered work, knowingly relying on a patent license,
and the Corresponding Source of the work is not available for anyone
to copy, free of charge and under the terms of this License, through a
publicly available network server or other readily accessible means,
then you must either (1) cause the Corresponding Source to be so
available, or (2) arrange to deprive yourself of the benefit of the
patent license for this particular work, or (3) arrange, in a manner
consistent with the requirements of this License, to extend the patent
license to downstream recipients. "Knowingly relying" means you have
actual knowledge that, but for the patent license, your conveying the
covered work in a country, or your recipient's use of the covered work
in a country, would infringe one or more identifiable patents in that
country that you have reason to believe are valid.
If, pursuant to or in connection with a single transaction or
arrangement, you convey, or propagate by procuring conveyance of, a
covered work, and grant a patent license to some of the parties
receiving the covered work authorizing them to use, propagate, modify
or convey a specific copy of the covered work, then the patent license
you grant is automatically extended to all recipients of the covered
work and works based on it.
A patent license is "discriminatory" if it does not include within
the scope of its coverage, prohibits the exercise of, or is
conditioned on the non-exercise of one or more of the rights that are
specifically granted under this License. You may not convey a covered
work if you are a party to an arrangement with a third party that is
in the business of distributing software, under which you make payment
to the third party based on the extent of your activity of conveying
the work, and under which the third party grants, to any of the
parties who would receive the covered work from you, a discriminatory
patent license (a) in connection with copies of the covered work
conveyed by you (or copies made from those copies), or (b) primarily
for and in connection with specific products or compilations that
contain the covered work, unless you entered into that arrangement,
or that patent license was granted, prior to 28 March 2007.
Nothing in this License shall be construed as excluding or limiting
any implied license or other defenses to infringement that may
otherwise be available to you under applicable patent law.
12. No Surrender of Others' Freedom.
If conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License. If you cannot convey a
covered work so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you may
not convey it at all. For example, if you agree to terms that obligate you
to collect a royalty for further conveying from those to whom you convey
the Program, the only way you could satisfy both those terms and this
License would be to refrain entirely from conveying the Program.
13. Use with the GNU Affero General Public License.
Notwithstanding any other provision of this License, you have
permission to link or combine any covered work with a work licensed
under version 3 of the GNU Affero General Public License into a single
combined work, and to convey the resulting work. The terms of this
License will continue to apply to the part which is the covered work,
but the special requirements of the GNU Affero General Public License,
section 13, concerning interaction through a network will apply to the
combination as such.
14. Revised Versions of this License.
The Free Software Foundation may publish revised and/or new versions of
the GNU General Public License from time to time. Such new versions will
be similar in spirit to the present version, but may differ in detail to
address new problems or concerns.
Each version is given a distinguishing version number. If the
Program specifies that a certain numbered version of the GNU General
Public License "or any later version" applies to it, you have the
option of following the terms and conditions either of that numbered
version or of any later version published by the Free Software
Foundation. If the Program does not specify a version number of the
GNU General Public License, you may choose any version ever published
by the Free Software Foundation.
If the Program specifies that a proxy can decide which future
versions of the GNU General Public License can be used, that proxy's
public statement of acceptance of a version permanently authorizes you
to choose that version for the Program.
Later license versions may give you additional or different
permissions. However, no additional obligations are imposed on any
author or copyright holder as a result of your choosing to follow a
later version.
15. Disclaimer of Warranty.
THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
16. Limitation of Liability.
IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGES.
17. Interpretation of Sections 15 and 16.
If the disclaimer of warranty and limitation of liability provided
above cannot be given local legal effect according to their terms,
reviewing courts shall apply local law that most closely approximates
an absolute waiver of all civil liability in connection with the
Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee.
END OF TERMS AND CONDITIONS

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,257 @@
/*
* JTEncode.h - JT65/JT9/WSPR/FSQ encoder library for Arduino
*
* Copyright (C) 2015-2018 Jason Milldrum <milldrum@gmail.com>
*
* Based on the algorithms presented in the WSJT software suite.
* Thanks to Andy Talbot G4JNT for the whitepaper on the WSPR encoding
* process that helped me to understand all of this.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef JTENCODE_H
#define JTENCODE_H
#include "int.h"
#include "rs_common.h"
#include <cstdint>
#define JT65_SYMBOL_COUNT 126
#define JT9_SYMBOL_COUNT 85
#define JT4_SYMBOL_COUNT 207
#define WSPR_SYMBOL_COUNT 162
#define FT8_SYMBOL_COUNT 79
#define JT65_ENCODE_COUNT 63
#define JT9_ENCODE_COUNT 69
#define FT8_ENCODE_COUNT 77
#define JT9_BIT_COUNT 206
#define JT4_BIT_COUNT 206
#define WSPR_BIT_COUNT 162
#define FT8_BIT_COUNT 174
// Define the structure of a varicode table
typedef struct fsq_varicode
{
uint8_t ch;
uint8_t var[2];
} Varicode;
// The FSQ varicode table, based on the FSQ Varicode V3.0
// document provided by Murray Greenman, ZL1BPU
const Varicode fsq_code_table[] =
{
{' ', {00, 00}}, // space
{'!', {11, 30}},
{'"', {12, 30}},
{'#', {13, 30}},
{'$', {14, 30}},
{'%', {15, 30}},
{'&', {16, 30}},
{'\'', {17, 30}},
{'(', {18, 30}},
{')', {19, 30}},
{'*', {20, 30}},
{'+', {21, 30}},
{',', {27, 29}},
{'-', {22, 30}},
{'.', {27, 00}},
{'/', {23, 30}},
{'0', {10, 30}},
{'1', {01, 30}},
{'2', {02, 30}},
{'3', {03, 30}},
{'4', {04, 30}},
{'5', {05, 30}},
{'6', {06, 30}},
{'7', {07, 30}},
{'8', {8, 30}},
{'9', {9, 30}},
{':', {24, 30}},
{';', {25, 30}},
{'<', {26, 30}},
{'=', {00, 31}},
{'>', {27, 30}},
{'?', {28, 29}},
{'@', {00, 29}},
{'A', {01, 29}},
{'B', {02, 29}},
{'C', {03, 29}},
{'D', {04, 29}},
{'E', {05, 29}},
{'F', {06, 29}},
{'G', {07, 29}},
{'H', {8, 29}},
{'I', {9, 29}},
{'J', {10, 29}},
{'K', {11, 29}},
{'L', {12, 29}},
{'M', {13, 29}},
{'N', {14, 29}},
{'O', {15, 29}},
{'P', {16, 29}},
{'Q', {17, 29}},
{'R', {18, 29}},
{'S', {19, 29}},
{'T', {20, 29}},
{'U', {21, 29}},
{'V', {22, 29}},
{'W', {23, 29}},
{'X', {24, 29}},
{'Y', {25, 29}},
{'Z', {26, 29}},
{'[', {01, 31}},
{'\\', {02, 31}},
{']', {03, 31}},
{'^', {04, 31}},
{'_', {05, 31}},
{'`', {9, 31}},
{'a', {01, 00}},
{'b', {02, 00}},
{'c', {03, 00}},
{'d', {04, 00}},
{'e', {05, 00}},
{'f', {06, 00}},
{'g', {07, 00}},
{'h', {8, 00}},
{'i', {9, 00}},
{'j', {10, 00}},
{'k', {11, 00}},
{'l', {12, 00}},
{'m', {13, 00}},
{'n', {14, 00}},
{'o', {15, 00}},
{'p', {16, 00}},
{'q', {17, 00}},
{'r', {18, 00}},
{'s', {19, 00}},
{'t', {20, 00}},
{'u', {21, 00}},
{'v', {22, 00}},
{'w', {23, 00}},
{'x', {24, 00}},
{'y', {25, 00}},
{'z', {26, 00}},
{'{', {06, 31}},
{'|', {07, 31}},
{'}', {8, 31}},
{'~', {00, 30}},
{127, {28, 31}}, // DEL
{13, {28, 00}}, // CR
{10, {28, 00}}, // LF
{0, {28, 30}}, // IDLE
{241, {10, 31}}, // plus/minus
{246, {11, 31}}, // division sign
{248, {12, 31}}, // degrees sign
{158, {13, 31}}, // multiply sign
{156, {14, 31}}, // pound sterling sign
{8, {27, 31}} // BS
};
const uint8_t crc8_table[] = {
0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31,
0x24, 0x23, 0x2a, 0x2d, 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65,
0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, 0xe0, 0xe7, 0xee, 0xe9,
0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd,
0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1,
0xb4, 0xb3, 0xba, 0xbd, 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2,
0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, 0xb7, 0xb0, 0xb9, 0xbe,
0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a,
0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16,
0x03, 0x04, 0x0d, 0x0a, 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42,
0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, 0x89, 0x8e, 0x87, 0x80,
0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4,
0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8,
0xdd, 0xda, 0xd3, 0xd4, 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c,
0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, 0x19, 0x1e, 0x17, 0x10,
0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34,
0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f,
0x6a, 0x6d, 0x64, 0x63, 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b,
0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, 0xae, 0xa9, 0xa0, 0xa7,
0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83,
0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef,
0xfa, 0xfd, 0xf4, 0xf3
};
const uint8_t jt9i[JT9_BIT_COUNT] = {
0x00, 0x80, 0x40, 0xc0, 0x20, 0xa0, 0x60, 0x10, 0x90, 0x50, 0x30, 0xb0, 0x70,
0x08, 0x88, 0x48, 0xc8, 0x28, 0xa8, 0x68, 0x18, 0x98, 0x58, 0x38, 0xb8, 0x78,
0x04, 0x84, 0x44, 0xc4, 0x24, 0xa4, 0x64, 0x14, 0x94, 0x54, 0x34, 0xb4, 0x74,
0x0c, 0x8c, 0x4c, 0xcc, 0x2c, 0xac, 0x6c, 0x1c, 0x9c, 0x5c, 0x3c, 0xbc, 0x7c,
0x02, 0x82, 0x42, 0xc2, 0x22, 0xa2, 0x62, 0x12, 0x92, 0x52, 0x32, 0xb2, 0x72,
0x0a, 0x8a, 0x4a, 0xca, 0x2a, 0xaa, 0x6a, 0x1a, 0x9a, 0x5a, 0x3a, 0xba, 0x7a,
0x06, 0x86, 0x46, 0xc6, 0x26, 0xa6, 0x66, 0x16, 0x96, 0x56, 0x36, 0xb6, 0x76,
0x0e, 0x8e, 0x4e, 0x2e, 0xae, 0x6e, 0x1e, 0x9e, 0x5e, 0x3e, 0xbe, 0x7e, 0x01,
0x81, 0x41, 0xc1, 0x21, 0xa1, 0x61, 0x11, 0x91, 0x51, 0x31, 0xb1, 0x71, 0x09,
0x89, 0x49, 0xc9, 0x29, 0xa9, 0x69, 0x19, 0x99, 0x59, 0x39, 0xb9, 0x79, 0x05,
0x85, 0x45, 0xc5, 0x25, 0xa5, 0x65, 0x15, 0x95, 0x55, 0x35, 0xb5, 0x75, 0x0d,
0x8d, 0x4d, 0xcd, 0x2d, 0xad, 0x6d, 0x1d, 0x9d, 0x5d, 0x3d, 0xbd, 0x7d, 0x03,
0x83, 0x43, 0xc3, 0x23, 0xa3, 0x63, 0x13, 0x93, 0x53, 0x33, 0xb3, 0x73, 0x0b,
0x8b, 0x4b, 0xcb, 0x2b, 0xab, 0x6b, 0x1b, 0x9b, 0x5b, 0x3b, 0xbb, 0x7b, 0x07,
0x87, 0x47, 0xc7, 0x27, 0xa7, 0x67, 0x17, 0x97, 0x57, 0x37, 0xb7, 0x77, 0x0f,
0x8f, 0x4f, 0x2f, 0xaf, 0x6f, 0x1f, 0x9f, 0x5f, 0x3f, 0xbf, 0x7f
};
class JTEncode
{
public:
JTEncode(void);
void jt65_encode(const char *, uint8_t *);
void jt9_encode(const char *, uint8_t *);
void jt4_encode(const char *, uint8_t *);
void wspr_encode(const char *, const char *, const uint8_t, uint8_t *);
void fsq_encode(const char *, const char *, uint8_t *);
void fsq_dir_encode(const char *, const char *, const char, const char *, uint8_t *);
void ft8_encode(const char *, uint8_t *);
private:
uint8_t jt_code(char);
uint8_t ft_code(char);
uint8_t wspr_code(char);
uint8_t gray_code(uint8_t);
int8_t hex2int(char);
void jt_message_prep(char *);
void ft_message_prep(char *);
void wspr_message_prep(char *, char *, uint8_t);
void jt65_bit_packing(char *, uint8_t *);
void jt9_bit_packing(char *, uint8_t *);
void wspr_bit_packing(uint8_t *);
void ft8_bit_packing(char*, uint8_t*);
void jt65_interleave(uint8_t *);
void jt9_interleave(uint8_t *);
void wspr_interleave(uint8_t *);
void jt9_packbits(uint8_t *, uint8_t *);
void jt_gray_code(uint8_t *, uint8_t);
void ft8_encode(uint8_t*, uint8_t*);
void jt65_merge_sync_vector(uint8_t *, uint8_t *);
void jt9_merge_sync_vector(uint8_t *, uint8_t *);
void jt4_merge_sync_vector(uint8_t *, uint8_t *);
void wspr_merge_sync_vector(uint8_t *, uint8_t *);
void ft8_merge_sync_vector(uint8_t*, uint8_t*);
void convolve(uint8_t *, uint8_t *, uint8_t, uint8_t);
void rs_encode(uint8_t *, uint8_t *);
void encode_rs_int(void *,data_t *, data_t *);
void free_rs_int(void *);
void * init_rs_int(int, int, int, int, int, int);
uint8_t crc8(const char *);
void * rs_inst;
char callsign[7];
char locator[5];
uint8_t power;
};
#endif

Wyświetl plik

@ -0,0 +1,303 @@
JT65/JT9/JT4/FT8/WSPR/FSQ Encoder Library for Arduino
=====================================================
This library very simply generates a set of channel symbols for JT65, JT9, JT4, FT8, or WSPR based on the user providing a properly formatted Type 6 message for JT65, JT9, or JT4 (which is 13 valid characters), Type 0.0 or 0.5 message for FT8 (v2.0.0 protocol) or a callsign, Maidenhead grid locator, and power output for WSPR. It will also generate an arbitrary FSQ message of up to 200 characters in both directed and non-directed format. When paired with a synthesizer that can output frequencies in fine, phase-continuous tuning steps (such as the Si5351), then a beacon or telemetry transmitter can be created which can change the transmitted characters as needed from the Arduino.
Please feel free to use the issues feature of GitHub if you run into problems or have suggestions for important features to implement.
Thanks For Your Support!
------------------------
If you would like to support my library development efforts, I would ask that you please consider sending a [one-time PayPal tip](https://paypal.me/NT7S) or [subscribe to me on SubscribeStar](https://www.subscribestar.com/nt7s) for an ongoing contribution.. Thank you!
Hardware Requirements and Setup
-------------------------------
This library has been written for the Arduino platform and has been successfully tested on the Arduino Uno, an Uno clone, an Arduino Zero clone, and a NodeMCU. Since the library itself does not access the hardware, there is no reason it should not run on any Arduino model of recent vintage as long as it has at least 2 kB of RAM.
How To Install
--------------
The best way to install the library is via the Arduino Library Manager, which is available if you are using Arduino IDE version 1.6.2 or greater. To install it this way, simply go to the menu Sketch > Include Library > Manage Libraries..., and then in the search box at the upper-right, type "Etherkit JTEncode". Click on the entry in the list below, then click on the provided "Install" button. By installing the library this way, you will always have notifications of future library updates, and can easily switch between library versions.
If you need to or would like to install the library in the old way, then you can download a copy of the library in a ZIP file. Download a ZIP file of the library from the GitHub repository by going to [this page](https://github.com/etherkit/JTEncode/releases) and clicking the "Source code (zip)" link under the latest release. Finally, open the Arduino IDE, select menu Sketch > Import Library... > Add Library..., and select the ZIP that you just downloaded.
RAM Usage
---------
Most of the encoding functions need to manipulate multiple arrays of symbols in RAM at the same time, and therefore are quite RAM intensive. Care has been taken to put as much data into program memory as is possible, but the encoding functions still can cause problems with the low RAM microcontrollers such as the ATmegaxx8 series. If you are using these, then please be sure to call them only once when a transmit buffer needs to be created or changed, and call them separately of other subroutine calls. When using other microcontrollers that have more RAM, such as most of the ARM ICs, this won't be as much of a problem. If you see unusual freezes, that almost certainly indicates a RAM shortage.
Example
-------
There is a simple example that is placed in your examples menu under JTEncode. Open this to see how to incorporate this library with your code. The example provided with with the library is meant to be used in conjunction with the [Etherkit Si5351A Breakout Board](https://www.etherkit.com/rf-modules/si5351a-breakout-board.html), although it could be modified to use with other synthesizers which meet the technical requirements of the JT65/JT9/JT4/WSPR/FSQ modes.
To run this example, be sure to download the [Si5351Arduino](https://github.com/etherkit/Si5351Arduino) library and follow the instructions there to connect the Si5351A Breakout Board to your Arduino. In order to trigger transmissions, you will also need to connect a momentary pushbutton from pin 12 of the Arduino to ground.
The example sketch itself is fairly straightforward. JT65, JT9, JT4, FT8, WSPR, and FSQ modes are modulated in same way: phase-continuous multiple-frequency shift keying (MFSK). The message to be transmitted is passed to the JTEncode method corresponding to the desired mode, along with a pointer to an array which holds the returned channel symbols. When the pushbutton is pushed, the sketch then transmits each channel symbol sequentially as an offset from the base frequency given in the sketch define section.
An instance of the JTEncode object is created:
JTEncode jtencode;
On sketch startup, the mode parameters are set based on which mode is currently selected (by the DEFAULT_MODE define):
// Set the proper frequency, tone spacing, symbol count, and
// tone delay depending on mode
switch(cur_mode)
{
case MODE_JT9:
freq = JT9_DEFAULT_FREQ;
symbol_count = JT9_SYMBOL_COUNT; // From the library defines
tone_spacing = JT9_TONE_SPACING;
tone_delay = JT9_DELAY;
break;
case MODE_JT65:
freq = JT65_DEFAULT_FREQ;
symbol_count = JT65_SYMBOL_COUNT; // From the library defines
tone_spacing = JT65_TONE_SPACING;
tone_delay = JT65_DELAY;
break;
case MODE_JT4:
freq = JT4_DEFAULT_FREQ;
symbol_count = JT4_SYMBOL_COUNT; // From the library defines
tone_spacing = JT4_TONE_SPACING;
tone_delay = JT4_DELAY;
break;
case MODE_WSPR:
freq = WSPR_DEFAULT_FREQ;
symbol_count = WSPR_SYMBOL_COUNT; // From the library defines
tone_spacing = WSPR_TONE_SPACING;
tone_delay = WSPR_DELAY;
break;
case MODE_FT8:
freq = FT8_DEFAULT_FREQ;
symbol_count = FT8_SYMBOL_COUNT; // From the library defines
tone_spacing = FT8_TONE_SPACING;
tone_delay = FT8_DELAY;
break;
case MODE_FSQ_2:
freq = FSQ_DEFAULT_FREQ;
tone_spacing = FSQ_TONE_SPACING;
tone_delay = FSQ_2_DELAY;
break;
case MODE_FSQ_3:
freq = FSQ_DEFAULT_FREQ;
tone_spacing = FSQ_TONE_SPACING;
tone_delay = FSQ_3_DELAY;
break;
case MODE_FSQ_4_5:
freq = FSQ_DEFAULT_FREQ;
tone_spacing = FSQ_TONE_SPACING;
tone_delay = FSQ_4_5_DELAY;
break;
case MODE_FSQ_6:
freq = FSQ_DEFAULT_FREQ;
tone_spacing = FSQ_TONE_SPACING;
tone_delay = FSQ_6_DELAY;
break;
}
Note that the number of channel symbols for each mode is defined in the library, so you can use those defines to initialize your own symbol array sizes.
Before transmit, the proper class method is chosen based on the desired mode, then the transmit symbol buffer and the other mode information is set:
// Set the proper frequency and timer CTC depending on mode
switch(cur_mode)
{
case MODE_JT9:
jtencode.jt9_encode(message, tx_buffer);
break;
case MODE_JT65:
jtencode.jt65_encode(message, tx_buffer);
break;
case MODE_JT4:
jtencode.jt4_encode(message, tx_buffer);
break;
case MODE_WSPR:
jtencode.wspr_encode(call, loc, dbm, tx_buffer);
break;
case MODE_FT8:
jtencode.ft_encode(message, tx_buffer);
break;
case MODE_FSQ_2:
case MODE_FSQ_3:
case MODE_FSQ_4_5:
case MODE_FSQ_6:
jtencode.fsq_dir_encode(call, "n0call", " ", "hello world", tx_buffer);
break;
}
As mentioned above, it is best if the message encoding functions are called only when needed, in its own subroutine.
Once the channel symbols have been generated, it is a simple matter of transmitting them in sequence, each the correct amount of time:
// Now transmit the channel symbols
for(i = 0; i < symbol_count; i++)
{
si5351.set_freq((freq * 100) + (tx_buffer[i] * tone_spacing), SI5351_CLK0);
delay(tone_delay);
}
Public Methods
------------------
### jt65_encode()
```
/*
* jt65_encode(const char * message, uint8_t * symbols)
*
* Takes an arbitrary message of up to 13 allowable characters and returns
* a channel symbol table.
*
* message - Plaintext Type 6 message.
* symbols - Array of channel symbols to transmit returned by the method.
* Ensure that you pass a uint8_t array of at least size JT65_SYMBOL_COUNT to the method.
*
*/
```
### jt9_encode()
```
/*
* jt9_encode(const char * message, uint8_t * symbols)
*
* Takes an arbitrary message of up to 13 allowable characters and returns
* a channel symbol table.
*
* message - Plaintext Type 6 message.
* symbols - Array of channel symbols to transmit returned by the method.
* Ensure that you pass a uint8_t array of at least size JT9_SYMBOL_COUNT to the method.
*
*/
```
### jt4_encode()
```
/*
* jt4_encode(const char * message, uint8_t * symbols)
*
* Takes an arbitrary message of up to 13 allowable characters and returns
* a channel symbol table.
*
* message - Plaintext Type 6 message.
* symbols - Array of channel symbols to transmit returned by the method.
* Ensure that you pass a uint8_t array of at least size JT9_SYMBOL_COUNT to the method.
*
*/
```
### wspr_encode()
```
/*
* wspr_encode(const char * call, const char * loc, const uint8_t dbm, uint8_t * symbols)
*
* Takes an arbitrary message of up to 13 allowable characters and returns
*
* call - Callsign (6 characters maximum).
* loc - Maidenhead grid locator (4 characters maximum).
* dbm - Output power in dBm.
* symbols - Array of channel symbols to transmit returned by the method.
* Ensure that you pass a uint8_t array of at least size WSPR_SYMBOL_COUNT to the method.
*
*/
```
### ft8_encode()
```
/*
* ft8_encode(const char * message, uint8_t * symbols)
*
* Takes an arbitrary message of up to 13 allowable characters or a telemetry message
* of up to 18 hexadecimal digit (in string format) and returns a channel symbol table.
* Encoded for the FT8 protocol used in WSJT-X v2.0 and beyond (79 channel symbols).
*
* message - Type 0.0 free text message or Type 0.5 telemetry message.
* symbols - Array of channel symbols to transmit returned by the method.
* Ensure that you pass a uint8_t array of at least size FT8_SYMBOL_COUNT to the method.
*
*/
```
### fsq_encode()
```
/*
* fsq_encode(const char * from_call, const char * message, uint8_t * symbols)
*
* Takes an arbitrary message and returns a FSQ channel symbol table.
*
* from_call - Callsign of issuing station (maximum size: 20)
* message - Null-terminated message string, no greater than 130 chars in length
* symbols - Array of channel symbols to transmit returned by the method.
* Ensure that you pass a uint8_t array of at least the size of the message
* plus 5 characters to the method. Terminated in 0xFF.
*
*/
```
### fsq_dir_encode()
```
/*
* fsq_dir_encode(const char * from_call, const char * to_call, const char cmd, const char * message, uint8_t * symbols)
*
* Takes an arbitrary message and returns a FSQ channel symbol table.
*
* from_call - Callsign from which message is directed (maximum size: 20)
* to_call - Callsign to which message is directed (maximum size: 20)
* cmd - Directed command
* message - Null-terminated message string, no greater than 100 chars in length
* symbols - Array of channel symbols to transmit returned by the method.
* Ensure that you pass a uint8_t array of at least the size of the message
* plus 5 characters to the method. Terminated in 0xFF.
*
*/
```
Tokens
------
Here are the defines, structs, and enumerations you will find handy to use with the library.
Defines:
JT65_SYMBOL_COUNT, JT9_SYMBOL_COUNT, JT4_SYMBOL_COUNT, WSPR_SYMBOL_COUNT, FT8_SYMBOL_COUNT
Acknowledgements
----------------
Many thanks to Joe Taylor K1JT for his innovative work in amateur radio. We are lucky to have him. The algorithms in this program were derived from the source code in the [WSJT-X](https://sourceforge.net/p/wsjt/) suite of applications. Also, many thanks for Andy Talbot G4JNT for [his paper](http://www.g4jnt.com/JTModesBcns.htm) on the WSPR coding protocol, which helped me to understand the WSPR encoding process, which in turn helped me to understand the related JT protocols.
Also, a big thank you to Murray Greenman, ZL1BPU for working allowing me to pick his brain regarding his neat new mode FSQ.
Changelog
---------
* v1.2.0
* Add support for FT8 protocol (79 symbol version introduced December 2018)
* v1.1.3
* Add support for ESP8266
* Fix WSPR regression in last release
* v1.1.2
* Fix buffer bug in _jt_message_prep()_ that caused messages of 11 chars to lock up the processor
* Made a handful of changes to make the library more friendly to ATmegaxx8 processors
* Rewrote example sketch to be generically compatible with most Arduino platforms
* v1.1.1
* Update example sketch for Si5351Arduino v2.0.0
* v1.1.0
* Added FSQ
* v1.0.1
* Fixed a bug in _jt65_interleave()_ that was causing a buffer overrun.
* v1.0.0
* Initial Release
License
-------
JTEncode is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.
JTEncode is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
You should have received a copy of the GNU General Public License along with JTEncode. If not, see <http://www.gnu.org/licenses/>.

Wyświetl plik

@ -0,0 +1,98 @@
/**
* \file
* Functions and types for CRC checks.
*
* Generated on Thu Dec 6 17:52:34 2018
* by pycrc v0.9.1, https://pycrc.org
* using the configuration:
* - Width = 14
* - Poly = 0x2757
* - XorIn = Undefined
* - ReflectIn = Undefined
* - XorOut = Undefined
* - ReflectOut = Undefined
* - Algorithm = bit-by-bit
*/
#include "crc14.h" /* include the header file generated with pycrc */
#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
static crc_t crc_reflect(crc_t data, size_t data_len);
crc_t crc_reflect(crc_t data, size_t data_len)
{
unsigned int i;
crc_t ret;
ret = data & 0x01;
for (i = 1; i < data_len; i++) {
data >>= 1;
ret = (ret << 1) | (data & 0x01);
}
return ret;
}
crc_t crc_init(const crc_cfg_t *cfg)
{
unsigned int i;
bool bit;
crc_t crc = cfg->xor_in;
for (i = 0; i < 14; i++) {
bit = crc & 0x01;
if (bit) {
crc = ((crc ^ 0x2757) >> 1) | 0x2000;
} else {
crc >>= 1;
}
}
return crc & 0x3fff;
}
crc_t crc_update(const crc_cfg_t *cfg, crc_t crc, const void *data, size_t data_len)
{
const unsigned char *d = (const unsigned char *)data;
unsigned int i;
bool bit;
unsigned char c;
while (data_len--) {
if (cfg->reflect_in) {
c = crc_reflect(*d++, 8);
} else {
c = *d++;
}
for (i = 0; i < 8; i++) {
bit = crc & 0x2000;
crc = (crc << 1) | ((c >> (7 - i)) & 0x01);
if (bit) {
crc ^= 0x2757;
}
}
crc &= 0x3fff;
}
return crc & 0x3fff;
}
crc_t crc_finalize(const crc_cfg_t *cfg, crc_t crc)
{
unsigned int i;
bool bit;
for (i = 0; i < 14; i++) {
bit = crc & 0x2000;
crc <<= 1;
if (bit) {
crc ^= 0x2757;
}
}
if (cfg->reflect_out) {
crc = crc_reflect(crc, 14);
}
return (crc ^ cfg->xor_out) & 0x3fff;
}

Wyświetl plik

@ -0,0 +1,121 @@
/**
* \file
* Functions and types for CRC checks.
*
* Generated on Thu Dec 6 17:52:01 2018
* by pycrc v0.9.1, https://pycrc.org
* using the configuration:
* - Width = 14
* - Poly = 0x2757
* - XorIn = Undefined
* - ReflectIn = Undefined
* - XorOut = Undefined
* - ReflectOut = Undefined
* - Algorithm = bit-by-bit
*
* This file defines the functions crc_init(), crc_update() and crc_finalize().
*
* The crc_init() function returns the inital \c crc value and must be called
* before the first call to crc_update().
* Similarly, the crc_finalize() function must be called after the last call
* to crc_update(), before the \c crc is being used.
* is being used.
*
* The crc_update() function can be called any number of times (including zero
* times) in between the crc_init() and crc_finalize() calls.
*
* This pseudo-code shows an example usage of the API:
* \code{.c}
* crc_cfg_t cfg = {
* 0, // reflect_in
* 0, // xor_in
* 0, // reflect_out
* 0, // xor_out
* };
* crc_t crc;
* unsigned char data[MAX_DATA_LEN];
* size_t data_len;
*
* crc = crc_init(&cfg);
* while ((data_len = read_data(data, MAX_DATA_LEN)) > 0) {
* crc = crc_update(&cfg, crc, data, data_len);
* }
* crc = crc_finalize(&cfg, crc);
* \endcode
*/
#ifndef CRC14_H
#define CRC14_H
#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* The definition of the used algorithm.
*
* This is not used anywhere in the generated code, but it may be used by the
* application code to call algorithm-specific code, if desired.
*/
#define CRC_ALGO_BIT_BY_BIT 1
/**
* The type of the CRC values.
*
* This type must be big enough to contain at least 14 bits.
*/
typedef uint_fast16_t crc_t;
/**
* The configuration type of the CRC algorithm.
*/
typedef struct {
bool reflect_in; /*!< Whether the input shall be reflected or not */
crc_t xor_in; /*!< The initial value of the register */
bool reflect_out; /*!< Whether the output shall be reflected or not */
crc_t xor_out; /*!< The value which shall be XOR-ed to the final CRC value */
} crc_cfg_t;
/**
* Calculate the initial crc value.
*
* \param[in] cfg A pointer to an initialised crc_cfg_t structure.
* \return The initial crc value.
*/
crc_t crc_init(const crc_cfg_t *cfg);
/**
* Update the crc value with new data.
*
* \param[in] crc The current crc value.
* \param[in] cfg A pointer to an initialised crc_cfg_t structure.
* \param[in] data Pointer to a buffer of \a data_len bytes.
* \param[in] data_len Number of bytes in the \a data buffer.
* \return The updated crc value.
*/
crc_t crc_update(const crc_cfg_t *cfg, crc_t crc, const void *data, size_t data_len);
/**
* Calculate the final crc value.
*
* \param[in] cfg A pointer to an initialised crc_cfg_t structure.
* \param[in] crc The current crc value.
* \return The final crc value.
*/
crc_t crc_finalize(const crc_cfg_t *cfg, crc_t crc);
#ifdef __cplusplus
} /* closing brace for extern "C" */
#endif
#endif /* CRC14_H */

Wyświetl plik

@ -0,0 +1,58 @@
/* The guts of the Reed-Solomon encoder, meant to be #included
* into a function body with the following typedefs, macros and variables supplied
* according to the code parameters:
* data_t - a typedef for the data symbol
* data_t data[] - array of NN-NROOTS-PAD and type data_t to be encoded
* data_t parity[] - an array of NROOTS and type data_t to be written with parity symbols
* NROOTS - the number of roots in the RS code generator polynomial,
* which is the same as the number of parity symbols in a block.
Integer variable or literal.
*
* NN - the total number of symbols in a RS block. Integer variable or literal.
* PAD - the number of pad symbols in a block. Integer variable or literal.
* ALPHA_TO - The address of an array of NN elements to convert Galois field
* elements in index (log) form to polynomial form. Read only.
* INDEX_OF - The address of an array of NN elements to convert Galois field
* elements in polynomial form to index (log) form. Read only.
* MODNN - a function to reduce its argument modulo NN. May be inline or a macro.
* GENPOLY - an array of NROOTS+1 elements containing the generator polynomial in index form
* The memset() and memmove() functions are used. The appropriate header
* file declaring these functions (usually <string.h>) must be included by the calling
* program.
* Copyright 2004, Phil Karn, KA9Q
* May be used under the terms of the GNU Lesser General Public License (LGPL)
*/
#undef A0
#define A0 (NN) /* Special reserved value encoding zero in index form */
{
int i, j;
data_t feedback;
memset(parity,0,NROOTS*sizeof(data_t));
for(i=0;i<NN-NROOTS-PAD;i++){
feedback = INDEX_OF[data[i] ^ parity[0]];
if(feedback != A0){ /* feedback term is non-zero */
#ifdef UNNORMALIZED
/* This line is unnecessary when GENPOLY[NROOTS] is unity, as it must
* always be for the polynomials constructed by init_rs()
*/
feedback = MODNN(NN - GENPOLY[NROOTS] + feedback);
#endif
for(j=1;j<NROOTS;j++)
parity[j] ^= ALPHA_TO[MODNN(feedback + GENPOLY[NROOTS-j])];
}
/* Shift */
memmove(&parity[0],&parity[1],sizeof(data_t)*(NROOTS-1));
if(feedback != A0)
parity[NROOTS-1] = ALPHA_TO[MODNN(feedback + GENPOLY[0])];
else
parity[NROOTS-1] = 0;
}
}

Wyświetl plik

@ -0,0 +1,70 @@
/* Reed-Solomon encoder
* Copyright 2003, Phil Karn, KA9Q
* May be used under the terms of the GNU Lesser General Public License (LGPL)
*
* Slightly modified by Jason Milldrum NT7S, 2015 to fit into the Arduino framework
*
* The guts of the Reed-Solomon encoder, meant to be #included
* into a function body with the following typedefs, macros and variables supplied
* according to the code parameters:
* data_t - a typedef for the data symbol
* data_t data[] - array of NN-NROOTS-PAD and type data_t to be encoded
* data_t parity[] - an array of NROOTS and type data_t to be written with parity symbols
* NROOTS - the number of roots in the RS code generator polynomial,
* which is the same as the number of parity symbols in a block.
Integer variable or literal.
*
* NN - the total number of symbols in a RS block. Integer variable or literal.
* PAD - the number of pad symbols in a block. Integer variable or literal.
* ALPHA_TO - The address of an array of NN elements to convert Galois field
* elements in index (log) form to polynomial form. Read only.
* INDEX_OF - The address of an array of NN elements to convert Galois field
* elements in polynomial form to index (log) form. Read only.
* MODNN - a function to reduce its argument modulo NN. May be inline or a macro.
* GENPOLY - an array of NROOTS+1 elements containing the generator polynomial in index form
* The memset() and memmove() functions are used. The appropriate header
* file declaring these functions (usually <string.h>) must be included by the calling
* program.
*/
#include <cstring>
#include "JTEncode.h"
#include "int.h"
#include "rs_common.h"
void JTEncode::encode_rs_int(void *p, data_t *data, data_t *parity)
{
struct rs *rs = (struct rs *)p;
#undef A_0
#define A_0 (NN) /* Special reserved value encoding zero in index form */
{
int i, j;
data_t feedback;
memset(parity,0,NROOTS*sizeof(data_t));
for(i=0;i<NN-NROOTS-PAD;i++){
feedback = INDEX_OF[data[i] ^ parity[0]];
if(feedback != A_0){ /* feedback term is non-zero */
#ifdef UNNORMALIZED
/* This line is unnecessary when GENPOLY[NROOTS] is unity, as it must
* always be for the polynomials constructed by init_rs()
*/
feedback = MODNN(NN - GENPOLY[NROOTS] + feedback);
#endif
for(j=1;j<NROOTS;j++)
parity[j] ^= ALPHA_TO[MODNN(feedback + GENPOLY[NROOTS-j])];
}
/* Shift */
memmove(&parity[0],&parity[1],sizeof(data_t)*(NROOTS-1));
if(feedback != A_0)
parity[NROOTS-1] = ALPHA_TO[MODNN(feedback + GENPOLY[0])];
else
parity[NROOTS-1] = 0;
}
}
}

Wyświetl plik

@ -0,0 +1,93 @@
#ifndef GENERATOR_H
#define GENERATOR_H
#include <cstdint>
const uint8_t generator_bits[83][12] =
{
{0b10000011, 0b00101001, 0b11001110, 0b00010001, 0b10111111, 0b00110001, 0b11101010, 0b11110101, 0b00001001, 0b11110010, 0b01111111, 0b11000000},
{0b01110110, 0b00011100, 0b00100110, 0b01001110, 0b00100101, 0b11000010, 0b01011001, 0b00110011, 0b01010100, 0b10010011, 0b00010011, 0b00100000},
{0b11011100, 0b00100110, 0b01011001, 0b00000010, 0b11111011, 0b00100111, 0b01111100, 0b01100100, 0b00010000, 0b10100001, 0b10111101, 0b11000000},
{0b00011011, 0b00111111, 0b01000001, 0b01111000, 0b01011000, 0b11001101, 0b00101101, 0b11010011, 0b00111110, 0b11000111, 0b11110110, 0b00100000},
{0b00001001, 0b11111101, 0b10100100, 0b11111110, 0b11100000, 0b01000001, 0b10010101, 0b11111101, 0b00000011, 0b01000111, 0b10000011, 0b10100000},
{0b00000111, 0b01111100, 0b11001100, 0b11000001, 0b00011011, 0b10001000, 0b01110011, 0b11101101, 0b01011100, 0b00111101, 0b01001000, 0b10100000},
{0b00101001, 0b10110110, 0b00101010, 0b11111110, 0b00111100, 0b10100000, 0b00110110, 0b11110100, 0b11111110, 0b00011010, 0b10011101, 0b10100000},
{0b01100000, 0b01010100, 0b11111010, 0b11110101, 0b11110011, 0b01011101, 0b10010110, 0b11010011, 0b10110000, 0b11001000, 0b11000011, 0b11100000},
{0b11100010, 0b00000111, 0b10011000, 0b11100100, 0b00110001, 0b00001110, 0b11101101, 0b00100111, 0b10001000, 0b01001010, 0b11101001, 0b00000000},
{0b01110111, 0b01011100, 0b10011100, 0b00001000, 0b11101000, 0b00001110, 0b00100110, 0b11011101, 0b10101110, 0b01010110, 0b00110001, 0b10000000},
{0b10110000, 0b10111000, 0b00010001, 0b00000010, 0b10001100, 0b00101011, 0b11111001, 0b10010111, 0b00100001, 0b00110100, 0b10000111, 0b11000000},
{0b00011000, 0b10100000, 0b11001001, 0b00100011, 0b00011111, 0b11000110, 0b00001010, 0b11011111, 0b01011100, 0b01011110, 0b10100011, 0b00100000},
{0b01110110, 0b01000111, 0b00011110, 0b10000011, 0b00000010, 0b10100000, 0b01110010, 0b00011110, 0b00000001, 0b10110001, 0b00101011, 0b10000000},
{0b11111111, 0b10111100, 0b11001011, 0b10000000, 0b11001010, 0b10000011, 0b01000001, 0b11111010, 0b11111011, 0b01000111, 0b10110010, 0b11100000},
{0b01100110, 0b10100111, 0b00101010, 0b00010101, 0b10001111, 0b10010011, 0b00100101, 0b10100010, 0b10111111, 0b01100111, 0b00010111, 0b00000000},
{0b11000100, 0b00100100, 0b00110110, 0b10001001, 0b11111110, 0b10000101, 0b10110001, 0b11000101, 0b00010011, 0b01100011, 0b10100001, 0b10000000},
{0b00001101, 0b11111111, 0b01110011, 0b10010100, 0b00010100, 0b11010001, 0b10100001, 0b10110011, 0b01001011, 0b00011100, 0b00100111, 0b00000000},
{0b00010101, 0b10110100, 0b10001000, 0b00110000, 0b01100011, 0b01101100, 0b10001011, 0b10011001, 0b10001001, 0b01001001, 0b01110010, 0b11100000},
{0b00101001, 0b10101000, 0b10011100, 0b00001101, 0b00111101, 0b11101000, 0b00011101, 0b01100110, 0b01010100, 0b10001001, 0b10110000, 0b11100000},
{0b01001111, 0b00010010, 0b01101111, 0b00110111, 0b11111010, 0b01010001, 0b11001011, 0b11100110, 0b00011011, 0b11010110, 0b10111001, 0b01000000},
{0b10011001, 0b11000100, 0b01110010, 0b00111001, 0b11010000, 0b11011001, 0b01111101, 0b00111100, 0b10000100, 0b11100000, 0b10010100, 0b00000000},
{0b00011001, 0b00011001, 0b10110111, 0b01010001, 0b00011001, 0b01110110, 0b01010110, 0b00100001, 0b10111011, 0b01001111, 0b00011110, 0b10000000},
{0b00001001, 0b11011011, 0b00010010, 0b11010111, 0b00110001, 0b11111010, 0b11101110, 0b00001011, 0b10000110, 0b11011111, 0b01101011, 0b10000000},
{0b01001000, 0b10001111, 0b11000011, 0b00111101, 0b11110100, 0b00111111, 0b10111101, 0b11101110, 0b10100100, 0b11101010, 0b11111011, 0b01000000},
{0b10000010, 0b01110100, 0b00100011, 0b11101110, 0b01000000, 0b10110110, 0b01110101, 0b11110111, 0b01010110, 0b11101011, 0b01011111, 0b11100000},
{0b10101011, 0b11100001, 0b10010111, 0b11000100, 0b10000100, 0b11001011, 0b01110100, 0b01110101, 0b01110001, 0b01000100, 0b10101001, 0b10100000},
{0b00101011, 0b01010000, 0b00001110, 0b01001011, 0b11000000, 0b11101100, 0b01011010, 0b01101101, 0b00101011, 0b11011011, 0b11011101, 0b00000000},
{0b11000100, 0b01110100, 0b10101010, 0b01010011, 0b11010111, 0b00000010, 0b00011000, 0b01110110, 0b00010110, 0b01101001, 0b00110110, 0b00000000},
{0b10001110, 0b10111010, 0b00011010, 0b00010011, 0b11011011, 0b00110011, 0b10010000, 0b10111101, 0b01100111, 0b00011000, 0b11001110, 0b11000000},
{0b01110101, 0b00111000, 0b01000100, 0b01100111, 0b00111010, 0b00100111, 0b01111000, 0b00101100, 0b11000100, 0b00100000, 0b00010010, 0b11100000},
{0b00000110, 0b11111111, 0b10000011, 0b10100001, 0b01000101, 0b11000011, 0b01110000, 0b00110101, 0b10100101, 0b11000001, 0b00100110, 0b10000000},
{0b00111011, 0b00110111, 0b01000001, 0b01111000, 0b01011000, 0b11001100, 0b00101101, 0b11010011, 0b00111110, 0b11000011, 0b11110110, 0b00100000},
{0b10011010, 0b01001010, 0b01011010, 0b00101000, 0b11101110, 0b00010111, 0b11001010, 0b10011100, 0b00110010, 0b01001000, 0b01000010, 0b11000000},
{0b10111100, 0b00101001, 0b11110100, 0b01100101, 0b00110000, 0b10011100, 0b10010111, 0b01111110, 0b10001001, 0b01100001, 0b00001010, 0b01000000},
{0b00100110, 0b01100011, 0b10101110, 0b01101101, 0b11011111, 0b10001011, 0b01011100, 0b11100010, 0b10111011, 0b00101001, 0b01001000, 0b10000000},
{0b01000110, 0b11110010, 0b00110001, 0b11101111, 0b11100100, 0b01010111, 0b00000011, 0b01001100, 0b00011000, 0b00010100, 0b01000001, 0b10000000},
{0b00111111, 0b10110010, 0b11001110, 0b10000101, 0b10101011, 0b11101001, 0b10110000, 0b11000111, 0b00101110, 0b00000110, 0b11111011, 0b11100000},
{0b11011110, 0b10000111, 0b01001000, 0b00011111, 0b00101000, 0b00101100, 0b00010101, 0b00111001, 0b01110001, 0b10100000, 0b10100010, 0b11100000},
{0b11111100, 0b11010111, 0b11001100, 0b11110010, 0b00111100, 0b01101001, 0b11111010, 0b10011001, 0b10111011, 0b10100001, 0b01000001, 0b00100000},
{0b11110000, 0b00100110, 0b00010100, 0b01000111, 0b11101001, 0b01001001, 0b00001100, 0b10101000, 0b11100100, 0b01110100, 0b11001110, 0b11000000},
{0b01000100, 0b00010000, 0b00010001, 0b01011000, 0b00011000, 0b00011001, 0b01101111, 0b10010101, 0b11001101, 0b11010111, 0b00000001, 0b00100000},
{0b00001000, 0b10001111, 0b11000011, 0b00011101, 0b11110100, 0b10111111, 0b10111101, 0b11100010, 0b10100100, 0b11101010, 0b11111011, 0b01000000},
{0b10111000, 0b11111110, 0b11110001, 0b10110110, 0b00110000, 0b01110111, 0b00101001, 0b11111011, 0b00001010, 0b00000111, 0b10001100, 0b00000000},
{0b01011010, 0b11111110, 0b10100111, 0b10101100, 0b11001100, 0b10110111, 0b01111011, 0b10111100, 0b10011101, 0b10011001, 0b10101001, 0b00000000},
{0b01001001, 0b10100111, 0b00000001, 0b01101010, 0b11000110, 0b01010011, 0b11110110, 0b01011110, 0b11001101, 0b11001001, 0b00000111, 0b01100000},
{0b00011001, 0b01000100, 0b11010000, 0b10000101, 0b10111110, 0b01001110, 0b01111101, 0b10101000, 0b11010110, 0b11001100, 0b01111101, 0b00000000},
{0b00100101, 0b00011111, 0b01100010, 0b10101101, 0b11000100, 0b00000011, 0b00101111, 0b00001110, 0b11100111, 0b00010100, 0b00000000, 0b00100000},
{0b01010110, 0b01000111, 0b00011111, 0b10000111, 0b00000010, 0b10100000, 0b01110010, 0b00011110, 0b00000000, 0b10110001, 0b00101011, 0b10000000},
{0b00101011, 0b10001110, 0b01001001, 0b00100011, 0b11110010, 0b11011101, 0b01010001, 0b11100010, 0b11010101, 0b00110111, 0b11111010, 0b00000000},
{0b01101011, 0b01010101, 0b00001010, 0b01000000, 0b10100110, 0b01101111, 0b01000111, 0b01010101, 0b11011110, 0b10010101, 0b11000010, 0b01100000},
{0b10100001, 0b10001010, 0b11010010, 0b10001101, 0b01001110, 0b00100111, 0b11111110, 0b10010010, 0b10100100, 0b11110110, 0b11001000, 0b01000000},
{0b00010000, 0b11000010, 0b11100101, 0b10000110, 0b00111000, 0b10001100, 0b10111000, 0b00101010, 0b00111101, 0b10000000, 0b01110101, 0b10000000},
{0b11101111, 0b00110100, 0b10100100, 0b00011000, 0b00010111, 0b11101110, 0b00000010, 0b00010011, 0b00111101, 0b10110010, 0b11101011, 0b00000000},
{0b01111110, 0b10011100, 0b00001100, 0b01010100, 0b00110010, 0b01011010, 0b10011100, 0b00010101, 0b10000011, 0b01101110, 0b00000000, 0b00000000},
{0b00110110, 0b10010011, 0b11100101, 0b01110010, 0b11010001, 0b11111101, 0b11100100, 0b11001101, 0b11110000, 0b01111001, 0b11101000, 0b01100000},
{0b10111111, 0b10110010, 0b11001110, 0b11000101, 0b10101011, 0b11100001, 0b10110000, 0b11000111, 0b00101110, 0b00000111, 0b11111011, 0b11100000},
{0b01111110, 0b11100001, 0b10000010, 0b00110000, 0b11000101, 0b10000011, 0b11001100, 0b11001100, 0b01010111, 0b11010100, 0b10110000, 0b10000000},
{0b10100000, 0b01100110, 0b11001011, 0b00101111, 0b11101101, 0b10101111, 0b11001001, 0b11110101, 0b00100110, 0b01100100, 0b00010010, 0b01100000},
{0b10111011, 0b00100011, 0b01110010, 0b01011010, 0b10111100, 0b01000111, 0b11001100, 0b01011111, 0b01001100, 0b11000100, 0b11001101, 0b00100000},
{0b11011110, 0b11011001, 0b11011011, 0b10100011, 0b10111110, 0b11100100, 0b00001100, 0b01011001, 0b10110101, 0b01100000, 0b10011011, 0b01000000},
{0b11011001, 0b10100111, 0b00000001, 0b01101010, 0b11000110, 0b01010011, 0b11100110, 0b11011110, 0b11001101, 0b11001001, 0b00000011, 0b01100000},
{0b10011010, 0b11010100, 0b01101010, 0b11101101, 0b01011111, 0b01110000, 0b01111111, 0b00101000, 0b00001010, 0b10110101, 0b11111100, 0b01000000},
{0b11100101, 0b10010010, 0b00011100, 0b01110111, 0b10000010, 0b00100101, 0b10000111, 0b00110001, 0b01101101, 0b01111101, 0b00111100, 0b00100000},
{0b01001111, 0b00010100, 0b11011010, 0b10000010, 0b01000010, 0b10101000, 0b10111000, 0b01101101, 0b11001010, 0b01110011, 0b00110101, 0b00100000},
{0b10001011, 0b10001011, 0b01010000, 0b01111010, 0b11010100, 0b01100111, 0b11010100, 0b01000100, 0b00011101, 0b11110111, 0b01110000, 0b11100000},
{0b00100010, 0b10000011, 0b00011100, 0b10011100, 0b11110001, 0b00010110, 0b10010100, 0b01100111, 0b10101101, 0b00000100, 0b10110110, 0b10000000},
{0b00100001, 0b00111011, 0b10000011, 0b10001111, 0b11100010, 0b10101110, 0b01010100, 0b11000011, 0b10001110, 0b11100111, 0b00011000, 0b00000000},
{0b01011101, 0b10010010, 0b01101011, 0b01101101, 0b11010111, 0b00011111, 0b00001000, 0b01010001, 0b10000001, 0b10100100, 0b11100001, 0b00100000},
{0b01100110, 0b10101011, 0b01111001, 0b11010100, 0b10110010, 0b10011110, 0b11100110, 0b11100110, 0b10010101, 0b00001001, 0b11100101, 0b01100000},
{0b10010101, 0b10000001, 0b01001000, 0b01101000, 0b00101101, 0b01110100, 0b10001010, 0b00111000, 0b11011101, 0b01101000, 0b10111010, 0b10100000},
{0b10111000, 0b11001110, 0b00000010, 0b00001100, 0b11110000, 0b01101001, 0b11000011, 0b00101010, 0b01110010, 0b00111010, 0b10110001, 0b01000000},
{0b11110100, 0b00110011, 0b00011101, 0b01101101, 0b01000110, 0b00010110, 0b00000111, 0b11101001, 0b01010111, 0b01010010, 0b01110100, 0b01100000},
{0b01101101, 0b10100010, 0b00111011, 0b10100100, 0b00100100, 0b10111001, 0b01011001, 0b01100001, 0b00110011, 0b11001111, 0b10011100, 0b10000000},
{0b10100110, 0b00110110, 0b10111100, 0b10111100, 0b01111011, 0b00110000, 0b11000101, 0b11111011, 0b11101010, 0b11100110, 0b01111111, 0b11100000},
{0b01011100, 0b10110000, 0b11011000, 0b01101010, 0b00000111, 0b11011111, 0b01100101, 0b01001010, 0b10010000, 0b10001001, 0b10100010, 0b00000000},
{0b11110001, 0b00011111, 0b00010000, 0b01101000, 0b01001000, 0b01111000, 0b00001111, 0b11001001, 0b11101100, 0b11011101, 0b10000000, 0b10100000},
{0b00011111, 0b10111011, 0b01010011, 0b01100100, 0b11111011, 0b10001101, 0b00101100, 0b10011101, 0b01110011, 0b00001101, 0b01011011, 0b10100000},
{0b11111100, 0b10111000, 0b01101011, 0b11000111, 0b00001010, 0b01010000, 0b11001001, 0b11010000, 0b00101010, 0b01011101, 0b00000011, 0b01000000},
{0b10100101, 0b00110100, 0b01000011, 0b00110000, 0b00101001, 0b11101010, 0b11000001, 0b01011111, 0b00110010, 0b00101110, 0b00110100, 0b11000000},
{0b11001001, 0b10001001, 0b11011001, 0b11000111, 0b11000011, 0b11010011, 0b10111000, 0b11000101, 0b01011101, 0b01110101, 0b00010011, 0b00000000},
{0b01111011, 0b10110011, 0b10001011, 0b00101111, 0b00000001, 0b10000110, 0b11010100, 0b01100110, 0b01000011, 0b10101110, 0b10010110, 0b00100000},
{0b00100110, 0b01000100, 0b11101011, 0b10101101, 0b11101011, 0b01000100, 0b10111001, 0b01000110, 0b01111101, 0b00011111, 0b01000010, 0b11000000},
{0b01100000, 0b10001100, 0b11001000, 0b01010111, 0b01011001, 0b01001011, 0b11111011, 0b10110101, 0b01011101, 0b01101001, 0b01100000, 0b00000000}
};
#endif

Wyświetl plik

@ -0,0 +1,106 @@
/* Common code for intializing a Reed-Solomon control block (char or int symbols)
* Copyright 2004 Phil Karn, KA9Q
* May be used under the terms of the GNU Lesser General Public License (LGPL)
*/
#undef NULL
#define NULL ((void *)0)
//{
int i, j, sr,root,iprim;
rs = NULL;
/* Check parameter ranges */
if(symsize < 0 || symsize > 8*sizeof(data_t)){
goto done;
}
if(fcr < 0 || fcr >= (1<<symsize))
goto done;
if(prim <= 0 || prim >= (1<<symsize))
goto done;
if(nroots < 0 || nroots >= (1<<symsize))
goto done; /* Can't have more roots than symbol values! */
if(pad < 0 || pad >= ((1<<symsize) -1 - nroots))
goto done; /* Too much padding */
rs = (struct rs *)calloc(1,sizeof(struct rs));
if(rs == NULL)
goto done;
rs->mm = symsize;
rs->nn = (1<<symsize)-1;
rs->pad = pad;
rs->alpha_to = (data_t *)malloc(sizeof(data_t)*(rs->nn+1));
if(rs->alpha_to == NULL){
free(rs);
rs = NULL;
goto done;
}
rs->index_of = (data_t *)malloc(sizeof(data_t)*(rs->nn+1));
if(rs->index_of == NULL){
free(rs->alpha_to);
free(rs);
rs = NULL;
goto done;
}
/* Generate Galois field lookup tables */
rs->index_of[0] = A0; /* log(zero) = -inf */
rs->alpha_to[A0] = 0; /* alpha**-inf = 0 */
sr = 1;
for(i=0;i<rs->nn;i++){
rs->index_of[sr] = i;
rs->alpha_to[i] = sr;
sr <<= 1;
if(sr & (1<<symsize))
sr ^= gfpoly;
sr &= rs->nn;
}
if(sr != 1){
/* field generator polynomial is not primitive! */
free(rs->alpha_to);
free(rs->index_of);
free(rs);
rs = NULL;
goto done;
}
/* Form RS code generator polynomial from its roots */
rs->genpoly = (data_t *)malloc(sizeof(data_t)*(nroots+1));
if(rs->genpoly == NULL){
free(rs->alpha_to);
free(rs->index_of);
free(rs);
rs = NULL;
goto done;
}
rs->fcr = fcr;
rs->prim = prim;
rs->nroots = nroots;
/* Find prim-th root of 1, used in decoding */
for(iprim=1;(iprim % prim) != 0;iprim += rs->nn)
;
rs->iprim = iprim / prim;
rs->genpoly[0] = 1;
for (i = 0,root=fcr*prim; i < nroots; i++,root += prim) {
rs->genpoly[i+1] = 1;
/* Multiply rs->genpoly[] by @**(root + x) */
for (j = i; j > 0; j--){
if (rs->genpoly[j] != 0)
rs->genpoly[j] = rs->genpoly[j-1] ^ rs->alpha_to[modnn(rs,rs->index_of[rs->genpoly[j]] + root)];
else
rs->genpoly[j] = rs->genpoly[j-1];
}
/* rs->genpoly[0] can never be zero */
rs->genpoly[0] = rs->alpha_to[modnn(rs,rs->index_of[rs->genpoly[0]] + root)];
}
/* convert rs->genpoly[] to index form for quicker encoding */
for (i = 0; i <= nroots; i++)
rs->genpoly[i] = rs->index_of[rs->genpoly[i]];
done:;
//}

Wyświetl plik

@ -0,0 +1,127 @@
/* Initialize a RS codec
*
* Copyright 2002 Phil Karn, KA9Q
* May be used under the terms of the GNU Lesser General Public License (LGPL)
*
* Slightly modified by Jason Milldrum NT7S, 2015 to fit into the Arduino framework
*/
#include <string>
#include <cstdlib>
#include "JTEncode.h"
#include "rs_common.h"
void JTEncode::free_rs_int(void * p)
{
struct rs *rs = (struct rs *)p;
free(rs->alpha_to);
free(rs->index_of);
free(rs->genpoly);
free(rs);
}
void * JTEncode::init_rs_int(int symsize, int gfpoly, int fcr, int prim,
int nroots, int pad)
{
struct rs *rs;
int i, j, sr,root,iprim;
rs = ((struct rs *)0);
/* Check parameter ranges */
if(symsize < 0 || symsize > 8*sizeof(data_t)){
goto done;
}
if(fcr < 0 || fcr >= (1<<symsize))
goto done;
if(prim <= 0 || prim >= (1<<symsize))
goto done;
if(nroots < 0 || nroots >= (1<<symsize))
goto done; /* Can't have more roots than symbol values! */
if(pad < 0 || pad >= ((1<<symsize) -1 - nroots))
goto done; /* Too much padding */
rs = (struct rs *)calloc(1,sizeof(struct rs));
if(rs == ((struct rs *)0))
goto done;
rs->mm = symsize;
rs->nn = (1<<symsize)-1;
rs->pad = pad;
rs->alpha_to = (data_t *)malloc(sizeof(data_t)*(rs->nn+1));
if(rs->alpha_to == NULL){
free(rs);
rs = ((struct rs *)0);
goto done;
}
rs->index_of = (data_t *)malloc(sizeof(data_t)*(rs->nn+1));
if(rs->index_of == NULL){
free(rs->alpha_to);
free(rs);
rs = ((struct rs *)0);
goto done;
}
/* Generate Galois field lookup tables */
rs->index_of[0] = A_0; /* log(zero) = -inf */
rs->alpha_to[A_0] = 0; /* alpha**-inf = 0 */
sr = 1;
for(i=0;i<rs->nn;i++){
rs->index_of[sr] = i;
rs->alpha_to[i] = sr;
sr <<= 1;
if(sr & (1<<symsize))
sr ^= gfpoly;
sr &= rs->nn;
}
if(sr != 1){
/* field generator polynomial is not primitive! */
free(rs->alpha_to);
free(rs->index_of);
free(rs);
rs = ((struct rs *)0);
goto done;
}
/* Form RS code generator polynomial from its roots */
rs->genpoly = (data_t *)malloc(sizeof(data_t)*(nroots+1));
if(rs->genpoly == NULL){
free(rs->alpha_to);
free(rs->index_of);
free(rs);
rs = ((struct rs *)0);
goto done;
}
rs->fcr = fcr;
rs->prim = prim;
rs->nroots = nroots;
/* Find prim-th root of 1, used in decoding */
for(iprim=1;(iprim % prim) != 0;iprim += rs->nn)
;
rs->iprim = iprim / prim;
rs->genpoly[0] = 1;
for (i = 0,root=fcr*prim; i < nroots; i++,root += prim) {
rs->genpoly[i+1] = 1;
/* Multiply rs->genpoly[] by @**(root + x) */
for (j = i; j > 0; j--){
if (rs->genpoly[j] != 0)
rs->genpoly[j] = rs->genpoly[j-1] ^ rs->alpha_to[modnn(rs,rs->index_of[rs->genpoly[j]] + root)];
else
rs->genpoly[j] = rs->genpoly[j-1];
}
/* rs->genpoly[0] can never be zero */
rs->genpoly[0] = rs->alpha_to[modnn(rs,rs->index_of[rs->genpoly[0]] + root)];
}
/* convert rs->genpoly[] to index form for quicker encoding */
for (i = 0; i <= nroots; i++)
rs->genpoly[i] = rs->index_of[rs->genpoly[i]];
done:;
return rs;
}

Wyświetl plik

@ -0,0 +1,27 @@
/* Stuff specific to the general (integer) version of the Reed-Solomon codecs
*
* Copyright 2003, Phil Karn, KA9Q
* May be used under the terms of the GNU Lesser General Public License (LGPL)
*/
#ifndef INT_H_
#define INT_H_
#include <cstdint>
typedef uint8_t data_t;
//typedef unsigned int data_t;
#define MODNN(x) modnn(rs,x)
#define MM (rs->mm)
#define NN (rs->nn)
#define ALPHA_TO (rs->alpha_to)
#define INDEX_OF (rs->index_of)
#define GENPOLY (rs->genpoly)
#define NROOTS (rs->nroots)
#define FCR (rs->fcr)
#define PRIM (rs->prim)
#define IPRIM (rs->iprim)
#define PAD (rs->pad)
#define A_0 (NN)
#endif

Wyświetl plik

@ -0,0 +1,33 @@
/* Stuff common to all the general-purpose Reed-Solomon codecs
* Copyright 2004 Phil Karn, KA9Q
* May be used under the terms of the GNU Lesser General Public License (LGPL)
*/
#ifndef RS_COMMON_H_
#define RS_COMMON_H_
#include "int.h"
/* Reed-Solomon codec control block */
struct rs {
int mm; /* Bits per symbol */
int nn; /* Symbols per block (= (1<<mm)-1) */
data_t *alpha_to; /* log lookup table */
data_t *index_of; /* Antilog lookup table */
data_t *genpoly; /* Generator polynomial */
int nroots; /* Number of generator roots = number of parity symbols */
int fcr; /* First consecutive root, index form */
int prim; /* Primitive element, index form */
int iprim; /* prim-th root of 1, index form */
int pad; /* Padding bytes in shortened block */
};
static inline int modnn(struct rs *rs,int x){
while (x >= rs->nn) {
x -= rs->nn;
x = (x >> rs->mm) + (x & rs->nn);
}
return x;
}
#endif

93
src/config-old.txt 100644
Wyświetl plik

@ -0,0 +1,93 @@
//********** RTTY
#define SEND_RTTY 1 // Set to 0 to disable RTTY
//**************RTTY Data Format**********************
// $$$<callsign>,<frame#>,[<hh:mm:ss>],[<latitude>,<longitude>],[<height>],[<speed>],[<rtty comment>],[<radio chip temperature (°C)>],[<battery voltage>],[<used gps satellites>],[<good gps datasets>,<bad gps datasets>,<gps fix flags>]*<CRC>
#define RTTY_CALLSIGN "OH3BHX" // put your RTTY callsign here, max. 15 characters
#define SEND_RTTY_TIME 1
#define SEND_RTTY_LATLON 1
#define SEND_RTTY_HEIGHT 1
#define SEND_RTTY_SPEED 1
#define SEND_RTTY_MESSAGE 1
#define SEND_RTTY_TEMPERATURE 1
#define SEND_RTTY_VOLTAGE 1
#define SEND_RTTY_SATELLITES 1
#define SEND_RTTY_GPSDATA 1
#define RTTY_COMMENT " Hello from the sky!" // max. 25 characters
#define RTTY_WWL 1 // Send WWL instead of the comment
// World Wide Locator pairs (precision)
#define PAIR_COUNT 4 // max. 6 (12 characters WWL)
#define RTTY_FREQUENCY 434.500f //Mhz middle frequency
//************RTTY Shift*********************** si4032
#define RTTY_DEVIATION 0x2 // RTTY shift = RTTY_DEVIATION x 270Hz
//************RTTY Speed*********************** si4032
#define RTTY_SPEED 75 // RTTY baudrate
//************rtty bits************************ si4032
#define RTTY_7BIT 1 // if 0 --> 5 bits
//************rtty stop bits******************* si4032
#define RTTY_USE_2_STOP_BITS 0
//********** APRS
#define SEND_APRS 1 // Set to 0 to disable APRS
#define APRS_CALLSIGN "OH3BHX" // put your APRS callsign here, 6 characters. If your callsign is shorter add spaces
#define APRS_SSID 'B' // put your APRS SSID here
// 0 --> Your primary station usually fixed and message capable
// 1 --> generic additional station, digi, mobile, wx, etc.
// 2 --> generic additional station, digi, mobile, wx, etc.
// 3 --> generic additional station, digi, mobile, wx, etc.
// 4 --> generic additional station, digi, mobile, wx, etc.
// 5 --> Other network sources (Dstar, Iphones, Blackberry's etc)
// 6 --> Special activity, Satellite ops, camping or 6 meters, etc.
// 7 --> walkie talkies, HT's or other human portable
// 8 --> boats, sailboats, RV's or second main mobile
// 9 --> Primary Mobile (usually message capable)
// A --> internet, Igates, echolink, winlink, AVRS, APRN, etc.
// B --> balloons, aircraft, spacecraft, etc.
// C --> APRStt, DTMF, RFID, devices, one-way trackers*, etc.
// D --> Weather stations
// E --> Truckers or generally full time drivers
// F --> generic additional station, digi, mobile, wx, etc.
#define APRS_FREQUENCY 432.500f //Mhz middle frequency
#define APRS_COMMENT " Hello from the sky!"
#define RTTY_TO_APRS_RATIO 5 //transmit APRS packet with each x RTTY packet
//********** Morse (CW)
#define SEND_MORSE 1 // Set to 0 to disable CW
#define MORSE_PREFIX "DE OH3BHX-11" // Start of the message
#define SEND_MORSE_WWL 1 // in <WW-locator>
#define SEND_MORSE_HEIGHT 0 // ASL <altitude>
#define SEND_MORSE_VOLTAGE 0 // bat <voltage>
#define MORSE_SUFFIX " +" // AR^ (end of transmission)
#define MORSE_WPM 20 // Speed in words per minute
#define RTTY_TO_MORSE_RATIO 1 // Transmit morse message with each x RTTY packet
//********* power definition**************************
#define TX_POWER 0 // PWR 0...7 0- MIN ... 7 - MAX
// 0 --> -1dBm
// 1 --> 2dBm
// 2 --> 5dBm
// 3 --> 8dBm
// 4 --> 11dBm
// 5 --> 14dBm
// 6 --> 17dBm
// 7 --> 20dBm
//****************************************************
// Switch sonde ON/OFF via Button
// If this is a flight you might prevent sonde from powered off by button
#define ALLOW_DISABLE_BY_BUTTON 1
//********** Frame Delay in msec**********************
#define TX_DELAY 5000
// Enable/disable LED blinking
// when set to 0, LEDs will stop blinking approx. 10 minutes after powering on the sonde
#define LED_ENABLED 1

6
src/config.c 100644
Wyświetl plik

@ -0,0 +1,6 @@
#include "config.h"
bool bmp280_enabled = SENSOR_BMP280_ENABLE;
bool si5351_enabled = RADIO_SI5351_ENABLE;
volatile bool system_initialized = false;

55
src/config.h 100644
Wyświetl plik

@ -0,0 +1,55 @@
#ifndef __CONFIG_H
#define __CONFIG_H
#include <stdbool.h>
#define RADIO_PAYLOAD_MAX_LENGTH 256
#define SENSOR_BMP280_ENABLE false
#define RADIO_SI5351_ENABLE true
#define RADIO_POST_TRANSMIT_DELAY 2000
// Si4032 transmit power: 0..100%
#define RADIO_SI4032_TX_POWER 100
#define RADIO_SI4032_TX_FREQUENCY_CW 432500000
#define RADIO_SI4032_TX_FREQUENCY_RTTY 434250000
#define RADIO_SI4032_TX_FREQUENCY_APRS 434250000
#define RADIO_SI5351_TX_POWER 100
#define RADIO_SI5351_TX_FREQUENCY_JT9 14078700UL
#define RADIO_SI5351_TX_FREQUENCY_JT65 14078300UL
#define RADIO_SI5351_TX_FREQUENCY_JT4 14078500UL
#define RADIO_SI5351_TX_FREQUENCY_WSPR 14085000UL // Was: 14097200UL
#define RADIO_SI5351_TX_FREQUENCY_FSQ 7105350UL // Base freq is 1350 Hz higher than dial freq in USB
#define RADIO_SI5351_TX_FREQUENCY_FT8 14085000UL // Was: 14075000UL
#define WSPR_CALLSIGN "OH3BHX"
#define WSPR_LOCATOR "AA00"
#define WSPR_DBM 10
#define FT8_CALLSIGN "OH3BHX"
#define FT8_LOCATOR "AA00"
#define FSQ_CALLSIGN_FROM "OH3BHX"
#define FSQ_CALLSIGN_TO "N0CALL"
#define FSQ_COMMAND ' '
#define APRS_CALLSIGN "OH3BHX"
#define APRS_SSID 13
#define APRS_SYMBOL 'O'
#define APRS_COMMENT "Testing 123"
#define APRS_RELAYS "WIDE1-1,WIDE2-1"
#define APRS_DESTINATION "APZ41N"
#define APRS_DESTINATION_SSID 0
#define PAIR_COUNT 4 // max. 6 (12 characters WWL)
#define RTTY_7BIT 1 // if 0 --> 5 bits
extern bool bmp280_enabled;
extern bool si5351_enabled;
extern volatile bool system_initialized;
#endif

Wyświetl plik

@ -0,0 +1,360 @@
/**
* The MIT License (MIT)
*
* Ciastkolog.pl (https://github.com/ciastkolog)
* Copyright (c) 2016 sheinz (https://github.com/sheinz)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "hal/i2c.h"
#include "bmp280.h"
/**
* BMP280 registers
*/
#define BMP280_REG_TEMP_XLSB 0xFC /* bits: 7-4 */
#define BMP280_REG_TEMP_LSB 0xFB
#define BMP280_REG_TEMP_MSB 0xFA
#define BMP280_REG_TEMP (BMP280_REG_TEMP_MSB)
#define BMP280_REG_PRESS_XLSB 0xF9 /* bits: 7-4 */
#define BMP280_REG_PRESS_LSB 0xF8
#define BMP280_REG_PRESS_MSB 0xF7
#define BMP280_REG_PRESSURE (BMP280_REG_PRESS_MSB)
#define BMP280_REG_CONFIG 0xF5 /* bits: 7-5 t_sb; 4-2 filter; 0 spi3w_en */
#define BMP280_REG_CTRL 0xF4 /* bits: 7-5 osrs_t; 4-2 osrs_p; 1-0 mode */
#define BMP280_REG_STATUS 0xF3 /* bits: 3 measuring; 0 im_update */
#define BMP280_REG_CTRL_HUM 0xF2 /* bits: 2-0 osrs_h; */
#define BMP280_REG_RESET 0xE0
#define BMP280_REG_ID 0xD0
#define BMP280_REG_CALIB 0x88
#define BMP280_REG_HUM_CALIB 0x88
#define BMP280_RESET_VALUE 0xB6
void bmp280_init_default_params(bmp280_params_t *params)
{
params->mode = BMP280_MODE_NORMAL;
params->filter = BMP280_FILTER_OFF;
params->oversampling_pressure = BMP280_STANDARD;
params->oversampling_temperature = BMP280_STANDARD;
params->oversampling_humidity = BMP280_STANDARD;
params->standby = BMP280_STANDBY_250;
}
static bool read_register16(bmp280 *dev, uint8_t reg, uint16_t *value)
{
uint8_t rx_buff[2];
if (i2c_read_bytes(dev->port, dev->addr, reg, 2, rx_buff) != HAL_OK) {
return false;
}
*value = (uint16_t) ((rx_buff[1] << 8) | rx_buff[0]);
return true;
}
static bool read_data(bmp280 *dev, uint8_t reg, uint8_t *value, uint8_t len)
{
if (i2c_read_bytes(dev->port, dev->addr, reg, len, value) != HAL_OK) {
return false;
}
return true;
}
static bool read_calibration_data(bmp280 *dev)
{
if (read_register16(dev, 0x88, &dev->dig_T1)
&& read_register16(dev, 0x8a, (uint16_t *) &dev->dig_T2)
&& read_register16(dev, 0x8c, (uint16_t *) &dev->dig_T3)
&& read_register16(dev, 0x8e, &dev->dig_P1)
&& read_register16(dev, 0x90, (uint16_t *) &dev->dig_P2)
&& read_register16(dev, 0x92, (uint16_t *) &dev->dig_P3)
&& read_register16(dev, 0x94, (uint16_t *) &dev->dig_P4)
&& read_register16(dev, 0x96, (uint16_t *) &dev->dig_P5)
&& read_register16(dev, 0x98, (uint16_t *) &dev->dig_P6)
&& read_register16(dev, 0x9a, (uint16_t *) &dev->dig_P7)
&& read_register16(dev, 0x9c, (uint16_t *) &dev->dig_P8)
&& read_register16(dev, 0x9e,
(uint16_t *) &dev->dig_P9)) {
return true;
}
return false;
}
static bool read_hum_calibration_data(bmp280 *dev)
{
uint16_t h4, h5;
if (read_data(dev, 0xa1, &dev->dig_H1, 1)
&& read_register16(dev, 0xe1, (uint16_t *) &dev->dig_H2)
&& read_data(dev, 0xe3, &dev->dig_H3, 1)
&& read_register16(dev, 0xe4, &h4)
&& read_register16(dev, 0xe5, &h5)
&& read_data(dev, 0xe7, (uint8_t *) &dev->dig_H6, 1)) {
dev->dig_H4 = (h4 & 0x00ff) << 4 | (h4 & 0x0f00) >> 8;
dev->dig_H5 = h5 >> 4;
return true;
}
return false;
}
static int write_register8(bmp280 *dev, uint8_t reg, uint8_t value)
{
if (i2c_write_byte(dev->port, dev->addr, reg, value) != HAL_OK) {
return false;
}
return true;
}
#include <stdio.h>
bool bmp280_init(bmp280 *dev, bmp280_params_t *params)
{
if (dev->addr != BMP280_I2C_ADDRESS_0
&& dev->addr != BMP280_I2C_ADDRESS_1) {
return false;
}
printf("bmp280 0\n");
if (!read_data(dev, BMP280_REG_ID, &dev->id, 1)) {
return false;
}
printf("bmp280 1\n");
if (dev->id != BMP280_CHIP_ID && dev->id != BME280_CHIP_ID) {
return false;
}
printf("bmp280 1.5\n");
// Soft reset.
if (!write_register8(dev, BMP280_REG_RESET, BMP280_RESET_VALUE)) {
return false;
}
printf("bmp280 2\n");
// Wait until finished copying over the NVP data.
while (1) {
uint8_t status;
if (read_data(dev, BMP280_REG_STATUS, &status, 1) && (status & 1) == 0) {
break;
}
}
if (!read_calibration_data(dev)) {
return false;
}
if (dev->id == BME280_CHIP_ID && !read_hum_calibration_data(dev)) {
return false;
}
uint8_t config = (params->standby << 5) | (params->filter << 2);
if (!write_register8(dev, BMP280_REG_CONFIG, config)) {
return false;
}
if (params->mode == BMP280_MODE_FORCED) {
params->mode = BMP280_MODE_SLEEP; // initial mode for forced is sleep
}
uint8_t ctrl = (params->oversampling_temperature << 5)
| (params->oversampling_pressure << 2) | (params->mode);
if (dev->id == BME280_CHIP_ID) {
// Write crtl hum reg first, only active after write to BMP280_REG_CTRL.
uint8_t ctrl_hum = params->oversampling_humidity;
if (!write_register8(dev, BMP280_REG_CTRL_HUM, ctrl_hum)) {
return false;
}
}
if (!write_register8(dev, BMP280_REG_CTRL, ctrl)) {
return false;
}
return true;
}
bool bmp280_force_measurement(bmp280 *dev)
{
uint8_t ctrl;
if (!read_data(dev, BMP280_REG_CTRL, &ctrl, 1)) {
return false;
}
ctrl &= ~0b11; // clear two lower bits
ctrl |= BMP280_MODE_FORCED;
if (!write_register8(dev, BMP280_REG_CTRL, ctrl)) {
return false;
}
return true;
}
bool bmp280_is_measuring(bmp280 *dev)
{
uint8_t status;
if (!read_data(dev, BMP280_REG_STATUS, &status, 1)) {
return false;
}
if (status & (1 << 3)) {
return true;
}
return false;
}
/**
* Compensation algorithm is taken from BMP280 datasheet.
*
* Return value is in degrees Celsius.
*/
static inline int32_t compensate_temperature(bmp280 *dev, int32_t adc_temp, int32_t *fine_temp)
{
int32_t var1, var2;
var1 = ((((adc_temp >> 3) - ((int32_t) dev->dig_T1 << 1)))
* (int32_t) dev->dig_T2) >> 11;
var2 = (((((adc_temp >> 4) - (int32_t) dev->dig_T1)
* ((adc_temp >> 4) - (int32_t) dev->dig_T1)) >> 12)
* (int32_t) dev->dig_T3) >> 14;
*fine_temp = var1 + var2;
return (*fine_temp * 5 + 128) >> 8;
}
/**
* Compensation algorithm is taken from BMP280 datasheet.
*
* Return value is in Pa, 24 integer bits and 8 fractional bits.
*/
static inline uint32_t compensate_pressure(bmp280 *dev, int32_t adc_press, int32_t fine_temp)
{
int64_t var1, var2, p;
var1 = (int64_t) fine_temp - 128000;
var2 = var1 * var1 * (int64_t) dev->dig_P6;
var2 = var2 + ((var1 * (int64_t) dev->dig_P5) << 17);
var2 = var2 + (((int64_t) dev->dig_P4) << 35);
var1 = ((var1 * var1 * (int64_t) dev->dig_P3) >> 8)
+ ((var1 * (int64_t) dev->dig_P2) << 12);
var1 = (((int64_t) 1 << 47) + var1) * ((int64_t) dev->dig_P1) >> 33;
if (var1 == 0) {
return 0; // avoid exception caused by division by zero
}
p = 1048576 - adc_press;
p = (((p << 31) - var2) * 3125) / var1;
var1 = ((int64_t) dev->dig_P9 * (p >> 13) * (p >> 13)) >> 25;
var2 = ((int64_t) dev->dig_P8 * p) >> 19;
p = ((p + var1 + var2) >> 8) + ((int64_t) dev->dig_P7 << 4);
return p;
}
/**
* Compensation algorithm is taken from BME280 datasheet.
*
* Return value is in Pa, 24 integer bits and 8 fractional bits.
*/
static inline uint32_t compensate_humidity(bmp280 *dev, int32_t adc_hum, int32_t fine_temp)
{
int32_t v_x1_u32r;
v_x1_u32r = fine_temp - (int32_t) 76800;
v_x1_u32r = ((((adc_hum << 14) - ((int32_t) dev->dig_H4 << 20)
- ((int32_t) dev->dig_H5 * v_x1_u32r)) + (int32_t) 16384) >> 15)
* (((((((v_x1_u32r * (int32_t) dev->dig_H6) >> 10)
* (((v_x1_u32r * (int32_t) dev->dig_H3) >> 11)
+ (int32_t) 32768)) >> 10) + (int32_t) 2097152)
* (int32_t) dev->dig_H2 + 8192) >> 14);
v_x1_u32r = v_x1_u32r
- (((((v_x1_u32r >> 15) * (v_x1_u32r >> 15)) >> 7)
* (int32_t) dev->dig_H1) >> 4);
v_x1_u32r = v_x1_u32r < 0 ? 0 : v_x1_u32r;
v_x1_u32r = v_x1_u32r > 419430400 ? 419430400 : v_x1_u32r;
return v_x1_u32r >> 12;
}
bool bmp280_read_fixed(bmp280 *dev, int32_t *temperature, uint32_t *pressure, uint32_t *humidity)
{
int32_t adc_pressure;
int32_t adc_temp;
uint8_t data[8];
// Only the BME280 supports reading the humidity.
if (dev->id != BME280_CHIP_ID) {
if (humidity) {
*humidity = 0;
}
humidity = NULL;
}
// Need to read in one sequence to ensure they match.
uint8_t size = humidity ? 8 : 6;
if (!read_data(dev, 0xf7, data, size)) {
return false;
}
adc_pressure = data[0] << 12 | data[1] << 4 | data[2] >> 4;
adc_temp = data[3] << 12 | data[4] << 4 | data[5] >> 4;
int32_t fine_temp;
*temperature = compensate_temperature(dev, adc_temp, &fine_temp);
*pressure = compensate_pressure(dev, adc_pressure, fine_temp);
if (humidity) {
int32_t adc_humidity = data[6] << 8 | data[7];
*humidity = compensate_humidity(dev, adc_humidity, fine_temp);
}
return true;
}
bool bmp280_read_float(bmp280 *dev, float *temperature, float *pressure, float *humidity)
{
int32_t fixed_temperature;
uint32_t fixed_pressure;
uint32_t fixed_humidity;
if (!bmp280_read_fixed(dev, &fixed_temperature, &fixed_pressure, humidity ? &fixed_humidity : NULL)) {
return false;
}
*temperature = (float) fixed_temperature / 100;
*pressure = (float) fixed_pressure / 256;
if (humidity) {
*humidity = (float) fixed_humidity / 1024;
}
return true;
}

Wyświetl plik

@ -0,0 +1,173 @@
/**
* The MIT License (MIT)
* Ciastkolog.pl (https://github.com/ciastkolog)
* Copyright (c) 2016 sheinz (https://github.com/sheinz)
*/
#ifndef __BMP280_H__
#define __BMP280_H__
#include <stdint.h>
#include <stdbool.h>
#include "hal/i2c.h"
/**
* BMP280 or BME280 address is 0x77 if SDO pin is high, and is 0x76 if
* SDO pin is low.
*/
#define BMP280_I2C_ADDRESS_0 0x76
#define BMP280_I2C_ADDRESS_1 0x77
#define BMP280_CHIP_ID 0x58 /* BMP280 has chip-id 0x58 */
#define BME280_CHIP_ID 0x60 /* BME280 has chip-id 0x60 */
/**
* Mode of BMP280 module operation.
* Forced - Measurement is initiated by user.
* Normal - Continues measurement.
*/
typedef enum {
BMP280_MODE_SLEEP = 0,
BMP280_MODE_FORCED = 1,
BMP280_MODE_NORMAL = 3
} BMP280_Mode;
typedef enum {
BMP280_FILTER_OFF = 0,
BMP280_FILTER_2 = 1,
BMP280_FILTER_4 = 2,
BMP280_FILTER_8 = 3,
BMP280_FILTER_16 = 4
} BMP280_Filter;
/**
* Pressure oversampling settings
*/
typedef enum {
BMP280_SKIPPED = 0, /* no measurement */
BMP280_ULTRA_LOW_POWER = 1, /* oversampling x1 */
BMP280_LOW_POWER = 2, /* oversampling x2 */
BMP280_STANDARD = 3, /* oversampling x4 */
BMP280_HIGH_RES = 4, /* oversampling x8 */
BMP280_ULTRA_HIGH_RES = 5 /* oversampling x16 */
} BMP280_Oversampling;
/**
* Stand by time between measurements in normal mode
*/
typedef enum {
BMP280_STANDBY_05 = 0, /* stand by time 0.5ms */
BMP280_STANDBY_62 = 1, /* stand by time 62.5ms */
BMP280_STANDBY_125 = 2, /* stand by time 125ms */
BMP280_STANDBY_250 = 3, /* stand by time 250ms */
BMP280_STANDBY_500 = 4, /* stand by time 500ms */
BMP280_STANDBY_1000 = 5, /* stand by time 1s */
BMP280_STANDBY_2000 = 6, /* stand by time 2s BMP280, 10ms BME280 */
BMP280_STANDBY_4000 = 7, /* stand by time 4s BMP280, 20ms BME280 */
} BMP280_StandbyTime;
/**
* Configuration parameters for BMP280 module.
* Use function bmp280_init_default_params to use default configuration.
*/
typedef struct {
BMP280_Mode mode;
BMP280_Filter filter;
BMP280_Oversampling oversampling_pressure;
BMP280_Oversampling oversampling_temperature;
BMP280_Oversampling oversampling_humidity;
BMP280_StandbyTime standby;
} bmp280_params_t;
typedef struct _bmp280 {
uint16_t dig_T1;
int16_t dig_T2;
int16_t dig_T3;
uint16_t dig_P1;
int16_t dig_P2;
int16_t dig_P3;
int16_t dig_P4;
int16_t dig_P5;
int16_t dig_P6;
int16_t dig_P7;
int16_t dig_P8;
int16_t dig_P9;
/* Humidity compensation for BME280 */
uint8_t dig_H1;
int16_t dig_H2;
uint8_t dig_H3;
int16_t dig_H4;
int16_t dig_H5;
int8_t dig_H6;
uint16_t addr;
i2c_port *port;
bmp280_params_t params;
uint8_t id; /* Chip ID */
} bmp280;
/**
* Initialize default parameters.
* Default configuration:
* mode: NORAML
* filter: OFF
* oversampling: x4
* standby time: 250ms
*/
void bmp280_init_default_params(bmp280_params_t *params);
/**
* Initialize BMP280 module, probes for the device, soft resets the device,
* reads the calibration constants, and configures the device using the supplied
* parameters. Returns true on success otherwise false.
*
* The I2C address is assumed to have been initialized in the dev, and
* may be either BMP280_I2C_ADDRESS_0 or BMP280_I2C_ADDRESS_1. If the I2C
* address is unknown then try initializing each in turn.
*
* This may be called again to soft reset the device and initialize it again.
*/
bool bmp280_init(bmp280 *dev, bmp280_params_t *params);
/**
* Start measurement in forced mode.
* The module remains in forced mode after this call.
* Do not call this method in normal mode.
*/
bool bmp280_force_measurement(bmp280 *dev);
/**
* Check if BMP280 is busy with measuring temperature/pressure.
* Return true if BMP280 is busy.
*/
bool bmp280_is_measuring(bmp280 *dev);
/**
* Read compensated temperature and pressure data:
*
* Temperature in degrees Celsius times 100.
*
* Pressure in Pascals in fixed point 24 bit integer 8 bit fraction format.
*
* Humidity is optional and only read for the BME280, in percent relative
* humidity as a fixed point 22 bit interger and 10 bit fraction format.
*/
bool bmp280_read_fixed(bmp280 *dev, int32_t *temperature, uint32_t *pressure, uint32_t *humidity);
/**
* Read compensated temperature and pressure data:
* Temperature in degrees Celsius.
* Pressure in Pascals.
* Humidity is optional and only read for the BME280, in percent relative
* humidity.
*/
bool bmp280_read_float(bmp280 *dev, float *temperature, float *pressure, float *humidity);
#endif // __BMP280_H__

Wyświetl plik

@ -0,0 +1,146 @@
#include <stm32f10x_gpio.h>
#include "hal/spi.h"
#include "si4032.h"
#define SPI_WRITE_FLAG 0x80
#define SI4032_CLOCK 26.0f
#define GPIO_SI_4032_CS GPIOC
#define GPIO_PIN_SI4032_CS GPIO_Pin_13
static inline uint8_t si4032_write(uint8_t reg, uint8_t value)
{
return spi_send_and_receive(GPIO_SI_4032_CS, GPIO_PIN_SI4032_CS, ((reg | SPI_WRITE_FLAG) << 8U) | value);
}
static inline uint8_t si4032_read(uint8_t reg)
{
return spi_send_and_receive(GPIO_SI_4032_CS, GPIO_PIN_SI4032_CS, (reg << 8U) | 0xFFU);
}
void si4032_soft_reset()
{
si4032_write(0x07, 0x80);
}
void si4032_enable_tx()
{
// Modified to set the PLL and Crystal enable bits to high. Not sure if this makes much difference.
si4032_write(0x07, 0x4B);
}
void si4032_inhibit_tx()
{
// Sleep mode, but with PLL idle mode enabled, in an attempt to reduce drift on key-up.
si4032_write(0x07, 0x43);
}
void si4032_disable_tx()
{
si4032_write(0x07, 0x40);
}
void si4032_use_direct_mode(bool use)
{
if (use) {
GPIO_SetBits(GPIO_SI_4032_CS, GPIO_PIN_SI4032_CS);
} else {
GPIO_ResetBits(GPIO_SI_4032_CS, GPIO_PIN_SI4032_CS);
}
}
void si4032_set_tx_frequency(const float frequency_mhz)
{
uint8_t hbsel = (uint8_t) ((frequency_mhz * (30.0f / SI4032_CLOCK)) >= 480.0f ? 1 : 0);
uint8_t fb = (uint8_t) ((((uint8_t) ((frequency_mhz * (30.0f / SI4032_CLOCK)) / 10) - 24) - (24 * hbsel)) /
(1 + hbsel));
uint8_t gen_div = 3; // constant - not possible to change!
uint16_t fc = (uint16_t) (((frequency_mhz / ((SI4032_CLOCK / gen_div) * (hbsel + 1))) - fb - 24) * 64000);
si4032_write(0x75, (uint8_t) (0b01000000 | (fb & 0b11111) | ((hbsel & 0b1) << 5)));
si4032_write(0x76, (uint8_t) (((uint16_t) fc >> 8U) & 0xffU));
si4032_write(0x77, (uint8_t) ((uint16_t) fc & 0xff));
}
void si4032_set_tx_power(uint8_t power)
{
si4032_write(0x6D, power & 0x7U);
}
/**
* The frequency offset can be calculated as Offset = 156.25 Hz x (hbsel + 1) x fo[7:0]. fo[9:0] is a twos complement value. fo[9] is the sign bit.
* For 70cm band hbsel is 1, so offset step is 312.5 Hz
*/
void si4032_set_frequency_offset(uint16_t offset)
{
si4032_write(0x73, 0);
si4032_write(0x74, 0);
}
void si4032_set_frequency_deviation(uint8_t deviation)
{
// The frequency deviation can be calculated: Fd = 625 Hz x fd[8:0].
// Zero disables deviation between 0/1 bits
si4032_write(0x72, deviation);
}
void si4032_set_modulation_type(si4032_modulation_type type)
{
uint8_t value;
switch (type) {
case SI4032_MODULATION_TYPE_NONE:
// No modulation (for modulating via frequency offset, e.g. for RTTY)
value = 0x00;
break;
case SI4032_MODULATION_TYPE_OOK:
// Direct Async Mode with OOK modulation
value = 0b00010001;
break;
case SI4032_MODULATION_TYPE_FSK:
// Direct Async Mode with FSK modulation
value = 0b00010010;
break;
default:
return;
}
si4032_write(0x71, value);
}
int32_t si4032_read_temperature_celsius_100()
{
int32_t raw_value = (int32_t) si4032_read(0x11);
int32_t temperature = (int32_t) (-64 + (raw_value * 5 / 10) - 16);
// TODO: correct unit/scale
si4032_write(0x0f, 0x80);
return temperature;
}
void si4032_init()
{
GPIO_InitTypeDef gpio_init;
// Si4032 chip select pin
gpio_init.GPIO_Pin = GPIO_PIN_SI4032_CS;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIO_SI_4032_CS, &gpio_init);
si4032_soft_reset();
si4032_set_tx_power(0);
// Temperature Value Offset
si4032_write(0x13, 0xF0);
// Temperature Sensor Calibration
si4032_write(0x12, 0x00);
// ADC configuration
si4032_write(0x0f, 0x80);
si4032_set_frequency_offset(0);
si4032_set_frequency_deviation(5); // Was: 5 for APRS in RS41HUP?
si4032_set_modulation_type(SI4032_MODULATION_TYPE_NONE);
}

Wyświetl plik

@ -0,0 +1,26 @@
#ifndef __SI4032_H
#define __SI4032_h
#include <stdint.h>
#include <stdbool.h>
typedef enum _si4032_modulation_type {
SI4032_MODULATION_TYPE_NONE = 0,
SI4032_MODULATION_TYPE_OOK,
SI4032_MODULATION_TYPE_FSK,
} si4032_modulation_type;
void si4032_soft_reset();
void si4032_enable_tx();
void si4032_inhibit_tx();
void si4032_disable_tx();
void si4032_use_direct_mode(bool use);
void si4032_set_tx_frequency(float frequency_mhz);
void si4032_set_tx_power(uint8_t power);
void si4032_set_frequency_offset(uint16_t offset);
void si4032_set_frequency_deviation(uint8_t deviation);
void si4032_set_modulation_type(si4032_modulation_type type);
int32_t si4032_read_temperature_celsius_100();
void si4032_init();
#endif

Wyświetl plik

@ -0,0 +1,795 @@
Si5351 Library for Arduino
==========================
This is a library for the Si5351 series of clock generator ICs from [Silicon Labs](http://www.silabs.com) for the Arduino development environment. It will allow you to control the Si5351 with an Arduino, and without depending on the proprietary ClockBuilder software from Silicon Labs.
This library is focused towards usage in RF/amateur radio applications, but it may be useful in other cases. However, keep in mind that coding decisions are and will be made with those applications in mind first, so if you need something a bit different, please do fork this repository.
**Please feel free to use the Issues feature of GitHub if you run into problems or have suggestions for important features to implement. This is the best way to get in touch.**
Thanks For Your Support!
------------------------
If you would like to support my library development efforts, I would ask that you please consider purchasing a Si5351A Breakout Board from my [online store at etherkit.com](https://www.etherkit.com) sending a [one-time PayPal tip](https://paypal.me/NT7S), or [subscribe to me on SubscribeStar](https://www.subscribestar.com/nt7s) for an ongoing contribution. Thank you!
Library Installation
---------------------
The best way to install the library is via the Arduino Library Manager, which is available if you are using Arduino IDE version 1.6.2 or greater. To install it this way, simply go to the menu Sketch > Include Library > Manage Libraries..., and then in the search box at the upper-right, type "Etherkit Si5351". Click on the entry in the list below, then click on the provided "Install" button. By installing the library this way, you will always have notifications of future library updates, and can easily switch between library versions.
If you need to or would like to install the library in the old way, then you can download a copy of the library in a ZIP file. Download a ZIP file of the library from the GitHub repository by using the "Download ZIP" button at the right of the main repository page. Extract the ZIP file, then rename the unzipped folder as "Si5351". Finally, open the Arduino IDE, select menu Sketch > Import Library... > Add Library..., and select the renamed folder that you just downloaded. Restart the IDE and you should have access to the new library.
Hardware Requirements and Setup
-------------------------------
This library has been written for the Arduino platform and has been successfully tested on the Arduino Uno and an Uno clone. There should be no reason that it would not work on any other Arduino hardware with I2C support.
The Si5351 is a +3.3 V only part, so if you are not using a +3.3 V microcontroller, be sure you have some kind of level conversion strategy.
Wire the SDA and SCL pins of the Si5351 to the corresponding pins on the Arduino. Use the pin assignments posted on the [Arduino Wire library page](http://arduino.cc/en/Reference/Wire). Since the I2C interface is set to 100 kHz, use 1 to 10 k&Omega; pullup resistors from +3.3 V to the SDA and SCL lines.
Connect a 25 MHz or 27 MHz crystal with a load capacitance of 6, 8, or 10 pF to the Si5351 XA and XB pins. Locate the crystal as close to the Si5351 as possible and keep the traces as short as possible. Please use a SMT crystal. A crystal with leads will have too much stray capacitance.
Changes from v1 to v2
---------------------
The public interface to the v2 library is similar to the v1 library, but a few of the most-used methods have had their signatures changed, so your old programs won't compile right out-of-the-box after a library upgrade. Most importantly, the _init()_ and _set_freq()_ methods are different, so you'll at least need to change these calls in your old sketches.
The _init()_ method now has three parameters: the crystal load capacitance, the reference frequency, and the frequency correction value (with this last parameter being a new addition). You'll need to add that third parameter to your old _init()_ calls, but then you can delete any _set_correction()_ calls after that (unless you explicitly are changing the frequency correction after the initialization).
The _set_freq()_ method is now more streamlined and only requires two parameters: the desired output frequency (from 4 kHz to 225 MHz) and clock output. In your old code, you can delete the 2nd parameter in _set_freq()_, which was the PLL frequency. In case you want to do things manually, there is now a new method called _set_freq_manual()_ (see below for details).
Those two changes should cover nearly all upgrade scenarios, unless you were doing some lower-level use of the Si5351.
Example
-------
First, install the Si5351Arduino library into your instance of the Arduino IDE as described above.
There is a simple example named **si5351_example.ino** that is placed in your examples menu under the Si5351Arduino folder. Open this to see how to initialize the Si5351 and set a couple of the outputs to different frequencies. The commentary below will analyze the sample sketch.
Before you do anything with the Si5351, you will need to include the "si5351.h" and "Wire.h" header files and instantiate the Si5351 class.
#include "si5351.h"
#include "Wire.h"
Si5351 si5351;
Now in the _Setup()_ function, let's initialize communications with the Si5351, specify the load capacitance of the reference crystal, that we want to use the default reference oscillator frequency of 25 MHz (the second argument of "0" indicates that we want to use the default), and that we will apply no frequency correction at this point (the third argument of "0"):
i2c_found = si5351.init(SI5351_CRYSTAL_LOAD_8PF, 0, 0);
The _init()_ method returns a _bool_ which indicates whether the Arduino can communicate with a device on the I2C bus at the specified address (it does not verify that the device is an actual Si5351, but this is useful for ensuring that I2C communication is working).
Next, let's set the CLK0 output to 14 MHz:
si5351.set_freq(1400000000ULL, SI5351_CLK0);
Frequencies are indicated in units of 0.01 Hz. Therefore, if you prefer to work in 1 Hz increments in your own code, simply multiply each frequency passed to the library by 100ULL (better yet, use the define called _SI5351_FREQ_MULT_ in the header file for this multiplication).
In the main _Loop()_, we use the Serial port to monitor the status of the Si5351, using a method to update a public struct which holds the status bits:
si5351.update_status();
Serial.print("SYS_INIT: ");
Serial.print(si5351.dev_status.SYS_INIT);
Serial.print(" LOL_A: ");
Serial.print(si5351.dev_status.LOL_A);
Serial.print(" LOL_B: ");
Serial.print(si5351.dev_status.LOL_B);
Serial.print(" LOS: ");
Serial.print(si5351.dev_status.LOS);
Serial.print(" REVID: ");
Serial.println(si5351.dev_status.REVID);
When the synthesizers are locked and the Si5351 is working correctly, you'll see an output similar to this one (the REVID may be different):
SYS_INIT: 0 LOL_A: 0 LOL_B: 0 LOS: 0 REVID: 3
The nominal status for each of those flags is a 0. When the program indicates 1, there may be a reference clock problem, tuning problem, or some kind of other issue. (Note that it may take the Si5351 a bit of time to return the proper status flags, so in program initialization issue _update_status()_ and then give the Si5351 a few hundred milliseconds to initialize before querying the status flags again.)
A Brief Word about the Si5351 Architecture
------------------------------------------
The Si5351 consists of two main stages: two PLLs which are locked to the reference oscillator (a 25/27 MHz crystal) and which can be set from 600 to 900 MHz, and the output (multisynth) clocks which are locked to a PLL of choice and can be set from 500 kHz to 200 MHz (per the datasheet, although it does seem to be possible to set an output up to 225 MHz).
The B variant has an additional VCXO stage with control voltage pin which can be used as a reference synth for a clock output (PLLB must be used as the source for any VCXO output clock).
The C variant is able to take a reference clock input from 10 to 100 MHz separate from the standard crystal reference. If using this reference input, be sure to initialize the library with the correct frequency.
This library makes PLL assignments based on ease of use. They can be changed manually if needed, although that can introduce complications (see _Manually Selecting a PLL Frequency_ below).
Setting the Output Frequency
----------------------------
As indicated above, the library accepts and indicates clock and PLL frequencies in units of 0.01 Hz, as an _unsigned long long_ variable type (or _uint64_t_). When entering literal values, append ```ULL``` to make an explicit unsigned long long number to ensure proper tuning. Since many applications won't require sub-Hertz tuning, you may wish to use an _unsigned long_ (or _uint32_t_) variable to hold your tune frequency, then scale it up by multiplying by 100ULL before passing it to the _set_freq()_ method.
Using the _set_freq()_ method is the easiest way to use the library and gives you a wide range of tuning options, but has some constraints in its usage. Outputs CLK0 through CLK5 by default are all locked to PLLA while CLK6 and CLK7 are locked to PLLB. Due to the nature of the Si5351 architecture, there may only be one CLK output among those sharing a PLL which may be set greater than 100 MHz (actually specified at 112.5 MHz by SiLabs, but stability issues have been found at the upper end). Therefore, once one CLK output has been set above 100 MHz, no more CLKs on the same PLL will be allowed to be set greater than 100 MHz (unless the one which is already set is changed to a frequency below this threshold).
If the above constraints are not suitable, you need glitch-free tuning, or you are counting on multiple clocks being locked to the same reference, you may set the PLL frequency manually then make clock reference assignments to either of the PLLs.
Manually Selecting a PLL Frequency
----------------------------------
Instead of letting the library choose a PLL frequency for your chosen output frequency, you can choose it yourself in the _set_freq_manual()_ method. This method is similar to _set_freq()_, but the second argument is the desired PLL frequency:
si5351.set_freq_manual(19800000000ULL, 79200000000ULL, SI5351_CLK0);
**If you use this method (or the other methods to tweak the PLL and multisynth settings manually), it is very important to remember that the library will no longer properly track the PLL and multisynth settings and that you alone will be responsible for keeping the synths tuned properly. Strange things can happen to your other outputs if they are already in use. Be sure to read the Si5351 datasheet and Silicon Labs AN619 before doing this so that you understand what you are doing.**
When you are setting the PLL manually you need to be mindful of the limits of the IC. The multisynth (MS0 through MS5) is a fractional PLL, with limits described in AN619 as:
>Valid Multisynth divider ratios are 4, 6, 8, and any fractional value between 8 + 1/1,048,575 and 900 + 0/1.
This means that if any output is greater than 112.5 MHz (900 MHz/8), then this output frequency sets one
of the VCO frequencies.
To put this in other words, if you want to manually set the PLL and wish to have an output frequency greater than 100 MHz (changed in this library from the stated 112.5 MHz due to stability issues which were noticed), then the choice of PLL frequency is dictated by the choice of output frequency, and will need to be an even multiple of 4, 6, or 8.
Further Details
---------------
If we like we can adjust the output drive power:
si5351.drive_strength(SI5351_CLK0, SI5351_DRIVE_4MA);
The drive strength is the amount of current into a 50&Omega; load. 2 mA roughly corresponds to 3 dBm output and 8 mA is approximately 10 dBm output.
Individual outputs can be turned on and off. In the second argument, use a 0 to disable and 1 to enable:
si5351.output_enable(SI5351_CLK0, 0);
You may invert a clock output signal by using this command:
si5351.set_clock_invert(SI5351_CLK0, 1);
Calibration
-----------
There will be some inherent error in the reference oscillator's actual frequency, so we can account for this by measuring the difference between the uncalibrated actual and nominal output frequencies, then using that difference as a correction factor in the library. The _init()_ and _set_correction()_ methods use a signed integer calibration constant measured in parts-per-billion. The easiest way to determine this correction factor is to measure a 10 MHz signal from one of the clock outputs (in Hz, or better resolution if you can measure it), scale it to parts-per-billion, then use it in the _set_correction()_ method in future use of this particular reference oscillator. Once this correction factor is determined, it should not need to be measured again for the same reference oscillator/Si5351 pair unless you want to redo the calibration. With an accurate measurement at one frequency, this calibration should be good across the entire tuning range.
The calibration method is called like this:
si5351.set_correction(-6190, SI5351_PLL_INPUT_XO);
However, you may use the third argument in the _init()_ method to specify the frequency correction and may not actually need to use the explict _set_correction()_ method in your code.
A handy calibration program is provided with the library in the example folder named _si5351_calibration_. To use it, simply hook up your Arduino to your Si5351, then connect it to a PC with the Arduino IDE. Connect the CLK0 output of the Si5351 to a frequency counter capable of measuring at 10 MHz (the more resolution, the better). Load the sketch then open the serial terminal window. Follow the prompts in the serial terminal to change the output frequency until your frequency counter reads exactly 10.000 000 00 MHz. The output from the Arduino on your serial terminal will tell you the correction factor you will need for future use of that reference oscillator/Si5351 combination.
One thing to note: the library is set for a 25 MHz reference crystal. If you are using a 27 MHz crystal, use the second parameter in the _init()_ method to specify that as the reference oscillator frequency.
Phase
------
_Please see the example sketch **si5351_phase.ino**_
The phase of the output clock signal can be changed by using the set_phase() method. Phase is in relation to (and measured against the period of) the PLL that the output multisynth is referencing. When you change the phase register from its default of 0, you will need to keep a few considerations in mind.
Setting the phase of a clock requires that you manually set the PLL and take the PLL frequency into account when calculation the value to place in the phase register. As shown on page 10 of Silicon Labs Application Note 619 (AN619), the phase register is a 7-bit register, where a bit represents a phase difference of 1/4 the PLL period. Therefore, the best way to get an accurate phase setting is to make the PLL an even multiple of the clock frequency, depending on what phase you need.
If you need a 90 degree phase shift (as in many RF applications), then it is quite easy to determine your parameters. Pick a PLL frequency that is an even multiple of your clock frequency (remember that the PLL needs to be in the range of 600 to 900 MHz). Then to set a 90 degree phase shift, you simply enter that multiple into the phase register. Remember when setting multiple outputs to be phase-related to each other, they each need to be referenced to the same PLL.
You can see this in action in a sketch in the examples folder called _si5351phase_. It shows how one would set up an I/Q pair of signals at 14.1 MHz.
// We will output 14.1 MHz on CLK0 and CLK1.
// A PLLA frequency of 705 MHz was chosen to give an even
// divisor by 14.1 MHz.
unsigned long long freq = 1410000000ULL;
unsigned long long pll_freq = 70500000000ULL;
// Set CLK0 and CLK1 to output 14.1 MHz with a fixed PLL frequency
si5351.set_freq_manual(freq, pll_freq, SI5351_CLK0);
si5351.set_freq_manual(freq, pll_freq, SI5351_CLK1);
// Now we can set CLK1 to have a 90 deg phase shift by entering
// 50 in the CLK1 phase register, since the ratio of the PLL to
// the clock frequency is 50.
si5351.set_phase(SI5351_CLK0, 0);
si5351.set_phase(SI5351_CLK1, 50);
// We need to reset the PLL before they will be in phase alignment
si5351.pll_reset(SI5351_PLLA);
CLK Output Options
------------------
_Please see the example sketch **si5351_outputs.ino**_
In most cases, you will most likely end up using the multisynth associated with a CLK output, but the Si5351 has some other options available as well. The reference clocks (both the crystal oscillator and the CLKIN signal) can be mirrored to any CLK output. Also CLK1 through CLK3 can mirror the MS0 (CLK0) output, and likewise the CLK5 through CLK7 outputs can mirror the MS4 (CLK4) output.
If you choose to use one or more of these output options, you first need to enable the fanout option for that particular signal:
// Enable clock fanout for the XO
si5351.set_clock_fanout(SI5351_FANOUT_XO, 1);
Once that is done, you can use the _set_clock_source()_ method to choose the output option you desire. Since the CLK outputs by default are turned off, you may need to turn your CLK output on as well:
// Set CLK1 to output the XO signal
si5351.set_clock_source(SI5351_CLK1, SI5351_CLK_SRC_XTAL);
si5351.output_enable(SI5351_CLK1, 1);
Using the VCXO (Si5351B)
-----------------------
_Please see the example sketch **si5351_vcxo.ino**_
The Si5351B variant has a VCXO feature which can be used to provide voltage-tunable clock outputs, with a voltage control input on pin 3 of the IC. This functionality is provided on the PLLB oscillator internal to the Si5351, so you must assign any clock outputs that you wish to voltage control to PLLB.
The library has a method named _set_vcxo()_ that allows you to set the PLLB frequency and the amount of pull range that you wish to use on that oscillator (from 30 to 240 parts-per-million). Using the VCXO is similar to manually setting an output frequency. First, call the _set_vcxo()_ method:
#define PLLB_FREQ 87600000000ULL
// Set VCXO osc to 876 MHz (146 MHz x 6), 40 ppm pull
si5351.set_vcxo(PLLB_FREQ, 40);
Next, we assign the desired VCXO clock output to PLLB:
// Set CLK0 to be locked to VCXO
si5351.set_ms_source(SI5351_CLK0, SI5351_PLLB);
Finally, we use the _set_freq_manual()_ method to set the clock output center frequency:
// Tune to 146 MHz center frequency
si5351.set_freq_manual(14600000000ULL, PLLB_FREQ, SI5351_CLK0);
Using an External Reference (Si5351C)
-------------------------------------
_Please see the example sketch **si5351_ext_ref.ino**_
The Si5351C variant has a CLKIN input (pin 6) which allows the use of an alternate external CMOS clock reference from 10 to 100 MHz. Either PLLA and/or PLLB can be locked to this external reference. The library tracks the referenced frequencies and correction factors individually for both the crystal oscillator reference (XO) and external reference (CLKIN).
The XO reference frequency is set during the call to _init()_. If you are going to use the external reference clock, then set its nominal frequency with the _set_ref_freq()_ method:
// Set the CLKIN reference frequency to 10 MHz
si5351.set_ref_freq(10000000UL, SI5351_PLL_INPUT_CLKIN);
A correction factor for the external reference clock may also now be set:
// Apply a correction factor to CLKIN
si5351.set_correction(0, SI5351_PLL_INPUT_CLKIN);
The _set_pll_input()_ method is used to set the desired PLLs to reference to the external reference signal on CLKIN instead of the XO signal:
// Set PLLA and PLLB to use the signal on CLKIN instead of the XTAL
si5351.set_pll_input(SI5351_PLLA, SI5351_PLL_INPUT_CLKIN);
si5351.set_pll_input(SI5351_PLLB, SI5351_PLL_INPUT_CLKIN);
Once that is set, the library can be used as you normally would, with all of the frequency calculations done based on the reference frequency set in _set_ref_freq()_.
Alternate I2C Addresses
-----------------------
The standard I2C bus address for the Si5351 is 0x60, however there are other ICs in the wild that use alternate bus addresses. In order to accommodate these ICs, the class constructor can be called with the I2C bus address as a parameter, as shown in this example:
Si5351 si5351(0x61);
Startup Conditions
------------------
This library initializes the Si5351 parameters to the following values upon startup and on reset:
Multisynths 0 through 5 (and hence the matching clock outputs CLK0 through CLK5) are assigned to PLLA, while Multisynths 6 and 7 are assigned to PLLB.
PLLA and PLLB are set to 800 MHz (also defined as _SI5351_PLL_FIXED_ in the library).
All CLK outputs are set to 0 Hz and disabled.
Default drive strength is 2 mA on each output.
Constraints
-----------
* Two multisynths cannot share a PLL with when both outputs are >= 100 MHz. The library will refuse to set another multisynth to a frequency in that range if another multisynth sharing the same PLL is already within that frequency range.
* Setting phase will be limited in the extreme edges of the output tuning ranges. Because the phase register is 7-bits in size and is denominated in units representing 1/4 the PLL period, not all phases can be set for all output frequencies. For example, if you need a 90&deg; phase shift, the lowest frequency you can set it at is 4.6875 MHz (600 MHz PLL/128).
* The frequency range of Multisynth 6 and 7 is ~18.45 kHz to 150 MHz. The library assigns PLLB to these two multisynths, so if you choose to use both, then both frequencies must be an even divisor of the PLL frequency (between 6 and 254), so plan accordingly. You can see the current PLLB frequency by accessing the _pllb_freq_ public member.
* VCXO pull range can be &plusmn;30 to &plusmn;240 ppm
Public Methods
--------------
### init()
```
/*
* init(uint8_t xtal_load_c, uint32_t ref_osc_freq, int32_t corr)
*
* Setup communications to the Si5351 and set the crystal
* load capacitance.
*
* xtal_load_c - Crystal load capacitance. Use the SI5351_CRYSTAL_LOAD_*PF
* defines in the header file
* xo_freq - Crystal/reference oscillator frequency in 1 Hz increments.
* Defaults to 25000000 if a 0 is used here.
* corr - Frequency correction constant in parts-per-billion
*
* Returns a boolean that indicates whether a device was found on the desired
* I2C address.
*
*/
bool Si5351::init(uint8_t xtal_load_c, uint32_t ref_osc_freq, uint32_t ref_osc_freq)
```
### reset()
```
/*
* reset(void)
*
* Call to reset the Si5351 to the state initialized by the library.
*
*/
void Si5351::reset(void)
```
### set_freq()
```
/*
* set_freq(uint64_t freq, enum si5351_clock clk)
*
* Sets the clock frequency of the specified CLK output
*
* freq - Output frequency in Hz
* clk - Clock output
* (use the si5351_clock enum)
*/
uint8_t Si5351::set_freq(uint64_t freq, enum si5351_clock clk)
```
### set_freq_manual()
```
/*
* set_freq_manual(uint64_t freq, uint64_t pll_freq, enum si5351_clock clk)
*
* Sets the clock frequency of the specified CLK output using the given PLL
* frequency. You must ensure that the MS is assigned to the correct PLL and
* that the PLL is set to the correct frequency before using this method.
*
* It is important to note that if you use this method, you will have to
* track that all settings are sane yourself.
*
* freq - Output frequency in Hz
* pll_freq - Frequency of the PLL driving the Multisynth in Hz * 100
* clk - Clock output
* (use the si5351_clock enum)
*/
```
### set_pll()
```
/*
* set_pll(uint64_t pll_freq, enum si5351_pll target_pll)
*
* Set the specified PLL to a specific oscillation frequency
*
* pll_freq - Desired PLL frequency in Hz * 100
* target_pll - Which PLL to set
* (use the si5351_pll enum)
*/
void Si5351::set_pll(uint64_t pll_freq, enum si5351_pll target_pll)
```
### set_ms()
```
/*
* set_ms(enum si5351_clock clk, struct Si5351RegSet ms_reg, uint8_t int_mode, uint8_t r_div, uint8_t div_by_4)
*
* Set the specified multisynth parameters. Not normally needed, but public for advanced users.
*
* clk - Clock output
* (use the si5351_clock enum)
* int_mode - Set integer mode
* Set to 1 to enable, 0 to disable
* r_div - Desired r_div ratio
* div_by_4 - Set Divide By 4 mode
* Set to 1 to enable, 0 to disable
*/
void Si5351::set_ms(enum si5351_clock clk, struct Si5351RegSet ms_reg, uint8_t int_mode, uint8_t r_div, uint8_t div_by_4)
```
### output_enable()
```
/*
* output_enable(enum si5351_clock clk, uint8_t enable)
*
* Enable or disable a chosen output
* clk - Clock output
* (use the si5351_clock enum)
* enable - Set to 1 to enable, 0 to disable
*/
void Si5351::output_enable(enum si5351_clock clk, uint8_t enable)
```
### drive_strength()
```
/*
* drive_strength(enum si5351_clock clk, enum si5351_drive drive)
*
* Sets the drive strength of the specified clock output
*
* clk - Clock output
* (use the si5351_clock enum)
* drive - Desired drive level
* (use the si5351_drive enum)
*/
void Si5351::drive_strength(enum si5351_clock clk, enum si5351_drive drive)
```
### update_status()
```
/*
* update_status(void)
*
* Call this to update the status structs, then access them
* via the dev_status and dev_int_status global variables.
*
* See the header file for the struct definitions. These
* correspond to the flag names for registers 0 and 1 in
* the Si5351 datasheet.
*/
void Si5351::update_status(void)
```
### set_correction()
```
/*
* set_correction(int32_t corr, enum si5351_pll_input ref_osc)
*
* corr - Correction factor in ppb
* ref_osc - Desired reference oscillator
* (use the si5351_pll_input enum)
*
* Use this to set the oscillator correction factor.
* This value is a signed 32-bit integer of the
* parts-per-billion value that the actual oscillation
* frequency deviates from the specified frequency.
*
* The frequency calibration is done as a one-time procedure.
* Any desired test frequency within the normal range of the
* Si5351 should be set, then the actual output frequency
* should be measured as accurately as possible. The
* difference between the measured and specified frequencies
* should be calculated in Hertz, then multiplied by 10 in
* order to get the parts-per-billion value.
*
* Since the Si5351 itself has an intrinsic 0 PPM error, this
* correction factor is good across the entire tuning range of
* the Si5351. Once this calibration is done accurately, it
* should not have to be done again for the same Si5351 and
* crystal.
*/
void Si5351::set_correction(int32_t corr, enum si5351_pll_input ref_osc)
```
### set_phase()
```
/*
* set_phase(enum si5351_clock clk, uint8_t phase)
*
* clk - Clock output
* (use the si5351_clock enum)
* phase - 7-bit phase word
* (in units of VCO/4 period)
*
* Write the 7-bit phase register. This must be used
* with a user-set PLL frequency so that the user can
* calculate the proper tuning word based on the PLL period.
*/
void Si5351::set_phase(enum si5351_clock clk, uint8_t phase)
```
### get_correction()
```
/*
* get_correction(enum si5351_pll_input ref_osc)
*
* ref_osc - Desired reference oscillator
* 0: crystal oscillator (XO)
* 1: external clock input (CLKIN)
*
* Returns the oscillator correction factor stored
* in RAM.
*/
int32_t Si5351::get_correction(enum si5351_pll_input ref_osc)
```
### pll_reset()
```
/*
* pll_reset(enum si5351_pll target_pll)
*
* target_pll - Which PLL to reset
* (use the si5351_pll enum)
*
* Apply a reset to the indicated PLL.
*/
void Si5351::pll_reset(enum si5351_pll target_pll)
```
### set_ms_source()
```
/*
* set_ms_source(enum si5351_clock clk, enum si5351_pll pll)
*
* clk - Clock output
* (use the si5351_clock enum)
* pll - Which PLL to use as the source
* (use the si5351_pll enum)
*
* Set the desired PLL source for a multisynth.
*/
void Si5351::set_ms_source(enum si5351_clock clk, enum si5351_pll pll)
```
### set_int()
```
/*
* set_int(enum si5351_clock clk, uint8_t int_mode)
*
* clk - Clock output
* (use the si5351_clock enum)
* enable - Set to 1 to enable, 0 to disable
*
* Set the indicated multisynth into integer mode.
*/
void Si5351::set_int(enum si5351_clock clk, uint8_t enable)
```
### set_clock_pwr()
```
/*
* set_clock_pwr(enum si5351_clock clk, uint8_t pwr)
*
* clk - Clock output
* (use the si5351_clock enum)
* pwr - Set to 1 to enable, 0 to disable
*
* Enable or disable power to a clock output (a power
* saving feature).
*/
void Si5351::set_clock_pwr(enum si5351_clock clk, uint8_t pwr)
```
### set_clock_invert()
```
/*
* set_clock_invert(enum si5351_clock clk, uint8_t inv)
*
* clk - Clock output
* (use the si5351_clock enum)
* inv - Set to 1 to enable, 0 to disable
*
* Enable to invert the clock output waveform.
*/
void Si5351::set_clock_invert(enum si5351_clock clk, uint8_t inv)
```
### set_clock_source()
```
/*
* set_clock_source(enum si5351_clock clk, enum si5351_clock_source src)
*
* clk - Clock output
* (use the si5351_clock enum)
* src - Which clock source to use for the multisynth
* (use the si5351_clock_source enum)
*
* Set the clock source for a multisynth (based on the options
* presented for Registers 16-23 in the Silicon Labs AN619 document).
* Choices are XTAL, CLKIN, MS0, or the multisynth associated with
* the clock output.
*/
void Si5351::set_clock_source(enum si5351_clock clk, enum si5351_clock_source src)
```
### set_clock_disable()
```
/*
* set_clock_disable(enum si5351_clock clk, enum si5351_clock_disable dis_state)
*
* clk - Clock output
* (use the si5351_clock enum)
* dis_state - Desired state of the output upon disable
* (use the si5351_clock_disable enum)
*
* Set the state of the clock output when it is disabled. Per page 27
* of AN619 (Registers 24 and 25), there are four possible values: low,
* high, high impedance, and never disabled.
*/
void Si5351::set_clock_disable(enum si5351_clock clk, enum si5351_clock_disable dis_state)
```
### set_clock_fanout()
```
/*
* set_clock_fanout(enum si5351_clock_fanout fanout, uint8_t enable)
*
* fanout - Desired clock fanout
* (use the si5351_clock_fanout enum)
* enable - Set to 1 to enable, 0 to disable
*
* Use this function to enable or disable the clock fanout options
* for individual clock outputs. If you intend to output the XO or
* CLKIN on the clock outputs, enable this first.
*
* By default, only the Multisynth fanout is enabled at startup.
*/
void Si5351::set_clock_fanout(enum si5351_clock_fanout fanout, uint8_t enable)
```
### set_pll_input()
```
/*
* set_pll_input(enum si5351_pll pll, enum si5351_pll_input input)
*
* pll - Which PLL to use as the source
* (use the si5351_pll enum)
* input - Which reference oscillator to use as PLL input
* (use the si5351_pll_input enum)
*
* Set the desired reference oscillator source for the given PLL.
*/
void Si5351::set_pll_input(enum si5351_pll pll, enum si5351_pll_input input)
```
### set_vcxo()
```
/*
* set_vcxo(uint64_t pll_freq, uint8_t ppm)
*
* pll_freq - Desired PLL base frequency in Hz * 100
* ppm - VCXO pull limit in ppm
*
* Set the parameters for the VCXO on the Si5351B.
*/
void Si5351::set_vcxo(uint64_t pll_freq, uint8_t ppm)
```
### set_ref_freq()
```
/*
* set_ref_freq(uint32_t ref_freq, enum si5351_pll_input ref_osc)
*
* ref_freq - Reference oscillator frequency in Hz
* ref_osc - Which reference oscillator frequency to set
* (use the si5351_pll_input enum)
*
* Set the reference frequency value for the desired reference oscillator
*/
void Si5351::set_ref_freq(uint32_t ref_freq, enum si5351_pll_input ref_osc)
```
### si5351_write_bulk()
```
uint8_t Si5351::si5351_write_bulk(uint8_t addr, uint8_t bytes, uint8_t *data)
```
### si5351_write()
```
uint8_t Si5351::si5351_write(uint8_t addr, uint8_t data)
```
### si5351_read()
```
uint8_t Si5351::si5351_read(uint8_t addr)
```
Public Variables
----------------
struct Si5351Status dev_status;
struct Si5351IntStatus dev_int_status;
enum si5351_pll pll_assignment[8];
uint64_t clk_freq[8];
uint64_t plla_freq;
uint64_t pllb_freq;
uint32_t xtal_freq;
Tokens
------
Here are the defines, structs, and enumerations you will find handy to use with the library.
Crystal load capacitance:
SI5351_CRYSTAL_LOAD_0PF
SI5351_CRYSTAL_LOAD_6PF
SI5351_CRYSTAL_LOAD_8PF
SI5351_CRYSTAL_LOAD_10PF
Clock outputs:
enum si5351_clock {SI5351_CLK0, SI5351_CLK1, SI5351_CLK2, SI5351_CLK3,
SI5351_CLK4, SI5351_CLK5, SI5351_CLK6, SI5351_CLK7};
PLL sources:
enum si5351_pll {SI5351_PLLA, SI5351_PLLB};
Drive levels:
enum si5351_drive {SI5351_DRIVE_2MA, SI5351_DRIVE_4MA, SI5351_DRIVE_6MA, SI5351_DRIVE_8MA};
Clock sources:
enum si5351_clock_source {SI5351_CLK_SRC_XTAL, SI5351_CLK_SRC_CLKIN, SI5351_CLK_SRC_MS0, SI5351_CLK_SRC_MS};
Clock disable states:
enum si5351_clock_disable {SI5351_CLK_DISABLE_LOW, SI5351_CLK_DISABLE_HIGH, SI5351_CLK_DISABLE_HI_Z, SI5351_CLK_DISABLE_NEVER};
Clock fanout:
enum si5351_clock_fanout {SI5351_FANOUT_CLKIN, SI5351_FANOUT_XO, SI5351_FANOUT_MS};
PLL input sources:
enum si5351_pll_input{SI5351_PLL_INPUT_XO, SI5351_PLL_INPUT_CLKIN};
Status register:
struct Si5351Status
{
uint8_t SYS_INIT;
uint8_t LOL_B;
uint8_t LOL_A;
uint8_t LOS;
uint8_t REVID;
};
Interrupt register:
struct Si5351IntStatus
{
uint8_t SYS_INIT_STKY;
uint8_t LOL_B_STKY;
uint8_t LOL_A_STKY;
uint8_t LOS_STKY;
};
Raw Commands
------------
If you need to read and write raw data to the Si5351, there is public access to the library's _read()_, _write()_, and _write_bulk()_ methods.
Unsupported Features
--------------------
This library does not currently support the spread spectrum function of the Si5351.
Changelog
---------
* v2.1.4
* Fix warning "reg may be uninitialized"
* v2.1.3
* Correct error in si5351_example.ino sketch
* v2.1.2
* Correct error in si5351_calibration.ino sketch
* v2.1.1
* Add bool return value to _init()_ indicating whether a device is on the I2C bus
* v2.1.0
* Add support for reference frequencies and corrections for both the XO and CLKIN
* v2.0.7
* Change _set_freq()_ behavior so that the output is only automatically enabled the very first time that _set_freq()_ is called
* v2.0.6
* Call _set_pll()_ in _set_correction()_ to ensure that the new correction factor is applied
* v2.0.5
* Remove PLL reset from _set_freq()_ when not necessary
* v2.0.4
* Fix error in VCXO algorithm
* v2.0.3
* Fix regression in _set_freq()_ that wiped out proper R div setting, causing errors in setting low frequency outputs
* v2.0.2
* Increase maximum frequency in _set_freq()_ to 225 MHz
* Change SI5351_MULTISYNTH_SHARE_MAX from 112.5 MHz to 100 MHz due to stability issues
* Add explicit reset of VCXO param in _reset()_
* Add I2C bus address parameter and default to class constructor
* Update si5351_calibration example sketch
* v2.0.1
* Fix logic error in _set_freq()_ which causes errors in setting multiple clocks >100 MHz
* v2.0.0
* Complete rewrite of tuning algorithm
* Add support for setting CLK6 and CLK7
* Add support for VCXO (on Si5351B)
* Change interface of _init()_ and _set_freq()_
* Add _set_freq_manual()_ method
* Add _reset()_ method
* Added many new example sketches
* v1.1.2
* Fix error where register 183 is not pre-loaded with correct value per AN619. Add define for SI5351_CRYSTAL_LOAD_0PF (undocumented in AN619 but present in the official ClockBuilder software).
* v1.1.1
* Fix if statement eval error in _set_clock_disable()_
* v1.1.0
* Added _set_pll_input()_ method to allow toggling the PLL reference source for the Si5351C variant and added support to _init()_ for different PLL reference frequencies from 10 to 100 MHz.
* v1.0.0
* Initial release
[1]: http://www.silabs.com
[2]: https://www.etherkit.com

Wyświetl plik

@ -0,0 +1,674 @@
GNU GENERAL PUBLIC LICENSE
Version 3, 29 June 2007
Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
Preamble
The GNU General Public License is a free, copyleft license for
software and other kinds of works.
The licenses for most software and other practical works are designed
to take away your freedom to share and change the works. By contrast,
the GNU General Public License is intended to guarantee your freedom to
share and change all versions of a program--to make sure it remains free
software for all its users. We, the Free Software Foundation, use the
GNU General Public License for most of our software; it applies also to
any other work released this way by its authors. You can apply it to
your programs, too.
When we speak of free software, we are referring to freedom, not
price. Our General Public Licenses are designed to make sure that you
have the freedom to distribute copies of free software (and charge for
them if you wish), that you receive source code or can get it if you
want it, that you can change the software or use pieces of it in new
free programs, and that you know you can do these things.
To protect your rights, we need to prevent others from denying you
these rights or asking you to surrender the rights. Therefore, you have
certain responsibilities if you distribute copies of the software, or if
you modify it: responsibilities to respect the freedom of others.
For example, if you distribute copies of such a program, whether
gratis or for a fee, you must pass on to the recipients the same
freedoms that you received. You must make sure that they, too, receive
or can get the source code. And you must show them these terms so they
know their rights.
Developers that use the GNU GPL protect your rights with two steps:
(1) assert copyright on the software, and (2) offer you this License
giving you legal permission to copy, distribute and/or modify it.
For the developers' and authors' protection, the GPL clearly explains
that there is no warranty for this free software. For both users' and
authors' sake, the GPL requires that modified versions be marked as
changed, so that their problems will not be attributed erroneously to
authors of previous versions.
Some devices are designed to deny users access to install or run
modified versions of the software inside them, although the manufacturer
can do so. This is fundamentally incompatible with the aim of
protecting users' freedom to change the software. The systematic
pattern of such abuse occurs in the area of products for individuals to
use, which is precisely where it is most unacceptable. Therefore, we
have designed this version of the GPL to prohibit the practice for those
products. If such problems arise substantially in other domains, we
stand ready to extend this provision to those domains in future versions
of the GPL, as needed to protect the freedom of users.
Finally, every program is threatened constantly by software patents.
States should not allow patents to restrict development and use of
software on general-purpose computers, but in those that do, we wish to
avoid the special danger that patents applied to a free program could
make it effectively proprietary. To prevent this, the GPL assures that
patents cannot be used to render the program non-free.
The precise terms and conditions for copying, distribution and
modification follow.
TERMS AND CONDITIONS
0. Definitions.
"This License" refers to version 3 of the GNU General Public License.
"Copyright" also means copyright-like laws that apply to other kinds of
works, such as semiconductor masks.
"The Program" refers to any copyrightable work licensed under this
License. Each licensee is addressed as "you". "Licensees" and
"recipients" may be individuals or organizations.
To "modify" a work means to copy from or adapt all or part of the work
in a fashion requiring copyright permission, other than the making of an
exact copy. The resulting work is called a "modified version" of the
earlier work or a work "based on" the earlier work.
A "covered work" means either the unmodified Program or a work based
on the Program.
To "propagate" a work means to do anything with it that, without
permission, would make you directly or secondarily liable for
infringement under applicable copyright law, except executing it on a
computer or modifying a private copy. Propagation includes copying,
distribution (with or without modification), making available to the
public, and in some countries other activities as well.
To "convey" a work means any kind of propagation that enables other
parties to make or receive copies. Mere interaction with a user through
a computer network, with no transfer of a copy, is not conveying.
An interactive user interface displays "Appropriate Legal Notices"
to the extent that it includes a convenient and prominently visible
feature that (1) displays an appropriate copyright notice, and (2)
tells the user that there is no warranty for the work (except to the
extent that warranties are provided), that licensees may convey the
work under this License, and how to view a copy of this License. If
the interface presents a list of user commands or options, such as a
menu, a prominent item in the list meets this criterion.
1. Source Code.
The "source code" for a work means the preferred form of the work
for making modifications to it. "Object code" means any non-source
form of a work.
A "Standard Interface" means an interface that either is an official
standard defined by a recognized standards body, or, in the case of
interfaces specified for a particular programming language, one that
is widely used among developers working in that language.
The "System Libraries" of an executable work include anything, other
than the work as a whole, that (a) is included in the normal form of
packaging a Major Component, but which is not part of that Major
Component, and (b) serves only to enable use of the work with that
Major Component, or to implement a Standard Interface for which an
implementation is available to the public in source code form. A
"Major Component", in this context, means a major essential component
(kernel, window system, and so on) of the specific operating system
(if any) on which the executable work runs, or a compiler used to
produce the work, or an object code interpreter used to run it.
The "Corresponding Source" for a work in object code form means all
the source code needed to generate, install, and (for an executable
work) run the object code and to modify the work, including scripts to
control those activities. However, it does not include the work's
System Libraries, or general-purpose tools or generally available free
programs which are used unmodified in performing those activities but
which are not part of the work. For example, Corresponding Source
includes interface definition files associated with source files for
the work, and the source code for shared libraries and dynamically
linked subprograms that the work is specifically designed to require,
such as by intimate data communication or control flow between those
subprograms and other parts of the work.
The Corresponding Source need not include anything that users
can regenerate automatically from other parts of the Corresponding
Source.
The Corresponding Source for a work in source code form is that
same work.
2. Basic Permissions.
All rights granted under this License are granted for the term of
copyright on the Program, and are irrevocable provided the stated
conditions are met. This License explicitly affirms your unlimited
permission to run the unmodified Program. The output from running a
covered work is covered by this License only if the output, given its
content, constitutes a covered work. This License acknowledges your
rights of fair use or other equivalent, as provided by copyright law.
You may make, run and propagate covered works that you do not
convey, without conditions so long as your license otherwise remains
in force. You may convey covered works to others for the sole purpose
of having them make modifications exclusively for you, or provide you
with facilities for running those works, provided that you comply with
the terms of this License in conveying all material for which you do
not control copyright. Those thus making or running the covered works
for you must do so exclusively on your behalf, under your direction
and control, on terms that prohibit them from making any copies of
your copyrighted material outside their relationship with you.
Conveying under any other circumstances is permitted solely under
the conditions stated below. Sublicensing is not allowed; section 10
makes it unnecessary.
3. Protecting Users' Legal Rights From Anti-Circumvention Law.
No covered work shall be deemed part of an effective technological
measure under any applicable law fulfilling obligations under article
11 of the WIPO copyright treaty adopted on 20 December 1996, or
similar laws prohibiting or restricting circumvention of such
measures.
When you convey a covered work, you waive any legal power to forbid
circumvention of technological measures to the extent such circumvention
is effected by exercising rights under this License with respect to
the covered work, and you disclaim any intention to limit operation or
modification of the work as a means of enforcing, against the work's
users, your or third parties' legal rights to forbid circumvention of
technological measures.
4. Conveying Verbatim Copies.
You may convey verbatim copies of the Program's source code as you
receive it, in any medium, provided that you conspicuously and
appropriately publish on each copy an appropriate copyright notice;
keep intact all notices stating that this License and any
non-permissive terms added in accord with section 7 apply to the code;
keep intact all notices of the absence of any warranty; and give all
recipients a copy of this License along with the Program.
You may charge any price or no price for each copy that you convey,
and you may offer support or warranty protection for a fee.
5. Conveying Modified Source Versions.
You may convey a work based on the Program, or the modifications to
produce it from the Program, in the form of source code under the
terms of section 4, provided that you also meet all of these conditions:
a) The work must carry prominent notices stating that you modified
it, and giving a relevant date.
b) The work must carry prominent notices stating that it is
released under this License and any conditions added under section
7. This requirement modifies the requirement in section 4 to
"keep intact all notices".
c) You must license the entire work, as a whole, under this
License to anyone who comes into possession of a copy. This
License will therefore apply, along with any applicable section 7
additional terms, to the whole of the work, and all its parts,
regardless of how they are packaged. This License gives no
permission to license the work in any other way, but it does not
invalidate such permission if you have separately received it.
d) If the work has interactive user interfaces, each must display
Appropriate Legal Notices; however, if the Program has interactive
interfaces that do not display Appropriate Legal Notices, your
work need not make them do so.
A compilation of a covered work with other separate and independent
works, which are not by their nature extensions of the covered work,
and which are not combined with it such as to form a larger program,
in or on a volume of a storage or distribution medium, is called an
"aggregate" if the compilation and its resulting copyright are not
used to limit the access or legal rights of the compilation's users
beyond what the individual works permit. Inclusion of a covered work
in an aggregate does not cause this License to apply to the other
parts of the aggregate.
6. Conveying Non-Source Forms.
You may convey a covered work in object code form under the terms
of sections 4 and 5, provided that you also convey the
machine-readable Corresponding Source under the terms of this License,
in one of these ways:
a) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by the
Corresponding Source fixed on a durable physical medium
customarily used for software interchange.
b) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by a
written offer, valid for at least three years and valid for as
long as you offer spare parts or customer support for that product
model, to give anyone who possesses the object code either (1) a
copy of the Corresponding Source for all the software in the
product that is covered by this License, on a durable physical
medium customarily used for software interchange, for a price no
more than your reasonable cost of physically performing this
conveying of source, or (2) access to copy the
Corresponding Source from a network server at no charge.
c) Convey individual copies of the object code with a copy of the
written offer to provide the Corresponding Source. This
alternative is allowed only occasionally and noncommercially, and
only if you received the object code with such an offer, in accord
with subsection 6b.
d) Convey the object code by offering access from a designated
place (gratis or for a charge), and offer equivalent access to the
Corresponding Source in the same way through the same place at no
further charge. You need not require recipients to copy the
Corresponding Source along with the object code. If the place to
copy the object code is a network server, the Corresponding Source
may be on a different server (operated by you or a third party)
that supports equivalent copying facilities, provided you maintain
clear directions next to the object code saying where to find the
Corresponding Source. Regardless of what server hosts the
Corresponding Source, you remain obligated to ensure that it is
available for as long as needed to satisfy these requirements.
e) Convey the object code using peer-to-peer transmission, provided
you inform other peers where the object code and Corresponding
Source of the work are being offered to the general public at no
charge under subsection 6d.
A separable portion of the object code, whose source code is excluded
from the Corresponding Source as a System Library, need not be
included in conveying the object code work.
A "User Product" is either (1) a "consumer product", which means any
tangible personal property which is normally used for personal, family,
or household purposes, or (2) anything designed or sold for incorporation
into a dwelling. In determining whether a product is a consumer product,
doubtful cases shall be resolved in favor of coverage. For a particular
product received by a particular user, "normally used" refers to a
typical or common use of that class of product, regardless of the status
of the particular user or of the way in which the particular user
actually uses, or expects or is expected to use, the product. A product
is a consumer product regardless of whether the product has substantial
commercial, industrial or non-consumer uses, unless such uses represent
the only significant mode of use of the product.
"Installation Information" for a User Product means any methods,
procedures, authorization keys, or other information required to install
and execute modified versions of a covered work in that User Product from
a modified version of its Corresponding Source. The information must
suffice to ensure that the continued functioning of the modified object
code is in no case prevented or interfered with solely because
modification has been made.
If you convey an object code work under this section in, or with, or
specifically for use in, a User Product, and the conveying occurs as
part of a transaction in which the right of possession and use of the
User Product is transferred to the recipient in perpetuity or for a
fixed term (regardless of how the transaction is characterized), the
Corresponding Source conveyed under this section must be accompanied
by the Installation Information. But this requirement does not apply
if neither you nor any third party retains the ability to install
modified object code on the User Product (for example, the work has
been installed in ROM).
The requirement to provide Installation Information does not include a
requirement to continue to provide support service, warranty, or updates
for a work that has been modified or installed by the recipient, or for
the User Product in which it has been modified or installed. Access to a
network may be denied when the modification itself materially and
adversely affects the operation of the network or violates the rules and
protocols for communication across the network.
Corresponding Source conveyed, and Installation Information provided,
in accord with this section must be in a format that is publicly
documented (and with an implementation available to the public in
source code form), and must require no special password or key for
unpacking, reading or copying.
7. Additional Terms.
"Additional permissions" are terms that supplement the terms of this
License by making exceptions from one or more of its conditions.
Additional permissions that are applicable to the entire Program shall
be treated as though they were included in this License, to the extent
that they are valid under applicable law. If additional permissions
apply only to part of the Program, that part may be used separately
under those permissions, but the entire Program remains governed by
this License without regard to the additional permissions.
When you convey a copy of a covered work, you may at your option
remove any additional permissions from that copy, or from any part of
it. (Additional permissions may be written to require their own
removal in certain cases when you modify the work.) You may place
additional permissions on material, added by you to a covered work,
for which you have or can give appropriate copyright permission.
Notwithstanding any other provision of this License, for material you
add to a covered work, you may (if authorized by the copyright holders of
that material) supplement the terms of this License with terms:
a) Disclaiming warranty or limiting liability differently from the
terms of sections 15 and 16 of this License; or
b) Requiring preservation of specified reasonable legal notices or
author attributions in that material or in the Appropriate Legal
Notices displayed by works containing it; or
c) Prohibiting misrepresentation of the origin of that material, or
requiring that modified versions of such material be marked in
reasonable ways as different from the original version; or
d) Limiting the use for publicity purposes of names of licensors or
authors of the material; or
e) Declining to grant rights under trademark law for use of some
trade names, trademarks, or service marks; or
f) Requiring indemnification of licensors and authors of that
material by anyone who conveys the material (or modified versions of
it) with contractual assumptions of liability to the recipient, for
any liability that these contractual assumptions directly impose on
those licensors and authors.
All other non-permissive additional terms are considered "further
restrictions" within the meaning of section 10. If the Program as you
received it, or any part of it, contains a notice stating that it is
governed by this License along with a term that is a further
restriction, you may remove that term. If a license document contains
a further restriction but permits relicensing or conveying under this
License, you may add to a covered work material governed by the terms
of that license document, provided that the further restriction does
not survive such relicensing or conveying.
If you add terms to a covered work in accord with this section, you
must place, in the relevant source files, a statement of the
additional terms that apply to those files, or a notice indicating
where to find the applicable terms.
Additional terms, permissive or non-permissive, may be stated in the
form of a separately written license, or stated as exceptions;
the above requirements apply either way.
8. Termination.
You may not propagate or modify a covered work except as expressly
provided under this License. Any attempt otherwise to propagate or
modify it is void, and will automatically terminate your rights under
this License (including any patent licenses granted under the third
paragraph of section 11).
However, if you cease all violation of this License, then your
license from a particular copyright holder is reinstated (a)
provisionally, unless and until the copyright holder explicitly and
finally terminates your license, and (b) permanently, if the copyright
holder fails to notify you of the violation by some reasonable means
prior to 60 days after the cessation.
Moreover, your license from a particular copyright holder is
reinstated permanently if the copyright holder notifies you of the
violation by some reasonable means, this is the first time you have
received notice of violation of this License (for any work) from that
copyright holder, and you cure the violation prior to 30 days after
your receipt of the notice.
Termination of your rights under this section does not terminate the
licenses of parties who have received copies or rights from you under
this License. If your rights have been terminated and not permanently
reinstated, you do not qualify to receive new licenses for the same
material under section 10.
9. Acceptance Not Required for Having Copies.
You are not required to accept this License in order to receive or
run a copy of the Program. Ancillary propagation of a covered work
occurring solely as a consequence of using peer-to-peer transmission
to receive a copy likewise does not require acceptance. However,
nothing other than this License grants you permission to propagate or
modify any covered work. These actions infringe copyright if you do
not accept this License. Therefore, by modifying or propagating a
covered work, you indicate your acceptance of this License to do so.
10. Automatic Licensing of Downstream Recipients.
Each time you convey a covered work, the recipient automatically
receives a license from the original licensors, to run, modify and
propagate that work, subject to this License. You are not responsible
for enforcing compliance by third parties with this License.
An "entity transaction" is a transaction transferring control of an
organization, or substantially all assets of one, or subdividing an
organization, or merging organizations. If propagation of a covered
work results from an entity transaction, each party to that
transaction who receives a copy of the work also receives whatever
licenses to the work the party's predecessor in interest had or could
give under the previous paragraph, plus a right to possession of the
Corresponding Source of the work from the predecessor in interest, if
the predecessor has it or can get it with reasonable efforts.
You may not impose any further restrictions on the exercise of the
rights granted or affirmed under this License. For example, you may
not impose a license fee, royalty, or other charge for exercise of
rights granted under this License, and you may not initiate litigation
(including a cross-claim or counterclaim in a lawsuit) alleging that
any patent claim is infringed by making, using, selling, offering for
sale, or importing the Program or any portion of it.
11. Patents.
A "contributor" is a copyright holder who authorizes use under this
License of the Program or a work on which the Program is based. The
work thus licensed is called the contributor's "contributor version".
A contributor's "essential patent claims" are all patent claims
owned or controlled by the contributor, whether already acquired or
hereafter acquired, that would be infringed by some manner, permitted
by this License, of making, using, or selling its contributor version,
but do not include claims that would be infringed only as a
consequence of further modification of the contributor version. For
purposes of this definition, "control" includes the right to grant
patent sublicenses in a manner consistent with the requirements of
this License.
Each contributor grants you a non-exclusive, worldwide, royalty-free
patent license under the contributor's essential patent claims, to
make, use, sell, offer for sale, import and otherwise run, modify and
propagate the contents of its contributor version.
In the following three paragraphs, a "patent license" is any express
agreement or commitment, however denominated, not to enforce a patent
(such as an express permission to practice a patent or covenant not to
sue for patent infringement). To "grant" such a patent license to a
party means to make such an agreement or commitment not to enforce a
patent against the party.
If you convey a covered work, knowingly relying on a patent license,
and the Corresponding Source of the work is not available for anyone
to copy, free of charge and under the terms of this License, through a
publicly available network server or other readily accessible means,
then you must either (1) cause the Corresponding Source to be so
available, or (2) arrange to deprive yourself of the benefit of the
patent license for this particular work, or (3) arrange, in a manner
consistent with the requirements of this License, to extend the patent
license to downstream recipients. "Knowingly relying" means you have
actual knowledge that, but for the patent license, your conveying the
covered work in a country, or your recipient's use of the covered work
in a country, would infringe one or more identifiable patents in that
country that you have reason to believe are valid.
If, pursuant to or in connection with a single transaction or
arrangement, you convey, or propagate by procuring conveyance of, a
covered work, and grant a patent license to some of the parties
receiving the covered work authorizing them to use, propagate, modify
or convey a specific copy of the covered work, then the patent license
you grant is automatically extended to all recipients of the covered
work and works based on it.
A patent license is "discriminatory" if it does not include within
the scope of its coverage, prohibits the exercise of, or is
conditioned on the non-exercise of one or more of the rights that are
specifically granted under this License. You may not convey a covered
work if you are a party to an arrangement with a third party that is
in the business of distributing software, under which you make payment
to the third party based on the extent of your activity of conveying
the work, and under which the third party grants, to any of the
parties who would receive the covered work from you, a discriminatory
patent license (a) in connection with copies of the covered work
conveyed by you (or copies made from those copies), or (b) primarily
for and in connection with specific products or compilations that
contain the covered work, unless you entered into that arrangement,
or that patent license was granted, prior to 28 March 2007.
Nothing in this License shall be construed as excluding or limiting
any implied license or other defenses to infringement that may
otherwise be available to you under applicable patent law.
12. No Surrender of Others' Freedom.
If conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License. If you cannot convey a
covered work so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you may
not convey it at all. For example, if you agree to terms that obligate you
to collect a royalty for further conveying from those to whom you convey
the Program, the only way you could satisfy both those terms and this
License would be to refrain entirely from conveying the Program.
13. Use with the GNU Affero General Public License.
Notwithstanding any other provision of this License, you have
permission to link or combine any covered work with a work licensed
under version 3 of the GNU Affero General Public License into a single
combined work, and to convey the resulting work. The terms of this
License will continue to apply to the part which is the covered work,
but the special requirements of the GNU Affero General Public License,
section 13, concerning interaction through a network will apply to the
combination as such.
14. Revised Versions of this License.
The Free Software Foundation may publish revised and/or new versions of
the GNU General Public License from time to time. Such new versions will
be similar in spirit to the present version, but may differ in detail to
address new problems or concerns.
Each version is given a distinguishing version number. If the
Program specifies that a certain numbered version of the GNU General
Public License "or any later version" applies to it, you have the
option of following the terms and conditions either of that numbered
version or of any later version published by the Free Software
Foundation. If the Program does not specify a version number of the
GNU General Public License, you may choose any version ever published
by the Free Software Foundation.
If the Program specifies that a proxy can decide which future
versions of the GNU General Public License can be used, that proxy's
public statement of acceptance of a version permanently authorizes you
to choose that version for the Program.
Later license versions may give you additional or different
permissions. However, no additional obligations are imposed on any
author or copyright holder as a result of your choosing to follow a
later version.
15. Disclaimer of Warranty.
THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
16. Limitation of Liability.
IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGES.
17. Interpretation of Sections 15 and 16.
If the disclaimer of warranty and limitation of liability provided
above cannot be given local legal effect according to their terms,
reviewing courts shall apply local law that most closely approximates
an absolute waiver of all civil liability in connection with the
Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee.
END OF TERMS AND CONDITIONS
How to Apply These Terms to Your New Programs
If you develop a new program, and you want it to be of the greatest
possible use to the public, the best way to achieve this is to make it
free software which everyone can redistribute and change under these terms.
To do so, attach the following notices to the program. It is safest
to attach them to the start of each source file to most effectively
state the exclusion of warranty; and each file should have at least
the "copyright" line and a pointer to where the full notice is found.
<one line to give the program's name and a brief idea of what it does.>
Copyright (C) <year> <name of author>
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
Also add information on how to contact you by electronic and paper mail.
If the program does terminal interaction, make it output a short
notice like this when it starts in an interactive mode:
<program> Copyright (C) <year> <name of author>
This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
This is free software, and you are welcome to redistribute it
under certain conditions; type `show c' for details.
The hypothetical commands `show w' and `show c' should show the appropriate
parts of the General Public License. Of course, your program's commands
might be different; for a GUI interface, you would use an "about box".
You should also get your employer (if you work as a programmer) or school,
if any, to sign a "copyright disclaimer" for the program, if necessary.
For more information on this, and how to apply and follow the GNU GPL, see
<http://www.gnu.org/licenses/>.
The GNU General Public License does not permit incorporating your program
into proprietary programs. If your program is a subroutine library, you
may consider it more useful to permit linking proprietary applications with
the library. If this is what you want to do, use the GNU Lesser General
Public License instead of this License. But first, please read
<http://www.gnu.org/philosophy/why-not-lgpl.html>.

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,379 @@
/*
* si5351.h - Si5351 library for Arduino
*
* Copyright (C) 2015 - 2019 Jason Milldrum <milldrum@gmail.com>
* Dana H. Myers <k6jq@comcast.net>
*
* Many defines derived from clk-si5351.h in the Linux kernel.
* Sebastian Hesselbarth <sebastian.hesselbarth@gmail.com>
* Rabeeh Khoury <rabeeh@solid-run.com>
*
* do_div() macro derived from /include/asm-generic/div64.h in
* the Linux kernel.
* Copyright (C) 2003 Bernardo Innocenti <bernie@develer.com>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef SI5351_H_
#define SI5351_H_
#include "hal/i2c.h"
/* Define definitions */
#define SI5351_BUS_BASE_ADDR 0x60
#define SI5351_XTAL_FREQ 25000000
#define SI5351_PLL_FIXED 80000000000ULL
#define SI5351_FREQ_MULT 100ULL
#define SI5351_DEFAULT_CLK 1000000000ULL
#define SI5351_PLL_VCO_MIN 600000000
#define SI5351_PLL_VCO_MAX 900000000
#define SI5351_MULTISYNTH_MIN_FREQ 500000
#define SI5351_MULTISYNTH_DIVBY4_FREQ 150000000
#define SI5351_MULTISYNTH_MAX_FREQ 225000000
#define SI5351_MULTISYNTH_SHARE_MAX 100000000
#define SI5351_MULTISYNTH_SHARE_MIN 1024000
#define SI5351_MULTISYNTH67_MAX_FREQ SI5351_MULTISYNTH_DIVBY4_FREQ
#define SI5351_CLKOUT_MIN_FREQ 4000
#define SI5351_CLKOUT_MAX_FREQ SI5351_MULTISYNTH_MAX_FREQ
#define SI5351_CLKOUT67_MS_MIN SI5351_PLL_VCO_MIN / SI5351_MULTISYNTH67_A_MAX
#define SI5351_CLKOUT67_MIN_FREQ SI5351_CLKOUT67_MS_MIN / 128
#define SI5351_CLKOUT67_MAX_FREQ SI5351_MULTISYNTH67_MAX_FREQ
#define SI5351_PLL_A_MIN 15
#define SI5351_PLL_A_MAX 90
#define SI5351_PLL_B_MAX (SI5351_PLL_C_MAX-1)
#define SI5351_PLL_C_MAX 1048575
#define SI5351_MULTISYNTH_A_MIN 6
#define SI5351_MULTISYNTH_A_MAX 1800
#define SI5351_MULTISYNTH67_A_MAX 254
#define SI5351_MULTISYNTH_B_MAX (SI5351_MULTISYNTH_C_MAX-1)
#define SI5351_MULTISYNTH_C_MAX 1048575
#define SI5351_MULTISYNTH_P1_MAX ((1<<18)-1)
#define SI5351_MULTISYNTH_P2_MAX ((1<<20)-1)
#define SI5351_MULTISYNTH_P3_MAX ((1<<20)-1)
#define SI5351_VCXO_PULL_MIN 30
#define SI5351_VCXO_PULL_MAX 240
#define SI5351_VCXO_MARGIN 103
#define SI5351_DEVICE_STATUS 0
#define SI5351_INTERRUPT_STATUS 1
#define SI5351_INTERRUPT_MASK 2
#define SI5351_STATUS_SYS_INIT (1<<7)
#define SI5351_STATUS_LOL_B (1<<6)
#define SI5351_STATUS_LOL_A (1<<5)
#define SI5351_STATUS_LOS (1<<4)
#define SI5351_OUTPUT_ENABLE_CTRL 3
#define SI5351_OEB_PIN_ENABLE_CTRL 9
#define SI5351_PLL_INPUT_SOURCE 15
#define SI5351_CLKIN_DIV_MASK (3<<6)
#define SI5351_CLKIN_DIV_1 (0<<6)
#define SI5351_CLKIN_DIV_2 (1<<6)
#define SI5351_CLKIN_DIV_4 (2<<6)
#define SI5351_CLKIN_DIV_8 (3<<6)
#define SI5351_PLLB_SOURCE (1<<3)
#define SI5351_PLLA_SOURCE (1<<2)
#define SI5351_CLK0_CTRL 16
#define SI5351_CLK1_CTRL 17
#define SI5351_CLK2_CTRL 18
#define SI5351_CLK3_CTRL 19
#define SI5351_CLK4_CTRL 20
#define SI5351_CLK5_CTRL 21
#define SI5351_CLK6_CTRL 22
#define SI5351_CLK7_CTRL 23
#define SI5351_CLK_POWERDOWN (1<<7)
#define SI5351_CLK_INTEGER_MODE (1<<6)
#define SI5351_CLK_PLL_SELECT (1<<5)
#define SI5351_CLK_INVERT (1<<4)
#define SI5351_CLK_INPUT_MASK (3<<2)
#define SI5351_CLK_INPUT_XTAL (0<<2)
#define SI5351_CLK_INPUT_CLKIN (1<<2)
#define SI5351_CLK_INPUT_MULTISYNTH_0_4 (2<<2)
#define SI5351_CLK_INPUT_MULTISYNTH_N (3<<2)
#define SI5351_CLK_DRIVE_STRENGTH_MASK (3<<0)
#define SI5351_CLK_DRIVE_STRENGTH_2MA (0<<0)
#define SI5351_CLK_DRIVE_STRENGTH_4MA (1<<0)
#define SI5351_CLK_DRIVE_STRENGTH_6MA (2<<0)
#define SI5351_CLK_DRIVE_STRENGTH_8MA (3<<0)
#define SI5351_CLK3_0_DISABLE_STATE 24
#define SI5351_CLK7_4_DISABLE_STATE 25
#define SI5351_CLK_DISABLE_STATE_MASK 3
#define SI5351_CLK_DISABLE_STATE_LOW 0
#define SI5351_CLK_DISABLE_STATE_HIGH 1
#define SI5351_CLK_DISABLE_STATE_FLOAT 2
#define SI5351_CLK_DISABLE_STATE_NEVER 3
#define SI5351_PARAMETERS_LENGTH 8
#define SI5351_PLLA_PARAMETERS 26
#define SI5351_PLLB_PARAMETERS 34
#define SI5351_CLK0_PARAMETERS 42
#define SI5351_CLK1_PARAMETERS 50
#define SI5351_CLK2_PARAMETERS 58
#define SI5351_CLK3_PARAMETERS 66
#define SI5351_CLK4_PARAMETERS 74
#define SI5351_CLK5_PARAMETERS 82
#define SI5351_CLK6_PARAMETERS 90
#define SI5351_CLK7_PARAMETERS 91
#define SI5351_CLK6_7_OUTPUT_DIVIDER 92
#define SI5351_OUTPUT_CLK_DIV_MASK (7 << 4)
#define SI5351_OUTPUT_CLK6_DIV_MASK (7 << 0)
#define SI5351_OUTPUT_CLK_DIV_SHIFT 4
#define SI5351_OUTPUT_CLK_DIV6_SHIFT 0
#define SI5351_OUTPUT_CLK_DIV_1 0
#define SI5351_OUTPUT_CLK_DIV_2 1
#define SI5351_OUTPUT_CLK_DIV_4 2
#define SI5351_OUTPUT_CLK_DIV_8 3
#define SI5351_OUTPUT_CLK_DIV_16 4
#define SI5351_OUTPUT_CLK_DIV_32 5
#define SI5351_OUTPUT_CLK_DIV_64 6
#define SI5351_OUTPUT_CLK_DIV_128 7
#define SI5351_OUTPUT_CLK_DIVBY4 (3<<2)
#define SI5351_SSC_PARAM0 149
#define SI5351_SSC_PARAM1 150
#define SI5351_SSC_PARAM2 151
#define SI5351_SSC_PARAM3 152
#define SI5351_SSC_PARAM4 153
#define SI5351_SSC_PARAM5 154
#define SI5351_SSC_PARAM6 155
#define SI5351_SSC_PARAM7 156
#define SI5351_SSC_PARAM8 157
#define SI5351_SSC_PARAM9 158
#define SI5351_SSC_PARAM10 159
#define SI5351_SSC_PARAM11 160
#define SI5351_SSC_PARAM12 161
#define SI5351_VXCO_PARAMETERS_LOW 162
#define SI5351_VXCO_PARAMETERS_MID 163
#define SI5351_VXCO_PARAMETERS_HIGH 164
#define SI5351_CLK0_PHASE_OFFSET 165
#define SI5351_CLK1_PHASE_OFFSET 166
#define SI5351_CLK2_PHASE_OFFSET 167
#define SI5351_CLK3_PHASE_OFFSET 168
#define SI5351_CLK4_PHASE_OFFSET 169
#define SI5351_CLK5_PHASE_OFFSET 170
#define SI5351_PLL_RESET 177
#define SI5351_PLL_RESET_B (1<<7)
#define SI5351_PLL_RESET_A (1<<5)
#define SI5351_CRYSTAL_LOAD 183
#define SI5351_CRYSTAL_LOAD_MASK (3<<6)
#define SI5351_CRYSTAL_LOAD_0PF (0<<6)
#define SI5351_CRYSTAL_LOAD_6PF (1<<6)
#define SI5351_CRYSTAL_LOAD_8PF (2<<6)
#define SI5351_CRYSTAL_LOAD_10PF (3<<6)
#define SI5351_FANOUT_ENABLE 187
#define SI5351_CLKIN_ENABLE (1<<7)
#define SI5351_XTAL_ENABLE (1<<6)
#define SI5351_MULTISYNTH_ENABLE (1<<4)
/* Macro definitions */
//#define RFRAC_DENOM ((1L << 20) - 1)
#define RFRAC_DENOM 1000000ULL
/*
* Based on former asm-ppc/div64.h and asm-m68knommu/div64.h
*
* The semantics of do_div() are:
*
* uint32_t do_div(uint64_t *n, uint32_t base)
* {
* uint32_t remainder = *n % base;
* *n = *n / base;
* return remainder;
* }
*
* NOTE: macro parameter n is evaluated multiple times,
* beware of side effects!
*/
# define do_div(n, base) ({ \
uint64_t __base = (base); \
uint64_t __rem; \
__rem = ((uint64_t)(n)) % __base; \
(n) = ((uint64_t)(n)) / __base; \
__rem; \
})
/* Enum definitions */
/*
* enum si5351_variant - SiLabs Si5351 chip variant
* @SI5351_VARIANT_A: Si5351A (8 output clocks, XTAL input)
* @SI5351_VARIANT_A3: Si5351A MSOP10 (3 output clocks, XTAL input)
* @SI5351_VARIANT_B: Si5351B (8 output clocks, XTAL/VXCO input)
* @SI5351_VARIANT_C: Si5351C (8 output clocks, XTAL/CLKIN input)
*/
/*
enum si5351_variant {
SI5351_VARIANT_A = 1,
SI5351_VARIANT_A3 = 2,
SI5351_VARIANT_B = 3,
SI5351_VARIANT_C = 4,
};
*/
enum si5351_clock {
SI5351_CLK0, SI5351_CLK1, SI5351_CLK2, SI5351_CLK3,
SI5351_CLK4, SI5351_CLK5, SI5351_CLK6, SI5351_CLK7
};
enum si5351_pll {
SI5351_PLLA, SI5351_PLLB
};
enum si5351_drive {
SI5351_DRIVE_2MA, SI5351_DRIVE_4MA, SI5351_DRIVE_6MA, SI5351_DRIVE_8MA
};
enum si5351_clock_source {
SI5351_CLK_SRC_XTAL, SI5351_CLK_SRC_CLKIN, SI5351_CLK_SRC_MS0, SI5351_CLK_SRC_MS
};
enum si5351_clock_disable {
SI5351_CLK_DISABLE_LOW, SI5351_CLK_DISABLE_HIGH, SI5351_CLK_DISABLE_HI_Z, SI5351_CLK_DISABLE_NEVER
};
enum si5351_clock_fanout {
SI5351_FANOUT_CLKIN, SI5351_FANOUT_XO, SI5351_FANOUT_MS
};
enum si5351_pll_input {
SI5351_PLL_INPUT_XO, SI5351_PLL_INPUT_CLKIN
};
/* Struct definitions */
struct Si5351RegSet {
uint32_t p1;
uint32_t p2;
uint32_t p3;
};
struct Si5351Status {
uint8_t SYS_INIT;
uint8_t LOL_B;
uint8_t LOL_A;
uint8_t LOS;
uint8_t REVID;
};
struct Si5351IntStatus {
uint8_t SYS_INIT_STKY;
uint8_t LOL_B_STKY;
uint8_t LOL_A_STKY;
uint8_t LOS_STKY;
};
class Si5351 {
public:
Si5351(i2c_port *port, uint8_t i2c_addr = SI5351_BUS_BASE_ADDR);
bool init(uint8_t, uint32_t, int32_t);
void reset(void);
uint8_t set_freq(uint64_t, enum si5351_clock);
uint8_t set_freq_manual(uint64_t, uint64_t, enum si5351_clock);
void set_pll(uint64_t, enum si5351_pll);
void set_ms(enum si5351_clock, struct Si5351RegSet, uint8_t, uint8_t, uint8_t);
void output_enable(enum si5351_clock, uint8_t);
void drive_strength(enum si5351_clock, enum si5351_drive);
void update_status(void);
void set_correction(int32_t, enum si5351_pll_input);
void set_phase(enum si5351_clock, uint8_t);
int32_t get_correction(enum si5351_pll_input);
void pll_reset(enum si5351_pll);
void set_ms_source(enum si5351_clock, enum si5351_pll);
void set_int(enum si5351_clock, uint8_t);
void set_clock_pwr(enum si5351_clock, uint8_t);
void set_clock_invert(enum si5351_clock, uint8_t);
void set_clock_source(enum si5351_clock, enum si5351_clock_source);
void set_clock_disable(enum si5351_clock, enum si5351_clock_disable);
void set_clock_fanout(enum si5351_clock_fanout, uint8_t);
void set_pll_input(enum si5351_pll, enum si5351_pll_input);
void set_vcxo(uint64_t, uint8_t);
void set_ref_freq(uint32_t, enum si5351_pll_input);
uint8_t si5351_write_bulk(uint8_t, uint8_t, uint8_t *);
uint8_t si5351_write(uint8_t, uint8_t);
uint8_t si5351_read(uint8_t);
struct Si5351Status dev_status = {.SYS_INIT = 0, .LOL_B = 0, .LOL_A = 0,
.LOS = 0, .REVID = 0};
struct Si5351IntStatus dev_int_status = {.SYS_INIT_STKY = 0, .LOL_B_STKY = 0,
.LOL_A_STKY = 0, .LOS_STKY = 0};
enum si5351_pll pll_assignment[8];
uint64_t clk_freq[8];
uint64_t plla_freq;
uint64_t pllb_freq;
enum si5351_pll_input plla_ref_osc;
enum si5351_pll_input pllb_ref_osc;
uint32_t xtal_freq[2];
private:
uint64_t pll_calc(enum si5351_pll, uint64_t, struct Si5351RegSet *, int32_t, uint8_t);
uint64_t multisynth_calc(uint64_t, uint64_t, struct Si5351RegSet *);
uint64_t multisynth67_calc(uint64_t, uint64_t, struct Si5351RegSet *);
void update_sys_status(struct Si5351Status *);
void update_int_status(struct Si5351IntStatus *);
void ms_div(enum si5351_clock, uint8_t, uint8_t);
uint8_t select_r_div(uint64_t *);
uint8_t select_r_div_ms67(uint64_t *);
int32_t ref_correction[2];
uint8_t clkin_div;
i2c_port *port;
uint8_t i2c_bus_addr;
bool clk_first_set[8];
};
#endif /* SI5351_H_ */

Wyświetl plik

@ -0,0 +1,301 @@
#include <string.h>
#include "hal/system.h"
#include "hal/usart_gps.h"
#include "hal/delay.h"
#include "ubxg6010.h"
gps_data current_gps_data;
volatile bool ack_received = false;
volatile bool nack_received = false;
static uBloxChecksum
ubxg6010_calculate_checksum(const uint8_t msgClass, const uint8_t msgId, const uint8_t *message, uint16_t size)
{
uBloxChecksum ck = {0, 0};
uint8_t i;
ck.ck_a += msgClass;
ck.ck_b += ck.ck_a;
ck.ck_a += msgId;
ck.ck_b += ck.ck_a;
ck.ck_a += size & 0xff;
ck.ck_b += ck.ck_a;
ck.ck_a += size >> 8;
ck.ck_b += ck.ck_a;
for (i = 0; i < size; i++) {
ck.ck_a += message[i];
ck.ck_b += ck.ck_a;
}
return ck;
}
static bool ubxg6010_wait_for_ack()
{
ack_received = false;
nack_received = false;
uint8_t timeout = 200;
while (!ack_received && !nack_received) {
delay_ms(1);
if (!timeout--) {
break;
}
}
return ack_received;
}
void ubxg6010_send_command(uint8_t msgClass, uint8_t msgId, uint8_t *payload, uint16_t payloadSize)
{
uBloxChecksum chksum = ubxg6010_calculate_checksum(msgClass, msgId, payload, payloadSize);
usart_gps_send_byte(0xB5);
usart_gps_send_byte(0x62);
usart_gps_send_byte(msgClass);
usart_gps_send_byte(msgId);
usart_gps_send_byte((uint8_t) (payloadSize & 0xFFU));
usart_gps_send_byte((uint8_t) (payloadSize >> 8U));
uint16_t i;
for (i = 0; i < payloadSize; ++i) {
usart_gps_send_byte(payload[i]);
}
usart_gps_send_byte(chksum.ck_a);
usart_gps_send_byte(chksum.ck_b);
}
void ubxg6010_send_packet(uBloxPacket *packet)
{
ubxg6010_send_command(packet->header.messageClass, packet->header.messageId, (uint8_t *) &packet->data,
packet->header.payloadSize);
}
void ubxg6010_get_current_gps_data(gps_data *data)
{
system_disable_irq();
memcpy(data, &current_gps_data, sizeof(gps_data));
system_enable_irq();
}
void ubxg6010_init()
{
usart_gps_init(38400, true);
delay_ms(10);
uBloxPacket msgcfgrst = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x04,
.payloadSize=sizeof(uBloxCFGRSTPayload)
},
.data.cfgrst = {
.navBbrMask=0xffff,
.resetMode=1,
.reserved1=0
},
};
ubxg6010_send_packet(&msgcfgrst);
delay_ms(800);
usart_gps_init(9600, true);
delay_ms(10);
ubxg6010_send_packet(&msgcfgrst);
delay_ms(800);
uBloxPacket msgcgprt = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x00,
.payloadSize=sizeof(uBloxCFGPRTPayload)
},
.data.cfgprt = {
.portID=1,
.reserved1=0,
.txReady=0,
.mode=0b00100011000000,
.baudRate=38400,
.inProtoMask=1,
.outProtoMask=1,
.flags=0,
.reserved2={0, 0}
},
};
ubxg6010_send_packet(&msgcgprt);
usart_gps_init(38400, true);
delay_ms(10);
uBloxPacket msgcfgrxm = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x11,
.payloadSize=sizeof(uBloxCFGRXMPayload)
},
.data.cfgrxm = {
.reserved1=8,
.lpMode=4
}
};
do {
ubxg6010_send_packet(&msgcfgrxm);
} while (!ubxg6010_wait_for_ack());
uBloxPacket msgcfgmsg = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x01,
.payloadSize=sizeof(uBloxCFGMSGPayload)
},
.data.cfgmsg = {
.msgClass=0x01,
.msgID=0x02,
.rate=1
}
};
do {
ubxg6010_send_packet(&msgcfgmsg);
} while (!ubxg6010_wait_for_ack());
msgcfgmsg.data.cfgmsg.msgID = 0x6;
do {
ubxg6010_send_packet(&msgcfgmsg);
} while (!ubxg6010_wait_for_ack());
msgcfgmsg.data.cfgmsg.msgID = 0x21;
do {
ubxg6010_send_packet(&msgcfgmsg);
} while (!ubxg6010_wait_for_ack());
uBloxPacket msgcfgnav5 = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x24,
.payloadSize=sizeof(uBloxCFGNAV5Payload)
},
.data.cfgnav5={
.mask=0b00000001111111111,
.dynModel=7,
.fixMode=2,
.fixedAlt=0,
.fixedAltVar=10000,
.minElev=5,
.drLimit=0,
.pDop=25,
.tDop=25,
.pAcc=100,
.tAcc=300,
.staticHoldThresh=0,
.dgpsTimeOut=2,
.reserved2=0,
.reserved3=0,
.reserved4=0
},
};
do {
ubxg6010_send_packet(&msgcfgnav5);
} while (!ubxg6010_wait_for_ack());
}
#include "log.h"
static void ubxg6010_handle_packet(uBloxPacket *pkt)
{
uBloxChecksum cksum = ubxg6010_calculate_checksum(pkt->header.messageClass, pkt->header.messageId,
(const uint8_t *) &pkt->data, pkt->header.payloadSize);
uBloxChecksum *checksum = (uBloxChecksum *) (((uint8_t *) &pkt->data) + pkt->header.payloadSize);
if (cksum.ck_a != checksum->ck_a || cksum.ck_b != checksum->ck_b) {
current_gps_data.bad_packets += 1;
return;
}
if (pkt->header.messageClass == 0x01 && pkt->header.messageId == 0x07) {
log_info("class: %02X, id %02X\n", pkt->header.messageClass, pkt->header.messageId);
current_gps_data.ok_packets += 1;
current_gps_data.fix = pkt->data.navpvt.fixType;
current_gps_data.lat_raw = pkt->data.navpvt.lat;
current_gps_data.lon_raw = pkt->data.navpvt.lon;
current_gps_data.alt_raw = pkt->data.navpvt.hMSL;
current_gps_data.hours = pkt->data.navpvt.hour;
current_gps_data.minutes = pkt->data.navpvt.min;
current_gps_data.seconds = pkt->data.navpvt.sec;
current_gps_data.sats_raw = pkt->data.navpvt.numSV;
current_gps_data.speed_raw = pkt->data.navpvt.gSpeed;
} else if (pkt->header.messageClass == 0x01 && pkt->header.messageId == 0x02) {
log_info("class: %02X, id %02X\n", pkt->header.messageClass, pkt->header.messageId);
current_gps_data.ok_packets += 1;
current_gps_data.lat_raw = pkt->data.navposllh.lat;
current_gps_data.lon_raw = pkt->data.navposllh.lon;
current_gps_data.alt_raw = pkt->data.navposllh.hMSL;
} else if (pkt->header.messageClass == 0x01 && pkt->header.messageId == 0x06) {
log_info("class: %02X, id %02X\n", pkt->header.messageClass, pkt->header.messageId);
log_info("flags: %02X\n", pkt->data.navsol.flags);
log_info("SV: %d\n", pkt->data.navsol.numSV);
current_gps_data.fix = pkt->data.navsol.gpsFix;
current_gps_data.sats_raw = pkt->data.navsol.numSV;
} else if (pkt->header.messageClass == 0x01 && pkt->header.messageId == 0x21) {
log_info("class: %02X, id %02X\n", pkt->header.messageClass, pkt->header.messageId);
current_gps_data.hours = pkt->data.navtimeutc.hour;
current_gps_data.minutes = pkt->data.navtimeutc.min;
current_gps_data.seconds = pkt->data.navtimeutc.sec;
} else if (pkt->header.messageClass == 0x05 && pkt->header.messageId == 0x01) {
ack_received = true;
} else if (pkt->header.messageClass == 0x05 && pkt->header.messageId == 0x00) {
nack_received = true;
}
}
void ubxg6010_handle_incoming_byte(uint8_t data)
{
static uint8_t sync = 0;
static uint8_t buffer_pos = 0;
static uint8_t incoming_packet_buffer[sizeof(uBloxPacket) + sizeof(uBloxChecksum)];
static uBloxPacket *incoming_packet = (uBloxPacket *) incoming_packet_buffer;
if (!sync) {
if (!buffer_pos && data == 0xB5) {
buffer_pos = 1;
incoming_packet->header.sc1 = data;
} else if (buffer_pos == 1 && data == 0x62) {
sync = 1;
buffer_pos = 2;
incoming_packet->header.sc2 = data;
} else {
buffer_pos = 0;
}
} else {
((uint8_t *) incoming_packet)[buffer_pos] = data;
if ((buffer_pos >= sizeof(uBloxHeader) - 1) &&
(buffer_pos - 1 == (incoming_packet->header.payloadSize + sizeof(uBloxHeader) + sizeof(uBloxChecksum)))) {
ubxg6010_handle_packet((uBloxPacket *) incoming_packet);
buffer_pos = 0;
sync = 0;
} else {
buffer_pos++;
if (buffer_pos >= sizeof(uBloxPacket) + sizeof(uBloxChecksum)) {
buffer_pos = 0;
sync = 0;
}
}
}
}

Wyświetl plik

@ -0,0 +1,192 @@
#ifndef __UBXG6010_H
#define __UBXG6010_H
#include <stdint.h>
#include "src/gps.h"
typedef struct __attribute__((packed)) {
uint8_t sc1; // 0xB5
uint8_t sc2; // 0x62
uint8_t messageClass;
uint8_t messageId;
uint16_t payloadSize;
} uBloxHeader;
typedef struct {
uint8_t ck_a;
uint8_t ck_b;
} uBloxChecksum;
typedef struct {
uint32_t iTOW; //GPS time of week of the navigation epoch. [- ms]
uint16_t year; //Year (UTC) [- y]
uint8_t month; //Month, range 1..12 (UTC) [- month]
uint8_t day; //Day of month, range 1..31 (UTC) [- d]
uint8_t hour; //Hour of day, range 0..23 (UTC) [- h]
uint8_t min; //Minute of hour, range 0..59 (UTC) [- min]
uint8_t sec; //Seconds of minute, range 0..60 (UTC) [- s]
uint8_t valid; //Validity flags (see graphic below) [- -]
uint32_t tAcc; //Time accuracy estimate (UTC) [- ns]
int32_t nano; //Fraction of second, range -1e9 .. 1e9 (UTC) [- ns]
uint8_t fixType; //GNSSfix Type: [- -]
uint8_t flags; //Fix status flags (see graphic below) [- -]
uint8_t flags2; //Additional flags (see graphic below) [- -]
uint8_t numSV; //Number of satellites used in Nav Solution [- -]
int32_t lon; //Longitude [1e-7 deg]
int32_t lat; //Latitude [1e-7 deg]
int32_t height; //Height above ellipsoid [- mm]
int32_t hMSL; //Height above mean sea level [- mm]
uint32_t hAcc; //Horizontal accuracy estimate [- mm]
uint32_t vAcc; //Vertical accuracy estimate [- mm]
int32_t velN; //NED north velocity [- mm/s]
int32_t velE; //NED east velocity [- mm/s]
int32_t velD; //NED down velocity [- mm/s]
int32_t gSpeed; //Ground Speed (2-D) [- mm/s]
int32_t headMot; //Heading of motion (2-D) [1e-5 deg]
uint32_t sAcc; //Speed accuracy estimate [- mm/s]
uint32_t headAcc; //Heading accuracy estimate (both motion and vehicle) [1e-5 deg]
uint16_t pDOP; //Position DOP [0.01 -]
uint8_t reserved1[6]; //Reserved [- -]
int32_t headVeh; //Heading of vehicle (2-D) [1e-5 deg]
uint8_t reserved2[4]; //Reserved [- -]
} uBloxNAVPVTPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
int32_t lon; //Longitude [1e-7 deg]
int32_t lat; //Latitude [1e-7 deg]
int32_t height; //Height above Ellipsoid [- mm]
int32_t hMSL; //Height above mean sea level [- mm]
uint32_t hAcc; //Horizontal Accuracy Estimate [- mm]
uint32_t vAcc; //Vertical Accuracy Estimate [- mm]
} uBloxNAVPOSLLHPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
int32_t fTOW; //Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 [- ns]
int16_t week; //GPS week (GPS time) [- -]
uint8_t gpsFix; //GPSfix Type, range 0..5 0x00 = No Fix 0x01 = Dead Reckoning only 0x02 = 2D-Fix 0x03 = 3D-Fix 0x04 = GPS + dead reckoning combined 0x05 = Time only fix 0x06..0xff: reserved [- -]
uint8_t flags; //Fix Status Flags (see graphic below) [- -]
int32_t ecefX; //ECEF X coordinate [- cm]
int32_t ecefY; //ECEF Y coordinate [- cm]
int32_t ecefZ; //ECEF Z coordinate [- cm]
uint32_t pAcc; //3D Position Accuracy Estimate [- cm]
int32_t ecefVX; //ECEF X velocity [- cm/s]
int32_t ecefVY; //ECEF Y velocity [- cm/s]
int32_t ecefVZ; //ECEF Z velocity [- cm/s]
uint32_t sAcc; //Speed Accuracy Estimate [- cm/s]
uint16_t pDOP; //Position DOP [0.01 -]
uint8_t reserved1; //Reserved [- -]
uint8_t numSV; //Number of SVs used in Nav Solution [- -]
uint32_t reserved2; //Reserved [- -]
} uBloxNAVSOLPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
uint32_t tAcc; //Time Accuracy Estimate [- ns]
int32_t nano; //Nanoseconds of second, range -1e9 .. 1e9 (UTC) [- ns]
uint16_t year; //Year, range 1999..2099 (UTC) [- y]
uint8_t month; //Month, range 1..12 (UTC) [- month]
uint8_t day; //Day of Month, range 1..31 (UTC) [- d]
uint8_t hour; //Hour of Day, range 0..23 (UTC) [- h]
uint8_t min; //Minute of Hour, range 0..59 (UTC) [- min]
uint8_t sec; //Seconds of Minute, range 0..59 (UTC) [- s]
uint8_t valid; //Validity Flags (see graphic below) [- -]
} uBloxNAVTIMEUTCPayload;
typedef struct {
uint8_t portID; //Port Identifier Number (see Serial [- -]
uint8_t reserved1; //Reserved [- -]
uint16_t txReady; //TX ready PIN configuration [- -]
uint32_t mode; //A bit mask describing the UART mode [- -]
uint32_t baudRate; //Baud rate in bits/second [- Bits/s]
uint16_t inProtoMask; //A mask describing which input protocols are active. [- -]
uint16_t outProtoMask; //A mask describing which output protocols are active. [- -]
uint16_t flags; //Flags bit mask (see graphic below) [- -]
uint8_t reserved2[2]; //Reserved [- -]
} uBloxCFGPRTPayload;
typedef struct {
uint8_t clsID; //Message Class [- -]
uint8_t msgID; //Message Identifier [- -]
uint8_t ck_a;
uint8_t ck_b;
} uBloxACKACKayload;
typedef struct {
uint8_t msgClass; //Message Class [- -]
uint8_t msgID; //Message Identifier [- -]
uint8_t rate; //Send rate on current Port [- -]
} uBloxCFGMSGPayload;
typedef struct {
uint16_t navBbrMask; //BBR Sections to clear. The following Special Sets apply:
// 0x0000 Hotstart
// 0x0001 Warmstart
// 0xFFFF Coldstart [- -]
uint8_t resetMode; //Reset Type
// - 0x00 - Hardware reset (Watchdog) immediately
// - 0x01 - Controlled Software reset
// - 0x02 - Controlled Software reset (GPS only)
// - 0x04 - Hardware reset (Watchdog) after shutdown (>=FW6.0)
// - 0x08 - Controlled GPS stop
// - 0x09 - Controlled GPS start [- -]
// - 0x09 - Controlled GPS start [- -]
uint8_t reserved1; //Reserved [- -]
} uBloxCFGRSTPayload;
typedef struct {
uint16_t mask; //Parameters Bitmask. Only the masked parameters will be applied. (see graphic below) [- -]
uint8_t dynModel; //Dynamic Platform model: - 0 􀀀 Portable - 2 􀀀 Stationary - 3 􀀀 Pedestrian - 4 􀀀 Automotive - 5 􀀀 Sea - 6 􀀀 Airborne with <1g Acceleration - 7 􀀀 Airborne with <2g Acceleration - 8 􀀀 Airborne with <4g Acceleration [- -]
uint8_t fixMode; //Position Fixing Mode. - 1: 2D only - 2: 3D only - 3: Auto 2D/3D [- -]
int32_t fixedAlt; //Fixed altitude (mean sea level) for 2D fix mode. [0.01 m]
uint32_t fixedAltVar; //Fixed altitude variance for 2D mode. [0.0001 m^2]
int8_t minElev; //Minimum Elevation for a GNSS satellite to be used in NAV [- deg]
uint8_t drLimit; //Maximum time to perform dead reckoning (linear extrapolation) in case of GPS signal loss [- s]
uint16_t pDop; //Position DOP Mask to use [0.1 -]
uint16_t tDop; //Time DOP Mask to use [0.1 -]
uint16_t pAcc; //Position Accuracy Mask [- m]
uint16_t tAcc; //Time Accuracy Mask [- m]
uint8_t staticHoldThresh; //Static hold threshold [- cm/s]
uint8_t dgpsTimeOut; //DGPS timeout, firmware 7 and newer only [- s]
uint32_t reserved2; //Always set to zero [- -]
uint32_t reserved3; //Always set to zero [- -]
uint32_t reserved4; //Always set to zero [- -]
} uBloxCFGNAV5Payload;
typedef struct {
uint8_t reserved1; //Always set to 8 [- -]
uint8_t lpMode; //Low Power Mode 0: Max. performance mode 1: Power Save Mode (>= FW 6.00 only) 2-3: reserved 4: Eco mode 5-255: reserved [- -]
} uBloxCFGRXMPayload;
typedef union {
uBloxNAVPVTPayload navpvt;
uBloxCFGPRTPayload cfgprt;
uBloxCFGMSGPayload cfgmsg;
uBloxCFGNAV5Payload cfgnav5;
uBloxNAVPOSLLHPayload navposllh;
uBloxNAVSOLPayload navsol;
uBloxNAVTIMEUTCPayload navtimeutc;
uBloxACKACKayload ackack;
uBloxCFGRSTPayload cfgrst;
uBloxCFGRXMPayload cfgrxm;
} ubloxPacketData;
typedef struct __attribute__((packed)) {
uBloxHeader header;
ubloxPacketData data;
} uBloxPacket;
void ubxg6010_init();
void ubxg6010_get_current_gps_data(gps_data *data);
void ubxg6010_handle_incoming_byte(uint8_t data);
#endif

37
src/f_rtty.c 100644
Wyświetl plik

@ -0,0 +1,37 @@
#include "f_rtty.h"
uint8_t start_bits;
rttyStates send_rtty(char *buffer) {
static uint8_t nr_bit = 0;
nr_bit++;
if (start_bits){
start_bits--;
return rttyOne;
}
if (nr_bit == 1) {
return rttyZero;
}
if (nr_bit > 1 && nr_bit < (RTTY_7BIT ? 9 : 10)) {
if ((*(buffer) >> (nr_bit - 2)) & 0x01) {
return rttyOne;
} else {
return rttyZero;
}
}
#ifdef RTTY_7BIT
nr_bit++;
#endif
if (nr_bit == 10) {
return rttyOne;
}
#ifdef RTTY_USE_2_STOP_BITS
if (nr_bit == 11) {
return rttyOne;
}
#endif
nr_bit = 0;
return rttyEnd;
}

12
src/f_rtty.h 100644
Wyświetl plik

@ -0,0 +1,12 @@
#include <stdint.h>
#include "config.h"
typedef enum {
rttyZero = 0,
rttyOne = 1,
rttyEnd = 2
} rttyStates;
static const uint8_t RTTY_PRE_START_BITS = 40;
rttyStates send_rtty(char *);
extern uint8_t start_bits;

20
src/gps.h 100644
Wyświetl plik

@ -0,0 +1,20 @@
#ifndef __GPS_H
#define __GPS_H
#include <stdint.h>
typedef struct _gps_data {
int32_t lat_raw;
int32_t lon_raw;
int32_t alt_raw;
int32_t speed_raw;
uint8_t sats_raw;
uint8_t seconds;
uint8_t minutes;
uint8_t hours;
uint8_t fix;
uint16_t ok_packets;
uint16_t bad_packets;
} gps_data;
#endif

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,616 @@
/**************************************************************************//**
* @file core_cmFunc.h
* @brief CMSIS Cortex-M Core Function Access Header File
* @version V3.01
* @date 06. March 2012
*
* @note
* Copyright (C) 2009-2012 ARM Limited. All rights reserved.
*
* @par
* ARM Limited (ARM) is supplying this software for use with Cortex-M
* processor based microcontrollers. This file can be freely distributed
* within development tools that are supporting such ARM based processors.
*
* @par
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
*
******************************************************************************/
#ifndef __CORE_CMFUNC_H
#define __CORE_CMFUNC_H
/* ########################### Core Function Access ########################### */
/** \ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
@{
*/
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
/* ARM armcc specific functions */
#if (__ARMCC_VERSION < 400677)
#error "Please use ARM Compiler Toolchain V4.0.677 or later!"
#endif
/* intrinsic void __enable_irq(); */
/* intrinsic void __disable_irq(); */
/** \brief Get Control Register
This function returns the content of the Control Register.
\return Control Register value
*/
__STATIC_INLINE uint32_t __get_CONTROL(void)
{
register uint32_t __regControl __ASM("control");
return(__regControl);
}
/** \brief Set Control Register
This function writes the given value to the Control Register.
\param [in] control Control Register value to set
*/
__STATIC_INLINE void __set_CONTROL(uint32_t control)
{
register uint32_t __regControl __ASM("control");
__regControl = control;
}
/** \brief Get IPSR Register
This function returns the content of the IPSR Register.
\return IPSR Register value
*/
__STATIC_INLINE uint32_t __get_IPSR(void)
{
register uint32_t __regIPSR __ASM("ipsr");
return(__regIPSR);
}
/** \brief Get APSR Register
This function returns the content of the APSR Register.
\return APSR Register value
*/
__STATIC_INLINE uint32_t __get_APSR(void)
{
register uint32_t __regAPSR __ASM("apsr");
return(__regAPSR);
}
/** \brief Get xPSR Register
This function returns the content of the xPSR Register.
\return xPSR Register value
*/
__STATIC_INLINE uint32_t __get_xPSR(void)
{
register uint32_t __regXPSR __ASM("xpsr");
return(__regXPSR);
}
/** \brief Get Process Stack Pointer
This function returns the current value of the Process Stack Pointer (PSP).
\return PSP Register value
*/
__STATIC_INLINE uint32_t __get_PSP(void)
{
register uint32_t __regProcessStackPointer __ASM("psp");
return(__regProcessStackPointer);
}
/** \brief Set Process Stack Pointer
This function assigns the given value to the Process Stack Pointer (PSP).
\param [in] topOfProcStack Process Stack Pointer value to set
*/
__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
{
register uint32_t __regProcessStackPointer __ASM("psp");
__regProcessStackPointer = topOfProcStack;
}
/** \brief Get Main Stack Pointer
This function returns the current value of the Main Stack Pointer (MSP).
\return MSP Register value
*/
__STATIC_INLINE uint32_t __get_MSP(void)
{
register uint32_t __regMainStackPointer __ASM("msp");
return(__regMainStackPointer);
}
/** \brief Set Main Stack Pointer
This function assigns the given value to the Main Stack Pointer (MSP).
\param [in] topOfMainStack Main Stack Pointer value to set
*/
__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
{
register uint32_t __regMainStackPointer __ASM("msp");
__regMainStackPointer = topOfMainStack;
}
/** \brief Get Priority Mask
This function returns the current state of the priority mask bit from the Priority Mask Register.
\return Priority Mask value
*/
__STATIC_INLINE uint32_t __get_PRIMASK(void)
{
register uint32_t __regPriMask __ASM("primask");
return(__regPriMask);
}
/** \brief Set Priority Mask
This function assigns the given value to the Priority Mask Register.
\param [in] priMask Priority Mask
*/
__STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
{
register uint32_t __regPriMask __ASM("primask");
__regPriMask = (priMask);
}
#if (__CORTEX_M >= 0x03)
/** \brief Enable FIQ
This function enables FIQ interrupts by clearing the F-bit in the CPSR.
Can only be executed in Privileged modes.
*/
#define __enable_fault_irq __enable_fiq
/** \brief Disable FIQ
This function disables FIQ interrupts by setting the F-bit in the CPSR.
Can only be executed in Privileged modes.
*/
#define __disable_fault_irq __disable_fiq
/** \brief Get Base Priority
This function returns the current value of the Base Priority register.
\return Base Priority register value
*/
__STATIC_INLINE uint32_t __get_BASEPRI(void)
{
register uint32_t __regBasePri __ASM("basepri");
return(__regBasePri);
}
/** \brief Set Base Priority
This function assigns the given value to the Base Priority register.
\param [in] basePri Base Priority value to set
*/
__STATIC_INLINE void __set_BASEPRI(uint32_t basePri)
{
register uint32_t __regBasePri __ASM("basepri");
__regBasePri = (basePri & 0xff);
}
/** \brief Get Fault Mask
This function returns the current value of the Fault Mask register.
\return Fault Mask register value
*/
__STATIC_INLINE uint32_t __get_FAULTMASK(void)
{
register uint32_t __regFaultMask __ASM("faultmask");
return(__regFaultMask);
}
/** \brief Set Fault Mask
This function assigns the given value to the Fault Mask register.
\param [in] faultMask Fault Mask value to set
*/
__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
{
register uint32_t __regFaultMask __ASM("faultmask");
__regFaultMask = (faultMask & (uint32_t)1);
}
#endif /* (__CORTEX_M >= 0x03) */
#if (__CORTEX_M == 0x04)
/** \brief Get FPSCR
This function returns the current value of the Floating Point Status/Control register.
\return Floating Point Status/Control register value
*/
__STATIC_INLINE uint32_t __get_FPSCR(void)
{
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
register uint32_t __regfpscr __ASM("fpscr");
return(__regfpscr);
#else
return(0);
#endif
}
/** \brief Set FPSCR
This function assigns the given value to the Floating Point Status/Control register.
\param [in] fpscr Floating Point Status/Control value to set
*/
__STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
{
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
register uint32_t __regfpscr __ASM("fpscr");
__regfpscr = (fpscr);
#endif
}
#endif /* (__CORTEX_M == 0x04) */
#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
/* IAR iccarm specific functions */
#include <cmsis_iar.h>
#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
/* TI CCS specific functions */
#include <cmsis_ccs.h>
#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
/* GNU gcc specific functions */
/** \brief Enable IRQ Interrupts
This function enables IRQ interrupts by clearing the I-bit in the CPSR.
Can only be executed in Privileged modes.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void)
{
__ASM volatile ("cpsie i");
}
/** \brief Disable IRQ Interrupts
This function disables IRQ interrupts by setting the I-bit in the CPSR.
Can only be executed in Privileged modes.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_irq(void)
{
__ASM volatile ("cpsid i");
}
/** \brief Get Control Register
This function returns the content of the Control Register.
\return Control Register value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_CONTROL(void)
{
uint32_t result;
__ASM volatile ("MRS %0, control" : "=r" (result) );
return(result);
}
/** \brief Set Control Register
This function writes the given value to the Control Register.
\param [in] control Control Register value to set
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_CONTROL(uint32_t control)
{
__ASM volatile ("MSR control, %0" : : "r" (control) );
}
/** \brief Get IPSR Register
This function returns the content of the IPSR Register.
\return IPSR Register value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_IPSR(void)
{
uint32_t result;
__ASM volatile ("MRS %0, ipsr" : "=r" (result) );
return(result);
}
/** \brief Get APSR Register
This function returns the content of the APSR Register.
\return APSR Register value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_APSR(void)
{
uint32_t result;
__ASM volatile ("MRS %0, apsr" : "=r" (result) );
return(result);
}
/** \brief Get xPSR Register
This function returns the content of the xPSR Register.
\return xPSR Register value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_xPSR(void)
{
uint32_t result;
__ASM volatile ("MRS %0, xpsr" : "=r" (result) );
return(result);
}
/** \brief Get Process Stack Pointer
This function returns the current value of the Process Stack Pointer (PSP).
\return PSP Register value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void)
{
register uint32_t result;
__ASM volatile ("MRS %0, psp\n" : "=r" (result) );
return(result);
}
/** \brief Set Process Stack Pointer
This function assigns the given value to the Process Stack Pointer (PSP).
\param [in] topOfProcStack Process Stack Pointer value to set
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
{
__ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) );
}
/** \brief Get Main Stack Pointer
This function returns the current value of the Main Stack Pointer (MSP).
\return MSP Register value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void)
{
register uint32_t result;
__ASM volatile ("MRS %0, msp\n" : "=r" (result) );
return(result);
}
/** \brief Set Main Stack Pointer
This function assigns the given value to the Main Stack Pointer (MSP).
\param [in] topOfMainStack Main Stack Pointer value to set
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
{
__ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) );
}
/** \brief Get Priority Mask
This function returns the current state of the priority mask bit from the Priority Mask Register.
\return Priority Mask value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PRIMASK(void)
{
uint32_t result;
__ASM volatile ("MRS %0, primask" : "=r" (result) );
return(result);
}
/** \brief Set Priority Mask
This function assigns the given value to the Priority Mask Register.
\param [in] priMask Priority Mask
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
{
__ASM volatile ("MSR primask, %0" : : "r" (priMask) );
}
#if (__CORTEX_M >= 0x03)
/** \brief Enable FIQ
This function enables FIQ interrupts by clearing the F-bit in the CPSR.
Can only be executed in Privileged modes.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void)
{
__ASM volatile ("cpsie f");
}
/** \brief Disable FIQ
This function disables FIQ interrupts by setting the F-bit in the CPSR.
Can only be executed in Privileged modes.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_fault_irq(void)
{
__ASM volatile ("cpsid f");
}
/** \brief Get Base Priority
This function returns the current value of the Base Priority register.
\return Base Priority register value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void)
{
uint32_t result;
__ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
return(result);
}
/** \brief Set Base Priority
This function assigns the given value to the Base Priority register.
\param [in] basePri Base Priority value to set
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t value)
{
__ASM volatile ("MSR basepri, %0" : : "r" (value) );
}
/** \brief Get Fault Mask
This function returns the current value of the Fault Mask register.
\return Fault Mask register value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FAULTMASK(void)
{
uint32_t result;
__ASM volatile ("MRS %0, faultmask" : "=r" (result) );
return(result);
}
/** \brief Set Fault Mask
This function assigns the given value to the Fault Mask register.
\param [in] faultMask Fault Mask value to set
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
{
__ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) );
}
#endif /* (__CORTEX_M >= 0x03) */
#if (__CORTEX_M == 0x04)
/** \brief Get FPSCR
This function returns the current value of the Floating Point Status/Control register.
\return Floating Point Status/Control register value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void)
{
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
uint32_t result;
__ASM volatile ("VMRS %0, fpscr" : "=r" (result) );
return(result);
#else
return(0);
#endif
}
/** \brief Set FPSCR
This function assigns the given value to the Floating Point Status/Control register.
\param [in] fpscr Floating Point Status/Control value to set
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
{
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
__ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) );
#endif
}
#endif /* (__CORTEX_M == 0x04) */
#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
/* TASKING carm specific functions */
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all instrinsics,
* Including the CMSIS ones.
*/
#endif
/*@} end of CMSIS_Core_RegAccFunctions */
#endif /* __CORE_CMFUNC_H */

Wyświetl plik

@ -0,0 +1,618 @@
/**************************************************************************//**
* @file core_cmInstr.h
* @brief CMSIS Cortex-M Core Instruction Access Header File
* @version V3.01
* @date 06. March 2012
*
* @note
* Copyright (C) 2009-2012 ARM Limited. All rights reserved.
*
* @par
* ARM Limited (ARM) is supplying this software for use with Cortex-M
* processor based microcontrollers. This file can be freely distributed
* within development tools that are supporting such ARM based processors.
*
* @par
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
*
******************************************************************************/
#ifndef __CORE_CMINSTR_H
#define __CORE_CMINSTR_H
/* ########################## Core Instruction Access ######################### */
/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
Access to dedicated instructions
@{
*/
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
/* ARM armcc specific functions */
#if (__ARMCC_VERSION < 400677)
#error "Please use ARM Compiler Toolchain V4.0.677 or later!"
#endif
/** \brief No Operation
No Operation does nothing. This instruction can be used for code alignment purposes.
*/
#define __NOP __nop
/** \brief Wait For Interrupt
Wait For Interrupt is a hint instruction that suspends execution
until one of a number of events occurs.
*/
#define __WFI __wfi
/** \brief Wait For Event
Wait For Event is a hint instruction that permits the processor to enter
a low-power state until one of a number of events occurs.
*/
#define __WFE __wfe
/** \brief Send Event
Send Event is a hint instruction. It causes an event to be signaled to the CPU.
*/
#define __SEV __sev
/** \brief Instruction Synchronization Barrier
Instruction Synchronization Barrier flushes the pipeline in the processor,
so that all instructions following the ISB are fetched from cache or
memory, after the instruction has been completed.
*/
#define __ISB() __isb(0xF)
/** \brief Data Synchronization Barrier
This function acts as a special kind of Data Memory Barrier.
It completes when all explicit memory accesses before this instruction complete.
*/
#define __DSB() __dsb(0xF)
/** \brief Data Memory Barrier
This function ensures the apparent order of the explicit memory operations before
and after the instruction, without ensuring their completion.
*/
#define __DMB() __dmb(0xF)
/** \brief Reverse byte order (32 bit)
This function reverses the byte order in integer value.
\param [in] value Value to reverse
\return Reversed value
*/
#define __REV __rev
/** \brief Reverse byte order (16 bit)
This function reverses the byte order in two unsigned short values.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value)
{
rev16 r0, r0
bx lr
}
/** \brief Reverse byte order in signed short value
This function reverses the byte order in a signed short value with sign extension to integer.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value)
{
revsh r0, r0
bx lr
}
/** \brief Rotate Right in unsigned value (32 bit)
This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
\param [in] value Value to rotate
\param [in] value Number of Bits to rotate
\return Rotated value
*/
#define __ROR __ror
#if (__CORTEX_M >= 0x03)
/** \brief Reverse bit order of value
This function reverses the bit order of the given value.
\param [in] value Value to reverse
\return Reversed value
*/
#define __RBIT __rbit
/** \brief LDR Exclusive (8 bit)
This function performs a exclusive LDR command for 8 bit value.
\param [in] ptr Pointer to data
\return value of type uint8_t at (*ptr)
*/
#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr))
/** \brief LDR Exclusive (16 bit)
This function performs a exclusive LDR command for 16 bit values.
\param [in] ptr Pointer to data
\return value of type uint16_t at (*ptr)
*/
#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr))
/** \brief LDR Exclusive (32 bit)
This function performs a exclusive LDR command for 32 bit values.
\param [in] ptr Pointer to data
\return value of type uint32_t at (*ptr)
*/
#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr))
/** \brief STR Exclusive (8 bit)
This function performs a exclusive STR command for 8 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
#define __STREXB(value, ptr) __strex(value, ptr)
/** \brief STR Exclusive (16 bit)
This function performs a exclusive STR command for 16 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
#define __STREXH(value, ptr) __strex(value, ptr)
/** \brief STR Exclusive (32 bit)
This function performs a exclusive STR command for 32 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
#define __STREXW(value, ptr) __strex(value, ptr)
/** \brief Remove the exclusive lock
This function removes the exclusive lock which is created by LDREX.
*/
#define __CLREX __clrex
/** \brief Signed Saturate
This function saturates a signed value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (1..32)
\return Saturated value
*/
#define __SSAT __ssat
/** \brief Unsigned Saturate
This function saturates an unsigned value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (0..31)
\return Saturated value
*/
#define __USAT __usat
/** \brief Count leading zeros
This function counts the number of leading zeros of a data value.
\param [in] value Value to count the leading zeros
\return number of leading zeros in value
*/
#define __CLZ __clz
#endif /* (__CORTEX_M >= 0x03) */
#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
/* IAR iccarm specific functions */
#include <cmsis_iar.h>
#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
/* TI CCS specific functions */
#include <cmsis_ccs.h>
#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
/* GNU gcc specific functions */
/** \brief No Operation
No Operation does nothing. This instruction can be used for code alignment purposes.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __NOP(void)
{
__ASM volatile ("nop");
}
/** \brief Wait For Interrupt
Wait For Interrupt is a hint instruction that suspends execution
until one of a number of events occurs.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFI(void)
{
__ASM volatile ("wfi");
}
/** \brief Wait For Event
Wait For Event is a hint instruction that permits the processor to enter
a low-power state until one of a number of events occurs.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFE(void)
{
__ASM volatile ("wfe");
}
/** \brief Send Event
Send Event is a hint instruction. It causes an event to be signaled to the CPU.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __SEV(void)
{
__ASM volatile ("sev");
}
/** \brief Instruction Synchronization Barrier
Instruction Synchronization Barrier flushes the pipeline in the processor,
so that all instructions following the ISB are fetched from cache or
memory, after the instruction has been completed.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __ISB(void)
{
__ASM volatile ("isb");
}
/** \brief Data Synchronization Barrier
This function acts as a special kind of Data Memory Barrier.
It completes when all explicit memory accesses before this instruction complete.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __DSB(void)
{
__ASM volatile ("dsb");
}
/** \brief Data Memory Barrier
This function ensures the apparent order of the explicit memory operations before
and after the instruction, without ensuring their completion.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void)
{
__ASM volatile ("dmb");
}
/** \brief Reverse byte order (32 bit)
This function reverses the byte order in integer value.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value)
{
uint32_t result;
__ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) );
return(result);
}
/** \brief Reverse byte order (16 bit)
This function reverses the byte order in two unsigned short values.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t value)
{
uint32_t result;
__ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) );
return(result);
}
/** \brief Reverse byte order in signed short value
This function reverses the byte order in a signed short value with sign extension to integer.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value)
{
uint32_t result;
__ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) );
return(result);
}
/** \brief Rotate Right in unsigned value (32 bit)
This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
\param [in] value Value to rotate
\param [in] value Number of Bits to rotate
\return Rotated value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2)
{
__ASM volatile ("ror %0, %0, %1" : "+r" (op1) : "r" (op2) );
return(op1);
}
#if (__CORTEX_M >= 0x03)
/** \brief Reverse bit order of value
This function reverses the bit order of the given value.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t value)
{
uint32_t result;
__ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) );
return(result);
}
/** \brief LDR Exclusive (8 bit)
This function performs a exclusive LDR command for 8 bit value.
\param [in] ptr Pointer to data
\return value of type uint8_t at (*ptr)
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr)
{
uint8_t result;
__ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) );
return(result);
}
/** \brief LDR Exclusive (16 bit)
This function performs a exclusive LDR command for 16 bit values.
\param [in] ptr Pointer to data
\return value of type uint16_t at (*ptr)
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr)
{
uint16_t result;
__ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) );
return(result);
}
/** \brief LDR Exclusive (32 bit)
This function performs a exclusive LDR command for 32 bit values.
\param [in] ptr Pointer to data
\return value of type uint32_t at (*ptr)
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr)
{
uint32_t result;
__ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) );
return(result);
}
/** \brief STR Exclusive (8 bit)
This function performs a exclusive STR command for 8 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr)
{
uint32_t result;
__ASM volatile ("strexb %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) );
return(result);
}
/** \brief STR Exclusive (16 bit)
This function performs a exclusive STR command for 16 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr)
{
uint32_t result;
__ASM volatile ("strexh %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) );
return(result);
}
/** \brief STR Exclusive (32 bit)
This function performs a exclusive STR command for 32 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr)
{
uint32_t result;
__ASM volatile ("strex %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) );
return(result);
}
/** \brief Remove the exclusive lock
This function removes the exclusive lock which is created by LDREX.
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void)
{
__ASM volatile ("clrex");
}
/** \brief Signed Saturate
This function saturates a signed value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (1..32)
\return Saturated value
*/
#define __SSAT(ARG1,ARG2) \
({ \
uint32_t __RES, __ARG1 = (ARG1); \
__ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
__RES; \
})
/** \brief Unsigned Saturate
This function saturates an unsigned value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (0..31)
\return Saturated value
*/
#define __USAT(ARG1,ARG2) \
({ \
uint32_t __RES, __ARG1 = (ARG1); \
__ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
__RES; \
})
/** \brief Count leading zeros
This function counts the number of leading zeros of a data value.
\param [in] value Value to count the leading zeros
\return number of leading zeros in value
*/
__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __CLZ(uint32_t value)
{
uint8_t result;
__ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) );
return(result);
}
#endif /* (__CORTEX_M >= 0x03) */
#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
/* TASKING carm specific functions */
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
#endif
/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
#endif /* __CORE_CMINSTR_H */

Wyświetl plik

@ -0,0 +1,289 @@
/**
******************************************************************************
* @file startup_stm32f10x_md_vl.c
* @author Coocox
* @version V1.0
* @date 3/4/2011
* @brief STM32F10x Medium Density Value Line Devices Startup code.
* This module performs:
* - Set the initial SP
* - Set the vector table entries with the exceptions ISR address
* - Initialize data and bss
* - Setup the microcontroller system.
* - Call the application's entry point.
* After Reset the Cortex-M3 processor is in Thread mode,
* priority is Privileged, and the Stack is set to Main.
*******************************************************************************
*/
/*----------Stack Configuration-----------------------------------------------*/
#define STACK_SIZE 0x00000100 /*!< The Stack size suggest using even number */
__attribute__ ((section(".co_stack")))
unsigned long pulStack[STACK_SIZE];
/*----------Macro definition--------------------------------------------------*/
#define WEAK __attribute__ ((weak))
/*----------Declaration of the default fault handlers-------------------------*/
/* System exception vector handler */
__attribute__ ((used))
void WEAK Reset_Handler(void);
void WEAK NMI_Handler(void);
void WEAK HardFault_Handler(void);
void WEAK MemManage_Handler(void);
void WEAK BusFault_Handler(void);
void WEAK UsageFault_Handler(void);
void WEAK SVC_Handler(void);
void WEAK DebugMon_Handler(void);
void WEAK PendSV_Handler(void);
void WEAK SysTick_Handler(void);
void WEAK WWDG_IRQHandler(void);
void WEAK PVD_IRQHandler(void);
void WEAK TAMPER_IRQHandler(void);
void WEAK RTC_IRQHandler(void);
void WEAK FLASH_IRQHandler(void);
void WEAK RCC_IRQHandler(void);
void WEAK EXTI0_IRQHandler(void);
void WEAK EXTI1_IRQHandler(void);
void WEAK EXTI2_IRQHandler(void);
void WEAK EXTI3_IRQHandler(void);
void WEAK EXTI4_IRQHandler(void);
void WEAK DMA1_Channel1_IRQHandler(void);
void WEAK DMA1_Channel2_IRQHandler(void);
void WEAK DMA1_Channel3_IRQHandler(void);
void WEAK DMA1_Channel4_IRQHandler(void);
void WEAK DMA1_Channel5_IRQHandler(void);
void WEAK DMA1_Channel6_IRQHandler(void);
void WEAK DMA1_Channel7_IRQHandler(void);
void WEAK ADC1_IRQHandler(void);
void WEAK EXTI9_5_IRQHandler(void);
void WEAK TIM1_BRK_TIM15_IRQHandler(void);
void WEAK TIM1_UP_TIM16_IRQHandler(void);
void WEAK TIM1_TRG_COM_TIM17_IRQHandler(void);
void WEAK TIM1_CC_IRQHandler(void);
void WEAK TIM2_IRQHandler(void);
void WEAK TIM3_IRQHandler(void);
void WEAK TIM4_IRQHandler(void);
void WEAK I2C1_EV_IRQHandler(void);
void WEAK I2C1_ER_IRQHandler(void);
void WEAK I2C2_EV_IRQHandler(void);
void WEAK I2C2_ER_IRQHandler(void);
void WEAK SPI1_IRQHandler(void);
void WEAK SPI2_IRQHandler(void);
void WEAK USART1_IRQHandler(void);
void WEAK USART2_IRQHandler(void);
void WEAK USART3_IRQHandler(void);
void WEAK EXTI15_10_IRQHandler(void);
void WEAK RTCAlarm_IRQHandler(void);
void WEAK CEC_IRQHandler(void);
void WEAK TIM6_DAC_IRQHandler(void);
void WEAK TIM7_IRQHandler(void);
/*----------Symbols defined in linker script----------------------------------*/
extern unsigned long _sidata; /*!< Start address for the initialization
values of the .data section. */
extern unsigned long _sdata; /*!< Start address for the .data section */
extern unsigned long _edata; /*!< End address for the .data section */
extern unsigned long _sbss; /*!< Start address for the .bss section */
extern unsigned long _ebss; /*!< End address for the .bss section */
extern void _eram; /*!< End address for ram */
/*----------Function prototypes-----------------------------------------------*/
extern int main(void); /*!< The entry point for the application. */
extern void SystemInit(void); /*!< Setup the microcontroller system(CMSIS) */
void Default_Reset_Handler(void); /*!< Default reset handler */
static void Default_Handler(void); /*!< Default exception handler */
/**
*@brief The minimal vector table for a Cortex M3. Note that the proper constructs
* must be placed on this to ensure that it ends up at physical address
* 0x00000000.
*/
__attribute__ ((used,section(".isr_vector")))
void (* const g_pfnVectors[])(void) =
{
/*----------Core Exceptions-------------------------------------------------*/
(void *)&pulStack[STACK_SIZE], /*!< The initial stack pointer */
Reset_Handler, /*!< Reset Handler */
NMI_Handler, /*!< NMI Handler */
HardFault_Handler, /*!< Hard Fault Handler */
MemManage_Handler, /*!< MPU Fault Handler */
BusFault_Handler, /*!< Bus Fault Handler */
UsageFault_Handler, /*!< Usage Fault Handler */
0,0,0,0, /*!< Reserved */
SVC_Handler, /*!< SVCall Handler */
DebugMon_Handler, /*!< Debug Monitor Handler */
0, /*!< Reserved */
PendSV_Handler, /*!< PendSV Handler */
SysTick_Handler, /*!< SysTick Handler */
/*----------External Exceptions---------------------------------------------*/
WWDG_IRQHandler, /*!< 0: Window Watchdog */
PVD_IRQHandler, /*!< 1: PVD through EXTI Line detect */
TAMPER_IRQHandler, /*!< 2: Tamper */
RTC_IRQHandler, /*!< 3: RTC */
FLASH_IRQHandler, /*!< 4: Flash */
RCC_IRQHandler, /*!< 5: RCC */
EXTI0_IRQHandler, /*!< 6: EXTI Line 0 */
EXTI1_IRQHandler, /*!< 7: EXTI Line 1 */
EXTI2_IRQHandler, /*!< 8: EXTI Line 2 */
EXTI3_IRQHandler, /*!< 9: EXTI Line 3 */
EXTI4_IRQHandler, /*!< 10: EXTI Line 4 */
DMA1_Channel1_IRQHandler, /*!< 11: DMA1 Channel 1 */
DMA1_Channel2_IRQHandler, /*!< 12: DMA1 Channel 2 */
DMA1_Channel3_IRQHandler, /*!< 13: DMA1 Channel 3 */
DMA1_Channel4_IRQHandler, /*!< 14: DMA1 Channel 4 */
DMA1_Channel5_IRQHandler, /*!< 15: DMA1 Channel 5 */
DMA1_Channel6_IRQHandler, /*!< 16: DMA1 Channel 6 */
DMA1_Channel7_IRQHandler, /*!< 17: DMA1 Channel 7 */
ADC1_IRQHandler, /*!< 18: ADC1 */
0, /*!< 19: USB High Priority or CAN1 TX */
0, /*!< 20: USB Low Priority or CAN1 RX0 */
0, /*!< 21: CAN1 RX1 */
0, /*!< 22: CAN1 SCE */
EXTI9_5_IRQHandler, /*!< 23: EXTI Line 9..5 */
TIM1_BRK_TIM15_IRQHandler, /*!< 24: TIM1 Break and TIM15 */
TIM1_UP_TIM16_IRQHandler, /*!< 25: TIM1 Update and TIM16 */
TIM1_TRG_COM_TIM17_IRQHandler,/*!< 26: TIM1 Trigger and Commutation and TIM17 */
TIM1_CC_IRQHandler, /*!< 27: TIM1 Capture Compare */
TIM2_IRQHandler, /*!< 28: TIM2 */
TIM3_IRQHandler, /*!< 29: TIM3 */
TIM4_IRQHandler, /*!< 30: TIM4 */
I2C1_EV_IRQHandler, /*!< 31: I2C1 Event */
I2C1_ER_IRQHandler, /*!< 32: I2C1 Error */
I2C2_EV_IRQHandler, /*!< 33: I2C2 Event */
I2C2_ER_IRQHandler, /*!< 34: I2C2 Error */
SPI1_IRQHandler, /*!< 35: SPI1 */
SPI2_IRQHandler, /*!< 36: SPI2 */
USART1_IRQHandler, /*!< 37: USART1 */
USART2_IRQHandler, /*!< 38: USART2 */
USART3_IRQHandler, /*!< 39: USART3 */
EXTI15_10_IRQHandler, /*!< 40: EXTI Line 15..10 */
RTCAlarm_IRQHandler, /*!< 41: RTC Alarm through EXTI Line */
CEC_IRQHandler, /*!< 42: HDMI-CEC */
0,0,0,0,0,0, /*!< Reserved */
0,0,0,0,0, /*!< Reserved */
TIM6_DAC_IRQHandler, /*!< 54: TIM6 and DAC underrun */
TIM7_IRQHandler, /*!< 55: TIM7 */
(void *)0xF108F85F /*!< Boot in RAM mode */
};
/**
* @brief This is the code that gets called when the processor first
* starts execution following a reset event. Only the absolutely
* necessary set is performed, after which the application
* supplied main() routine is called.
* @param None
* @retval None
*/
void Default_Reset_Handler(void)
{
/* Initialize data and bss */
unsigned long *pulSrc, *pulDest;
/* Copy the data segment initializers from flash to SRAM */
pulSrc = &_sidata;
for(pulDest = &_sdata; pulDest < &_edata; )
{
*(pulDest++) = *(pulSrc++);
}
/* Zero fill the bss segment. This is done with inline assembly since this
will clear the value of pulDest if it is not kept in a register. */
__asm(" ldr r0, =_sbss\n"
" ldr r1, =_ebss\n"
" mov r2, #0\n"
" .thumb_func\n"
" zero_loop:\n"
" cmp r0, r1\n"
" it lt\n"
" strlt r2, [r0], #4\n"
" blt zero_loop");
/* Setup the microcontroller system. */
//SystemInit();
/* Call the application's entry point.*/
main();
}
/**
*@brief Provide weak aliases for each Exception handler to the Default_Handler.
* As they are weak aliases, any function with the same name will override
* this definition.
*/
#pragma weak Reset_Handler = Default_Reset_Handler
#pragma weak NMI_Handler = Default_Handler
#pragma weak HardFault_Handler = Default_Handler
#pragma weak MemManage_Handler = Default_Handler
#pragma weak BusFault_Handler = Default_Handler
#pragma weak UsageFault_Handler = Default_Handler
#pragma weak SVC_Handler = Default_Handler
#pragma weak DebugMon_Handler = Default_Handler
#pragma weak PendSV_Handler = Default_Handler
#pragma weak SysTick_Handler = Default_Handler
#pragma weak WWDG_IRQHandler = Default_Handler
#pragma weak PVD_IRQHandler = Default_Handler
#pragma weak TAMPER_IRQHandler = Default_Handler
#pragma weak RTC_IRQHandler = Default_Handler
#pragma weak FLASH_IRQHandler = Default_Handler
#pragma weak RCC_IRQHandler = Default_Handler
#pragma weak EXTI0_IRQHandler = Default_Handler
#pragma weak EXTI1_IRQHandler = Default_Handler
#pragma weak EXTI2_IRQHandler = Default_Handler
#pragma weak EXTI3_IRQHandler = Default_Handler
#pragma weak EXTI4_IRQHandler = Default_Handler
#pragma weak DMA1_Channel1_IRQHandler = Default_Handler
#pragma weak DMA1_Channel2_IRQHandler = Default_Handler
#pragma weak DMA1_Channel3_IRQHandler = Default_Handler
#pragma weak DMA1_Channel4_IRQHandler = Default_Handler
#pragma weak DMA1_Channel5_IRQHandler = Default_Handler
#pragma weak DMA1_Channel6_IRQHandler = Default_Handler
#pragma weak DMA1_Channel7_IRQHandler = Default_Handler
#pragma weak ADC1_IRQHandler = Default_Handler
#pragma weak EXTI9_5_IRQHandler = Default_Handler
#pragma weak TIM1_BRK_TIM15_IRQHandler = Default_Handler
#pragma weak TIM1_UP_TIM16_IRQHandler = Default_Handler
#pragma weak TIM1_TRG_COM_TIM17_IRQHandler = Default_Handler
#pragma weak TIM1_CC_IRQHandler = Default_Handler
#pragma weak TIM2_IRQHandler = Default_Handler
#pragma weak TIM3_IRQHandler = Default_Handler
#pragma weak TIM4_IRQHandler = Default_Handler
#pragma weak I2C1_EV_IRQHandler = Default_Handler
#pragma weak I2C1_ER_IRQHandler = Default_Handler
#pragma weak I2C2_EV_IRQHandler = Default_Handler
#pragma weak I2C2_ER_IRQHandler = Default_Handler
#pragma weak SPI1_IRQHandler = Default_Handler
#pragma weak SPI2_IRQHandler = Default_Handler
#pragma weak USART1_IRQHandler = Default_Handler
#pragma weak USART2_IRQHandler = Default_Handler
#pragma weak USART3_IRQHandler = Default_Handler
#pragma weak EXTI15_10_IRQHandler = Default_Handler
#pragma weak RTCAlarm_IRQHandler = Default_Handler
#pragma weak CEC_IRQHandler = Default_Handler
#pragma weak TIM6_DAC_IRQHandler = Default_Handler
#pragma weak TIM7_IRQHandler = Default_Handler
/**
* @brief This is the code that gets called when the processor receives an
* unexpected interrupt. This simply enters an infinite loop,
* preserving the system state for examination by a debugger.
* @param None
* @retval None
*/
static void Default_Handler(void)
{
/* Go into an infinite loop. */
while (1)
{
}
}
/*********************** (C) COPYRIGHT 2011 Coocox ************END OF FILE*****/

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,78 @@
/**
******************************************************************************
* @file RTC/Calendar/stm32f10x_conf.h
* @author MCD Application Team
* @version V3.4.0
* @date 10/15/2010
* @brief Library configuration file.
******************************************************************************
* @copy
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2010 STMicroelectronics</center></h2>
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_CONF_H
#define __STM32F10x_CONF_H
/* Includes ------------------------------------------------------------------*/
/* Uncomment the line below to enable peripheral header file inclusion */
/* #include "stm32f10x_adc.h" */
/* #include "stm32f10x_bkp.h" */
/* #include "stm32f10x_can.h" */
/* #include "stm32f10x_cec.h" */
/* #include "stm32f10x_crc.h" */
/* #include "stm32f10x_dac.h" */
/* #include "stm32f10x_dbgmcu.h" */
/* #include "stm32f10x_dma.h" */
/* #include "stm32f10x_exti.h" */
/* #include "stm32f10x_flash.h" */
/* #include "stm32f10x_fsmc.h" */
/* #include "stm32f10x_gpio.h" */
/* #include "stm32f10x_i2c.h" */
/* #include "stm32f10x_iwdg.h" */
/* #include "stm32f10x_pwr.h" */
/* #include "stm32f10x_rcc.h" */
/* #include "stm32f10x_rtc.h" */
/* #include "stm32f10x_sdio.h" */
/* #include "stm32f10x_spi.h" */
/* #include "stm32f10x_tim.h" */
/* #include "stm32f10x_usart.h" */
/* #include "stm32f10x_wwdg.h" */
/* #include "misc.h" */ /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Uncomment the line below to expanse the "assert_param" macro in the
Standard Peripheral Library drivers code */
/* #define USE_FULL_ASSERT 1 */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#endif /* __STM32F10x_CONF_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,98 @@
/**
******************************************************************************
* @file system_stm32f10x.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f10x_system
* @{
*/
/**
* @brief Define to prevent recursive inclusion
*/
#ifndef __SYSTEM_STM32F10X_H
#define __SYSTEM_STM32F10X_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup STM32F10x_System_Includes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_types
* @{
*/
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_Constants
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_STM32F10X_H */
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

66
src/hal/delay.c 100644
Wyświetl plik

@ -0,0 +1,66 @@
#include <stdbool.h>
#include <stm32f10x.h>
#include <stm32f10x_rcc.h>
#include <stm32f10x_tim.h>
#include <misc.h>
#include "delay.h"
volatile bool done;
void delay_init()
{
TIM_DeInit(TIM3);
TIM_TimeBaseInitTypeDef tim_init;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE);
tim_init.TIM_Prescaler = 192 - 1;
tim_init.TIM_CounterMode = TIM_CounterMode_Up;
tim_init.TIM_Period = 0;
tim_init.TIM_ClockDivision = TIM_CKD_DIV1;
tim_init.TIM_RepetitionCounter = 0;
TIM_TimeBaseInit(TIM3, &tim_init);
TIM_ClearITPendingBit(TIM3, TIM_IT_Update);
TIM_ITConfig(TIM3, TIM_IT_Update, ENABLE);
NVIC_InitTypeDef nvic_init;
nvic_init.NVIC_IRQChannel = TIM3_IRQn;
nvic_init.NVIC_IRQChannelPreemptionPriority = 2;
nvic_init.NVIC_IRQChannelSubPriority = 2;
nvic_init.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic_init);
TIM_Cmd(TIM3, DISABLE);
}
void delay_us(uint16_t us)
{
TIM_Cmd(TIM3, DISABLE);
TIM_SetAutoreload(TIM3, us / 8);
TIM_SetCounter(TIM3, 0);
TIM_Cmd(TIM3, ENABLE);
done = false;
while (!done) {}
TIM_Cmd(TIM3, DISABLE);
}
inline void delay_ms(uint32_t ms)
{
while (ms-- > 0) {
delay_us(1000);
}
}
void TIM3_IRQHandler(void)
{
if (TIM_GetITStatus(TIM3, TIM_IT_Update) != RESET) {
TIM_ClearITPendingBit(TIM3, TIM_IT_Update);
done = true;
}
}

18
src/hal/delay.h 100644
Wyświetl plik

@ -0,0 +1,18 @@
#ifndef __DELAY_H
#define __DELAY_H
#ifdef __cplusplus
extern "C" {
#endif
void delay_init();
void delay_us(uint16_t us);
void delay_ms(uint32_t ms);
#ifdef __cplusplus
}
#endif
#endif

13
src/hal/hal.h 100644
Wyświetl plik

@ -0,0 +1,13 @@
#ifndef __HAL_H
#define __HAL_H
#include <stddef.h>
#include <stdint.h>
#include <stdbool.h>
#define HAL_OK 0
#define HAL_ERROR -1
#define HAL_ERROR_TIMEOUT -2
#endif

164
src/hal/i2c.c 100644
Wyświetl plik

@ -0,0 +1,164 @@
#include "stm32f10x_rcc.h"
#include "stm32f10x_gpio.h"
#include "stm32f10x_i2c.h"
#include "hal.h"
#include "i2c.h"
#include "delay.h"
struct _i2c_port {
I2C_TypeDef *i2c;
};
i2c_port DEFAULT_I2C_PORT = {
.i2c = I2C_PORT,
};
void i2c_init()
{
GPIO_InitTypeDef gpio_init;
gpio_init.GPIO_Pin = I2C_PIN_SCL;
gpio_init.GPIO_Mode = GPIO_Mode_AF_OD;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(I2C_GPIO, &gpio_init);
gpio_init.GPIO_Pin = I2C_PIN_SDA;
gpio_init.GPIO_Mode = GPIO_Mode_AF_OD;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(I2C_GPIO, &gpio_init);
RCC_APB1PeriphClockCmd(I2C_PORT_RCC_PERIPH, ENABLE);
I2C_SoftwareResetCmd(I2C_PORT, ENABLE);
delay_ms(2);
I2C_SoftwareResetCmd(I2C_PORT, DISABLE);
RCC_APB1PeriphResetCmd(I2C_PORT_RCC_PERIPH, ENABLE);
delay_ms(2);
RCC_APB1PeriphResetCmd(I2C_PORT_RCC_PERIPH, DISABLE);
// NOTE: I2C chip reset is necessary here!
I2C_DeInit(I2C_PORT);
I2C_InitTypeDef i2c_init;
I2C_StructInit(&i2c_init);
i2c_init.I2C_ClockSpeed = 10000;
i2c_init.I2C_Mode = I2C_Mode_I2C;
i2c_init.I2C_DutyCycle = I2C_DutyCycle_2;
i2c_init.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
i2c_init.I2C_Ack = I2C_Ack_Enable;
I2C_Init(I2C_PORT, &i2c_init);
while (I2C_GetFlagStatus(I2C_PORT, I2C_FLAG_BUSY));
I2C_Cmd(I2C_PORT, ENABLE);
}
void i2c_uninit()
{
I2C_Cmd(I2C_PORT, DISABLE);
I2C_DeInit(I2C_PORT);
RCC_APB1PeriphClockCmd(I2C_PORT_RCC_PERIPH, DISABLE);
}
static int i2c_prepare_op(i2c_port *port, uint8_t address)
{
I2C_AcknowledgeConfig(port->i2c, ENABLE);
I2C_GenerateSTART(port->i2c, ENABLE);
while (!I2C_CheckEvent(port->i2c, I2C_EVENT_MASTER_MODE_SELECT));
I2C_Send7bitAddress(port->i2c, address, I2C_Direction_Transmitter);
while (!I2C_CheckEvent(port->i2c, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED));
return HAL_OK;
}
static int i2c_prepare_op_with_register(i2c_port *port, uint8_t address, uint8_t reg)
{
i2c_prepare_op(port, address);
I2C_SendData(port->i2c, reg);
while (!I2C_CheckEvent(port->i2c, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
return HAL_OK;
}
static int i2c_prepare_read(i2c_port *port, uint8_t address, uint8_t reg)
{
i2c_prepare_op_with_register(port, address, reg);
I2C_GenerateSTART(port->i2c, ENABLE);
while (!I2C_CheckEvent(port->i2c, I2C_EVENT_MASTER_MODE_SELECT));
I2C_Send7bitAddress(port->i2c, address, I2C_Direction_Receiver);
while (!I2C_CheckEvent(port->i2c, I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED));
return HAL_OK;
}
static int i2c_finish_read(i2c_port *port)
{
I2C_GenerateSTOP(port->i2c, ENABLE);
I2C_AcknowledgeConfig(port->i2c, DISABLE);
while (!I2C_CheckEvent(port->i2c, I2C_EVENT_MASTER_BYTE_RECEIVED));
I2C_ReceiveData(port->i2c);
return HAL_OK;
}
static int i2c_prepare_write(i2c_port *port, uint8_t address, uint8_t reg)
{
return i2c_prepare_op_with_register(port, address, reg);
}
static int i2c_finish_write(i2c_port *port)
{
I2C_GenerateSTOP(port->i2c, ENABLE);
while (!I2C_CheckEvent(port->i2c, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
return HAL_OK;
}
int i2c_read_bytes(i2c_port *port, uint8_t address, uint8_t reg, uint8_t size, uint8_t *data)
{
i2c_prepare_read(port, address, reg);
for (uint8_t i = 0; i < size; i++) {
while (!I2C_CheckEvent(port->i2c, I2C_EVENT_MASTER_BYTE_RECEIVED));
data[i] = I2C_ReceiveData(port->i2c);
}
i2c_finish_read(port);
return HAL_OK;
}
int i2c_read_byte(i2c_port *port, uint8_t address, uint8_t reg, uint8_t *data)
{
return i2c_read_bytes(port, address, reg, 1, data);
}
int i2c_write_bytes(i2c_port *port, uint8_t address, uint8_t reg, uint8_t size, uint8_t *data)
{
i2c_prepare_write(port, address, reg);
for (uint8_t i = 0; i < size; i++) {
I2C_SendData(port->i2c, data[i]);
while (!I2C_CheckEvent(port->i2c, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
}
i2c_finish_write(port);
return HAL_OK;
}
int i2c_write_byte(i2c_port *port, uint8_t address, uint8_t reg, uint8_t data)
{
return i2c_write_bytes(port, address, reg, 1, &data);
}

34
src/hal/i2c.h 100644
Wyświetl plik

@ -0,0 +1,34 @@
#ifndef __HAL_I2C_H
#define __HAL_I2C_H
#define I2C_PORT I2C2
#define I2C_PORT_RCC_PERIPH RCC_APB1Periph_I2C2
#define I2C_GPIO GPIOB
// PB10: I2C2_SCL/USART3_TX
#define I2C_PIN_SCL GPIO_Pin_10
// PB11: I2C2_SDA/USART3_RX
#define I2C_PIN_SDA GPIO_Pin_11
#include "hal.h"
typedef struct _i2c_port i2c_port;
extern i2c_port DEFAULT_I2C_PORT;
#ifdef __cplusplus
extern "C" {
#endif
void i2c_init();
void i2c_uninit();
int i2c_read_bytes(struct _i2c_port *port, uint8_t address, uint8_t reg, uint8_t size, uint8_t *data);
int i2c_read_byte(struct _i2c_port *port, uint8_t address, uint8_t reg, uint8_t *data);
int i2c_write_bytes(struct _i2c_port *port, uint8_t address, uint8_t reg, uint8_t size, uint8_t *data);
int i2c_write_byte(struct _i2c_port *port, uint8_t address, uint8_t reg, uint8_t data);
#ifdef __cplusplus
};
#endif
#endif

230
src/hal/pwm.c 100644
Wyświetl plik

@ -0,0 +1,230 @@
#include <stm32f10x_rcc.h>
#include <stm32f10x_gpio.h>
#include <stm32f10x_tim.h>
#include <stm32f10x_dma.h>
#include <misc.h>
#include "pwm.h"
uint16_t pwm_timer_dma_buffer[PWM_TIMER_DMA_BUFFER_SIZE];
size_t (*pwm_handle_dma_transfer_half)(size_t buffer_size, uint16_t *buffer) = NULL;
size_t (*pwm_handle_dma_transfer_full)(size_t buffer_size, uint16_t *buffer) = NULL;
DMA_Channel_TypeDef *pwm_dma_channel = DMA1_Channel2;
void pwm_data_timer_init()
{
// Timer frequency = TIM_CLK/(TIM_PSC+1)/(TIM_ARR + 1)
// TIM_CLK =
// TIM_PSC = Prescaler
// TIM_ARR = Period
TIM_DeInit(TIM2);
TIM_TimeBaseInitTypeDef tim_init;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE);
tim_init.TIM_Prescaler = 2 - 1; // tick every 1/12000000 s
tim_init.TIM_CounterMode = TIM_CounterMode_Up;
tim_init.TIM_Period = 10000 - 1 - 55; // update every 1/1200 s
tim_init.TIM_ClockDivision = TIM_CKD_DIV1;
tim_init.TIM_RepetitionCounter = 0;
TIM_TimeBaseInit(TIM2, &tim_init);
// No interrupts necessary for data timer, as it is only used for triggering DMA transfers
/*
TIM_ClearITPendingBit(TIM2, TIM_IT_Update);
TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE);
NVIC_InitTypeDef nvic_init;
nvic_init.NVIC_IRQChannel = TIM2_IRQn;
nvic_init.NVIC_IRQChannelPreemptionPriority = 0;
nvic_init.NVIC_IRQChannelSubPriority = 1;
nvic_init.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic_init);
*/
TIM_Cmd(TIM2, ENABLE);
}
void pwm_data_timer_dma_request_enable(bool enabled)
{
// TIM2 Update DMA requests are routed to DMA1 Channel2
TIM_DMACmd(TIM2, TIM_DMA_Update, enabled ? ENABLE : DISABLE);
}
void pwm_timer_init(uint32_t frequency_hz_100)
{
TIM_DeInit(TIM15);
GPIO_PinRemapConfig(GPIO_Remap_TIM15, DISABLE);
// Not needed: AFIO->MAPR2 |= AFIO_MAPR2_TIM15_REMAP;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM15, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, DISABLE);
TIM_TimeBaseInitTypeDef tim_init;
// Not needed: TIM_InternalClockConfig(TIM15);
tim_init.TIM_Prescaler = 24 - 1; // tick every 1/1000000 s
tim_init.TIM_CounterMode = TIM_CounterMode_Up;
tim_init.TIM_Period = (uint16_t) (((100.0f * 1000000.0f) / (frequency_hz_100 * 2.0f))) - 1;
tim_init.TIM_ClockDivision = TIM_CKD_DIV1;
tim_init.TIM_RepetitionCounter = 0;
TIM_TimeBaseInit(TIM15, &tim_init);
TIM_OCInitTypeDef TIM15_OCInitStruct;
TIM_OCStructInit(&TIM15_OCInitStruct);
TIM15_OCInitStruct.TIM_Pulse = 0; // Was: tim_init.TIM_Period / 2
TIM15_OCInitStruct.TIM_OCMode = TIM_OCMode_Toggle; // Was: TIM_OCMode_PWM1
TIM15_OCInitStruct.TIM_OutputState = TIM_OutputState_Enable;
TIM15_OCInitStruct.TIM_OCPolarity = TIM_OCPolarity_High;
TIM_OC2Init(TIM15, &TIM15_OCInitStruct);
// These are not needed?
// TIM_SelectOCxM(TIM15, TIM_Channel_2, TIM_OCMode_PWM1);
// TIM_CCxCmd(TIM15, TIM_Channel_2, TIM_CCx_Enable);
// The following make transitions smooth
TIM_ARRPreloadConfig(TIM15, ENABLE);
TIM_OC2PreloadConfig(TIM15, TIM_OCPreload_Enable);
TIM_OC2FastConfig(TIM15, TIM_OCFast_Enable);
TIM_CtrlPWMOutputs(TIM15, DISABLE);
TIM_Cmd(TIM15, ENABLE);
}
static void pwm_dma_init_channel()
{
DMA_InitTypeDef dma_init;
dma_init.DMA_BufferSize = PWM_TIMER_DMA_BUFFER_SIZE;
dma_init.DMA_DIR = DMA_DIR_PeripheralDST;
dma_init.DMA_M2M = DMA_M2M_Disable;
dma_init.DMA_MemoryBaseAddr = (uint32_t) pwm_timer_dma_buffer;
dma_init.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable;
dma_init.DMA_Mode = DMA_Mode_Circular;
dma_init.DMA_PeripheralBaseAddr = (uint32_t) &TIM15->ARR;
dma_init.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; // DMA_PeripheralDataSize_Word ?
dma_init.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
dma_init.DMA_Priority = DMA_Priority_VeryHigh;
DMA_Init(pwm_dma_channel, &dma_init);
}
inline void pwm_dma_interrupt_enable(bool enabled)
{
DMA_ClearITPendingBit(DMA1_IT_HT2);
DMA_ClearITPendingBit(DMA1_IT_TC2);
DMA_ITConfig(pwm_dma_channel, DMA_IT_HT | DMA_IT_TC | DMA_IT_TE, enabled ? ENABLE : DISABLE);
}
void pwm_dma_init()
{
DMA_DeInit(pwm_dma_channel);
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
pwm_dma_init_channel();
pwm_dma_interrupt_enable(true);
DMA_Cmd(pwm_dma_channel, ENABLE);
NVIC_InitTypeDef nvic_init;
nvic_init.NVIC_IRQChannel = DMA1_Channel2_IRQn;
nvic_init.NVIC_IRQChannelPreemptionPriority = 0;
nvic_init.NVIC_IRQChannelSubPriority = 1;
nvic_init.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic_init);
}
#include "log.h"
void pwm_dma_start()
{
//pwm_dma_init_channel();
//pwm_dma_interrupt_enable(true);
// TODO: Why doesn't timer DMA request restart without reinitializing the timer?
pwm_timer_init(100 * 100);
pwm_timer_pwm_enable(true);
pwm_timer_use(true);
DMA_SetCurrDataCounter(pwm_dma_channel, PWM_TIMER_DMA_BUFFER_SIZE);
DMA_Cmd(pwm_dma_channel, ENABLE);
pwm_data_timer_dma_request_enable(true);
}
void pwm_dma_stop()
{
pwm_data_timer_dma_request_enable(false);
DMA_Cmd(pwm_dma_channel, DISABLE);
//pwm_dma_interrupt_enable(false);
}
void DMA1_Channel2_IRQHandler(void)
{
if (DMA_GetITStatus(DMA1_IT_TE2)) {
DMA_ClearITPendingBit(DMA1_IT_TE2);
log_info("DMA Transfer Error\n");
}
if (DMA_GetITStatus(DMA1_IT_HT2)) {
DMA_ClearITPendingBit(DMA1_IT_HT2);
pwm_handle_dma_transfer_half(PWM_TIMER_DMA_BUFFER_SIZE, pwm_timer_dma_buffer);
//if (length < PWM_TIMER_DMA_BUFFER_SIZE / 2) {
//}
}
if (DMA_GetITStatus(DMA1_IT_TC2)) {
DMA_ClearITPendingBit(DMA1_IT_TC2);
pwm_handle_dma_transfer_full(PWM_TIMER_DMA_BUFFER_SIZE, pwm_timer_dma_buffer);
//if (length < PWM_TIMER_DMA_BUFFER_SIZE / 2) {
//}
}
}
void pwm_timer_pwm_enable(bool enabled)
{
TIM_CtrlPWMOutputs(TIM15, enabled ? ENABLE : DISABLE);
}
void pwm_timer_use(bool use)
{
GPIO_PinRemapConfig(GPIO_Remap_TIM15, use ? ENABLE : DISABLE);
}
void pwm_timer_uninit()
{
TIM_CtrlPWMOutputs(TIM15, DISABLE);
TIM_Cmd(TIM15, DISABLE);
TIM_DeInit(TIM15);
GPIO_PinRemapConfig(GPIO_Remap_TIM15, DISABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM15, DISABLE);
}
inline uint16_t pwm_calculate_period(uint32_t frequency_hz_100)
{
return (uint16_t) (((100.0f * 1000000.0f) / (frequency_hz_100 * 2.0f))) - 1;
}
inline void pwm_timer_set_frequency(uint32_t frequency_hz_100)
{
uint16_t period = pwm_calculate_period(frequency_hz_100);
// TIM_CtrlPWMOutputs(TIM15, DISABLE);
// TIM_Cmd(TIM15, DISABLE);
TIM_SetAutoreload(TIM15, period);
// TIM_SetCompare2(TIM15, period / 2);
// TIM_Cmd(TIM15, ENABLE);
// TIM_CtrlPWMOutputs(TIM15, ENABLE);
}

29
src/hal/pwm.h 100644
Wyświetl plik

@ -0,0 +1,29 @@
#ifndef __PWM_H
#define __PWM_H
#include <stddef.h>
#include <stdbool.h>
#define PWM_TIMER_DMA_BUFFER_SIZE 256
void pwm_data_timer_init();
void pwm_data_timer_dma_request_enable(bool enabled);
void pwm_timer_init(uint32_t frequency_hz_100);
void pwm_timer_pwm_enable(bool enabled);
void pwm_timer_use(bool use);
void pwm_timer_uninit();
uint16_t pwm_calculate_period(uint32_t frequency_hz_100);
void pwm_timer_set_frequency(uint32_t frequency_hz_100);
void pwm_dma_init();
void pwm_dma_interrupt_enable(bool enabled);
void pwm_dma_start();
void pwm_dma_stop();
extern size_t (*pwm_handle_dma_transfer_half)(size_t buffer_size, uint16_t *buffer);
extern size_t (*pwm_handle_dma_transfer_full)(size_t buffer_size, uint16_t *buffer);
extern uint16_t pwm_timer_dma_buffer[PWM_TIMER_DMA_BUFFER_SIZE];
#endif

87
src/hal/spi.c 100644
Wyświetl plik

@ -0,0 +1,87 @@
#include <stm32f10x_rcc.h>
#include <stm32f10x_gpio.h>
#include <stm32f10x_spi.h>
#include "spi.h"
void spi_init()
{
GPIO_InitTypeDef gpio_init;
// SPI2_SCK & SPI2_MOSI
gpio_init.GPIO_Pin = GPIO_Pin_13 | GPIO_Pin_15;
gpio_init.GPIO_Mode = GPIO_Mode_AF_PP;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOB, &gpio_init);
// SPI2_MISO
gpio_init.GPIO_Pin = GPIO_Pin_14;
gpio_init.GPIO_Mode = GPIO_Mode_IN_FLOATING;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOB, &gpio_init);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
SPI_InitTypeDef spi_init;
SPI_StructInit(&spi_init);
spi_init.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
spi_init.SPI_Mode = SPI_Mode_Master;
spi_init.SPI_DataSize = SPI_DataSize_16b;
spi_init.SPI_CPOL = SPI_CPOL_Low;
spi_init.SPI_CPHA = SPI_CPHA_1Edge;
spi_init.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256;
spi_init.SPI_FirstBit = SPI_FirstBit_MSB;
spi_init.SPI_CRCPolynomial = 7;
SPI_Init(SPI2, &spi_init);
SPI_SSOutputCmd(SPI2, ENABLE);
SPI_Cmd(SPI2, ENABLE);
SPI_Init(SPI2, &spi_init);
}
void spi_uninit()
{
SPI_I2S_DeInit(SPI2);
SPI_Cmd(SPI2, DISABLE);
SPI_SSOutputCmd(SPI2, DISABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, DISABLE);
GPIO_InitTypeDef gpio_init;
gpio_init.GPIO_Pin = GPIO_Pin_14;
gpio_init.GPIO_Mode = GPIO_Mode_AF_PP;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOB, &gpio_init);
gpio_init.GPIO_Pin = GPIO_Pin_15;
gpio_init.GPIO_Mode = GPIO_Mode_AF_PP; // was: GPIO_Mode_Out_PP; // GPIO_Mode_AF_PP
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOB, &gpio_init);
}
inline void spi_send(uint16_t data)
{
// Wait for TX buffer
while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_TXE) == RESET);
SPI_I2S_SendData(SPI2, data);
}
inline uint8_t spi_receive()
{
// Wait for data in RX buffer
while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_RXNE) == RESET);
return (uint8_t) SPI_I2S_ReceiveData(SPI2);
}
uint8_t spi_send_and_receive(GPIO_TypeDef *gpio_cs, uint16_t pin_cs, uint16_t data) {
GPIO_ResetBits(gpio_cs, pin_cs);
while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_TXE) == RESET);
SPI_I2S_SendData(SPI2, data);
while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_RXNE) == RESET);
GPIO_SetBits(gpio_cs, pin_cs);
return (uint8_t) SPI_I2S_ReceiveData(SPI2);
}

17
src/hal/spi.h 100644
Wyświetl plik

@ -0,0 +1,17 @@
#ifndef __SPI_H
#define __SPI_H
#include <stdint.h>
#include <stm32f10x.h>
void spi_init();
void spi_uninit();
void spi_send(uint16_t data);
uint8_t spi_receive();
uint8_t spi_send_and_receive(GPIO_TypeDef *gpio_cs, uint16_t pin_cs, uint16_t data);
#endif

Wyświetl plik

@ -0,0 +1,220 @@
/**
******************************************************************************
* @file misc.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the miscellaneous
* firmware library functions (add-on to CMSIS functions).
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MISC_H
#define __MISC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup MISC
* @{
*/
/** @defgroup MISC_Exported_Types
* @{
*/
/**
* @brief NVIC Init Structure definition
*/
typedef struct
{
uint8_t NVIC_IRQChannel; /*!< Specifies the IRQ channel to be enabled or disabled.
This parameter can be a value of @ref IRQn_Type
(For the complete STM32 Devices IRQ Channels list, please
refer to stm32f10x.h file) */
uint8_t NVIC_IRQChannelPreemptionPriority; /*!< Specifies the pre-emption priority for the IRQ channel
specified in NVIC_IRQChannel. This parameter can be a value
between 0 and 15 as described in the table @ref NVIC_Priority_Table */
uint8_t NVIC_IRQChannelSubPriority; /*!< Specifies the subpriority level for the IRQ channel specified
in NVIC_IRQChannel. This parameter can be a value
between 0 and 15 as described in the table @ref NVIC_Priority_Table */
FunctionalState NVIC_IRQChannelCmd; /*!< Specifies whether the IRQ channel defined in NVIC_IRQChannel
will be enabled or disabled.
This parameter can be set either to ENABLE or DISABLE */
} NVIC_InitTypeDef;
/**
* @}
*/
/** @defgroup NVIC_Priority_Table
* @{
*/
/**
@code
The table below gives the allowed values of the pre-emption priority and subpriority according
to the Priority Grouping configuration performed by NVIC_PriorityGroupConfig function
============================================================================================================================
NVIC_PriorityGroup | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority | Description
============================================================================================================================
NVIC_PriorityGroup_0 | 0 | 0-15 | 0 bits for pre-emption priority
| | | 4 bits for subpriority
----------------------------------------------------------------------------------------------------------------------------
NVIC_PriorityGroup_1 | 0-1 | 0-7 | 1 bits for pre-emption priority
| | | 3 bits for subpriority
----------------------------------------------------------------------------------------------------------------------------
NVIC_PriorityGroup_2 | 0-3 | 0-3 | 2 bits for pre-emption priority
| | | 2 bits for subpriority
----------------------------------------------------------------------------------------------------------------------------
NVIC_PriorityGroup_3 | 0-7 | 0-1 | 3 bits for pre-emption priority
| | | 1 bits for subpriority
----------------------------------------------------------------------------------------------------------------------------
NVIC_PriorityGroup_4 | 0-15 | 0 | 4 bits for pre-emption priority
| | | 0 bits for subpriority
============================================================================================================================
@endcode
*/
/**
* @}
*/
/** @defgroup MISC_Exported_Constants
* @{
*/
/** @defgroup Vector_Table_Base
* @{
*/
#define NVIC_VectTab_RAM ((uint32_t)0x20000000)
#define NVIC_VectTab_FLASH ((uint32_t)0x08000000)
#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \
((VECTTAB) == NVIC_VectTab_FLASH))
/**
* @}
*/
/** @defgroup System_Low_Power
* @{
*/
#define NVIC_LP_SEVONPEND ((uint8_t)0x10)
#define NVIC_LP_SLEEPDEEP ((uint8_t)0x04)
#define NVIC_LP_SLEEPONEXIT ((uint8_t)0x02)
#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \
((LP) == NVIC_LP_SLEEPDEEP) || \
((LP) == NVIC_LP_SLEEPONEXIT))
/**
* @}
*/
/** @defgroup Preemption_Priority_Group
* @{
*/
#define NVIC_PriorityGroup_0 ((uint32_t)0x700) /*!< 0 bits for pre-emption priority
4 bits for subpriority */
#define NVIC_PriorityGroup_1 ((uint32_t)0x600) /*!< 1 bits for pre-emption priority
3 bits for subpriority */
#define NVIC_PriorityGroup_2 ((uint32_t)0x500) /*!< 2 bits for pre-emption priority
2 bits for subpriority */
#define NVIC_PriorityGroup_3 ((uint32_t)0x400) /*!< 3 bits for pre-emption priority
1 bits for subpriority */
#define NVIC_PriorityGroup_4 ((uint32_t)0x300) /*!< 4 bits for pre-emption priority
0 bits for subpriority */
#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \
((GROUP) == NVIC_PriorityGroup_1) || \
((GROUP) == NVIC_PriorityGroup_2) || \
((GROUP) == NVIC_PriorityGroup_3) || \
((GROUP) == NVIC_PriorityGroup_4))
#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10)
#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10)
#define IS_NVIC_OFFSET(OFFSET) ((OFFSET) < 0x000FFFFF)
/**
* @}
*/
/** @defgroup SysTick_clock_source
* @{
*/
#define SysTick_CLKSource_HCLK_Div8 ((uint32_t)0xFFFFFFFB)
#define SysTick_CLKSource_HCLK ((uint32_t)0x00000004)
#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \
((SOURCE) == SysTick_CLKSource_HCLK_Div8))
/**
* @}
*/
/**
* @}
*/
/** @defgroup MISC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup MISC_Exported_Functions
* @{
*/
void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup);
void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct);
void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset);
void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState);
void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource);
#ifdef __cplusplus
}
#endif
#endif /* __MISC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Wyświetl plik

@ -0,0 +1,483 @@
/**
******************************************************************************
* @file stm32f10x_adc.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the ADC firmware
* library.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_ADC_H
#define __STM32F10x_ADC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup ADC
* @{
*/
/** @defgroup ADC_Exported_Types
* @{
*/
/**
* @brief ADC Init structure definition
*/
typedef struct
{
uint32_t ADC_Mode; /*!< Configures the ADC to operate in independent or
dual mode.
This parameter can be a value of @ref ADC_mode */
FunctionalState ADC_ScanConvMode; /*!< Specifies whether the conversion is performed in
Scan (multichannels) or Single (one channel) mode.
This parameter can be set to ENABLE or DISABLE */
FunctionalState ADC_ContinuousConvMode; /*!< Specifies whether the conversion is performed in
Continuous or Single mode.
This parameter can be set to ENABLE or DISABLE. */
uint32_t ADC_ExternalTrigConv; /*!< Defines the external trigger used to start the analog
to digital conversion of regular channels. This parameter
can be a value of @ref ADC_external_trigger_sources_for_regular_channels_conversion */
uint32_t ADC_DataAlign; /*!< Specifies whether the ADC data alignment is left or right.
This parameter can be a value of @ref ADC_data_align */
uint8_t ADC_NbrOfChannel; /*!< Specifies the number of ADC channels that will be converted
using the sequencer for regular channel group.
This parameter must range from 1 to 16. */
}ADC_InitTypeDef;
/**
* @}
*/
/** @defgroup ADC_Exported_Constants
* @{
*/
#define IS_ADC_ALL_PERIPH(PERIPH) (((PERIPH) == ADC1) || \
((PERIPH) == ADC2) || \
((PERIPH) == ADC3))
#define IS_ADC_DMA_PERIPH(PERIPH) (((PERIPH) == ADC1) || \
((PERIPH) == ADC3))
/** @defgroup ADC_mode
* @{
*/
#define ADC_Mode_Independent ((uint32_t)0x00000000)
#define ADC_Mode_RegInjecSimult ((uint32_t)0x00010000)
#define ADC_Mode_RegSimult_AlterTrig ((uint32_t)0x00020000)
#define ADC_Mode_InjecSimult_FastInterl ((uint32_t)0x00030000)
#define ADC_Mode_InjecSimult_SlowInterl ((uint32_t)0x00040000)
#define ADC_Mode_InjecSimult ((uint32_t)0x00050000)
#define ADC_Mode_RegSimult ((uint32_t)0x00060000)
#define ADC_Mode_FastInterl ((uint32_t)0x00070000)
#define ADC_Mode_SlowInterl ((uint32_t)0x00080000)
#define ADC_Mode_AlterTrig ((uint32_t)0x00090000)
#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \
((MODE) == ADC_Mode_RegInjecSimult) || \
((MODE) == ADC_Mode_RegSimult_AlterTrig) || \
((MODE) == ADC_Mode_InjecSimult_FastInterl) || \
((MODE) == ADC_Mode_InjecSimult_SlowInterl) || \
((MODE) == ADC_Mode_InjecSimult) || \
((MODE) == ADC_Mode_RegSimult) || \
((MODE) == ADC_Mode_FastInterl) || \
((MODE) == ADC_Mode_SlowInterl) || \
((MODE) == ADC_Mode_AlterTrig))
/**
* @}
*/
/** @defgroup ADC_external_trigger_sources_for_regular_channels_conversion
* @{
*/
#define ADC_ExternalTrigConv_T1_CC1 ((uint32_t)0x00000000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_T1_CC2 ((uint32_t)0x00020000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_T2_CC2 ((uint32_t)0x00060000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_T3_TRGO ((uint32_t)0x00080000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_T4_CC4 ((uint32_t)0x000A0000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO ((uint32_t)0x000C0000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_T1_CC3 ((uint32_t)0x00040000) /*!< For ADC1, ADC2 and ADC3 */
#define ADC_ExternalTrigConv_None ((uint32_t)0x000E0000) /*!< For ADC1, ADC2 and ADC3 */
#define ADC_ExternalTrigConv_T3_CC1 ((uint32_t)0x00000000) /*!< For ADC3 only */
#define ADC_ExternalTrigConv_T2_CC3 ((uint32_t)0x00020000) /*!< For ADC3 only */
#define ADC_ExternalTrigConv_T8_CC1 ((uint32_t)0x00060000) /*!< For ADC3 only */
#define ADC_ExternalTrigConv_T8_TRGO ((uint32_t)0x00080000) /*!< For ADC3 only */
#define ADC_ExternalTrigConv_T5_CC1 ((uint32_t)0x000A0000) /*!< For ADC3 only */
#define ADC_ExternalTrigConv_T5_CC3 ((uint32_t)0x000C0000) /*!< For ADC3 only */
#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \
((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \
((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \
((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \
((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \
((REGTRIG) == ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO) || \
((REGTRIG) == ADC_ExternalTrigConv_None) || \
((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \
((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \
((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_T5_CC3))
/**
* @}
*/
/** @defgroup ADC_data_align
* @{
*/
#define ADC_DataAlign_Right ((uint32_t)0x00000000)
#define ADC_DataAlign_Left ((uint32_t)0x00000800)
#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \
((ALIGN) == ADC_DataAlign_Left))
/**
* @}
*/
/** @defgroup ADC_channels
* @{
*/
#define ADC_Channel_0 ((uint8_t)0x00)
#define ADC_Channel_1 ((uint8_t)0x01)
#define ADC_Channel_2 ((uint8_t)0x02)
#define ADC_Channel_3 ((uint8_t)0x03)
#define ADC_Channel_4 ((uint8_t)0x04)
#define ADC_Channel_5 ((uint8_t)0x05)
#define ADC_Channel_6 ((uint8_t)0x06)
#define ADC_Channel_7 ((uint8_t)0x07)
#define ADC_Channel_8 ((uint8_t)0x08)
#define ADC_Channel_9 ((uint8_t)0x09)
#define ADC_Channel_10 ((uint8_t)0x0A)
#define ADC_Channel_11 ((uint8_t)0x0B)
#define ADC_Channel_12 ((uint8_t)0x0C)
#define ADC_Channel_13 ((uint8_t)0x0D)
#define ADC_Channel_14 ((uint8_t)0x0E)
#define ADC_Channel_15 ((uint8_t)0x0F)
#define ADC_Channel_16 ((uint8_t)0x10)
#define ADC_Channel_17 ((uint8_t)0x11)
#define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_16)
#define ADC_Channel_Vrefint ((uint8_t)ADC_Channel_17)
#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || ((CHANNEL) == ADC_Channel_1) || \
((CHANNEL) == ADC_Channel_2) || ((CHANNEL) == ADC_Channel_3) || \
((CHANNEL) == ADC_Channel_4) || ((CHANNEL) == ADC_Channel_5) || \
((CHANNEL) == ADC_Channel_6) || ((CHANNEL) == ADC_Channel_7) || \
((CHANNEL) == ADC_Channel_8) || ((CHANNEL) == ADC_Channel_9) || \
((CHANNEL) == ADC_Channel_10) || ((CHANNEL) == ADC_Channel_11) || \
((CHANNEL) == ADC_Channel_12) || ((CHANNEL) == ADC_Channel_13) || \
((CHANNEL) == ADC_Channel_14) || ((CHANNEL) == ADC_Channel_15) || \
((CHANNEL) == ADC_Channel_16) || ((CHANNEL) == ADC_Channel_17))
/**
* @}
*/
/** @defgroup ADC_sampling_time
* @{
*/
#define ADC_SampleTime_1Cycles5 ((uint8_t)0x00)
#define ADC_SampleTime_7Cycles5 ((uint8_t)0x01)
#define ADC_SampleTime_13Cycles5 ((uint8_t)0x02)
#define ADC_SampleTime_28Cycles5 ((uint8_t)0x03)
#define ADC_SampleTime_41Cycles5 ((uint8_t)0x04)
#define ADC_SampleTime_55Cycles5 ((uint8_t)0x05)
#define ADC_SampleTime_71Cycles5 ((uint8_t)0x06)
#define ADC_SampleTime_239Cycles5 ((uint8_t)0x07)
#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1Cycles5) || \
((TIME) == ADC_SampleTime_7Cycles5) || \
((TIME) == ADC_SampleTime_13Cycles5) || \
((TIME) == ADC_SampleTime_28Cycles5) || \
((TIME) == ADC_SampleTime_41Cycles5) || \
((TIME) == ADC_SampleTime_55Cycles5) || \
((TIME) == ADC_SampleTime_71Cycles5) || \
((TIME) == ADC_SampleTime_239Cycles5))
/**
* @}
*/
/** @defgroup ADC_external_trigger_sources_for_injected_channels_conversion
* @{
*/
#define ADC_ExternalTrigInjecConv_T2_TRGO ((uint32_t)0x00002000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigInjecConv_T2_CC1 ((uint32_t)0x00003000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigInjecConv_T3_CC4 ((uint32_t)0x00004000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigInjecConv_T4_TRGO ((uint32_t)0x00005000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4 ((uint32_t)0x00006000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigInjecConv_T1_TRGO ((uint32_t)0x00000000) /*!< For ADC1, ADC2 and ADC3 */
#define ADC_ExternalTrigInjecConv_T1_CC4 ((uint32_t)0x00001000) /*!< For ADC1, ADC2 and ADC3 */
#define ADC_ExternalTrigInjecConv_None ((uint32_t)0x00007000) /*!< For ADC1, ADC2 and ADC3 */
#define ADC_ExternalTrigInjecConv_T4_CC3 ((uint32_t)0x00002000) /*!< For ADC3 only */
#define ADC_ExternalTrigInjecConv_T8_CC2 ((uint32_t)0x00003000) /*!< For ADC3 only */
#define ADC_ExternalTrigInjecConv_T8_CC4 ((uint32_t)0x00004000) /*!< For ADC3 only */
#define ADC_ExternalTrigInjecConv_T5_TRGO ((uint32_t)0x00005000) /*!< For ADC3 only */
#define ADC_ExternalTrigInjecConv_T5_CC4 ((uint32_t)0x00006000) /*!< For ADC3 only */
#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_None) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4))
/**
* @}
*/
/** @defgroup ADC_injected_channel_selection
* @{
*/
#define ADC_InjectedChannel_1 ((uint8_t)0x14)
#define ADC_InjectedChannel_2 ((uint8_t)0x18)
#define ADC_InjectedChannel_3 ((uint8_t)0x1C)
#define ADC_InjectedChannel_4 ((uint8_t)0x20)
#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \
((CHANNEL) == ADC_InjectedChannel_2) || \
((CHANNEL) == ADC_InjectedChannel_3) || \
((CHANNEL) == ADC_InjectedChannel_4))
/**
* @}
*/
/** @defgroup ADC_analog_watchdog_selection
* @{
*/
#define ADC_AnalogWatchdog_SingleRegEnable ((uint32_t)0x00800200)
#define ADC_AnalogWatchdog_SingleInjecEnable ((uint32_t)0x00400200)
#define ADC_AnalogWatchdog_SingleRegOrInjecEnable ((uint32_t)0x00C00200)
#define ADC_AnalogWatchdog_AllRegEnable ((uint32_t)0x00800000)
#define ADC_AnalogWatchdog_AllInjecEnable ((uint32_t)0x00400000)
#define ADC_AnalogWatchdog_AllRegAllInjecEnable ((uint32_t)0x00C00000)
#define ADC_AnalogWatchdog_None ((uint32_t)0x00000000)
#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_None))
/**
* @}
*/
/** @defgroup ADC_interrupts_definition
* @{
*/
#define ADC_IT_EOC ((uint16_t)0x0220)
#define ADC_IT_AWD ((uint16_t)0x0140)
#define ADC_IT_JEOC ((uint16_t)0x0480)
#define IS_ADC_IT(IT) ((((IT) & (uint16_t)0xF81F) == 0x00) && ((IT) != 0x00))
#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \
((IT) == ADC_IT_JEOC))
/**
* @}
*/
/** @defgroup ADC_flags_definition
* @{
*/
#define ADC_FLAG_AWD ((uint8_t)0x01)
#define ADC_FLAG_EOC ((uint8_t)0x02)
#define ADC_FLAG_JEOC ((uint8_t)0x04)
#define ADC_FLAG_JSTRT ((uint8_t)0x08)
#define ADC_FLAG_STRT ((uint8_t)0x10)
#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint8_t)0xE0) == 0x00) && ((FLAG) != 0x00))
#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || ((FLAG) == ADC_FLAG_EOC) || \
((FLAG) == ADC_FLAG_JEOC) || ((FLAG)== ADC_FLAG_JSTRT) || \
((FLAG) == ADC_FLAG_STRT))
/**
* @}
*/
/** @defgroup ADC_thresholds
* @{
*/
#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF)
/**
* @}
*/
/** @defgroup ADC_injected_offset
* @{
*/
#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF)
/**
* @}
*/
/** @defgroup ADC_injected_length
* @{
*/
#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4))
/**
* @}
*/
/** @defgroup ADC_injected_rank
* @{
*/
#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4))
/**
* @}
*/
/** @defgroup ADC_regular_length
* @{
*/
#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10))
/**
* @}
*/
/** @defgroup ADC_regular_rank
* @{
*/
#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10))
/**
* @}
*/
/** @defgroup ADC_regular_discontinuous_mode_number
* @{
*/
#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8))
/**
* @}
*/
/**
* @}
*/
/** @defgroup ADC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup ADC_Exported_Functions
* @{
*/
void ADC_DeInit(ADC_TypeDef* ADCx);
void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct);
void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct);
void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState);
void ADC_ResetCalibration(ADC_TypeDef* ADCx);
FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx);
void ADC_StartCalibration(ADC_TypeDef* ADCx);
FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx);
void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx);
void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number);
void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime);
void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx);
uint32_t ADC_GetDualModeConversionValue(void);
void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv);
void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx);
void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime);
void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length);
void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset);
uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel);
void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog);
void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, uint16_t LowThreshold);
void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel);
void ADC_TempSensorVrefintCmd(FunctionalState NewState);
FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG);
void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG);
ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT);
void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT);
#ifdef __cplusplus
}
#endif
#endif /*__STM32F10x_ADC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Wyświetl plik

@ -0,0 +1,439 @@
/**
******************************************************************************
* @file stm32f10x_dma.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the DMA firmware
* library.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_DMA_H
#define __STM32F10x_DMA_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup DMA
* @{
*/
/** @defgroup DMA_Exported_Types
* @{
*/
/**
* @brief DMA Init structure definition
*/
typedef struct
{
uint32_t DMA_PeripheralBaseAddr; /*!< Specifies the peripheral base address for DMAy Channelx. */
uint32_t DMA_MemoryBaseAddr; /*!< Specifies the memory base address for DMAy Channelx. */
uint32_t DMA_DIR; /*!< Specifies if the peripheral is the source or destination.
This parameter can be a value of @ref DMA_data_transfer_direction */
uint32_t DMA_BufferSize; /*!< Specifies the buffer size, in data unit, of the specified Channel.
The data unit is equal to the configuration set in DMA_PeripheralDataSize
or DMA_MemoryDataSize members depending in the transfer direction. */
uint32_t DMA_PeripheralInc; /*!< Specifies whether the Peripheral address register is incremented or not.
This parameter can be a value of @ref DMA_peripheral_incremented_mode */
uint32_t DMA_MemoryInc; /*!< Specifies whether the memory address register is incremented or not.
This parameter can be a value of @ref DMA_memory_incremented_mode */
uint32_t DMA_PeripheralDataSize; /*!< Specifies the Peripheral data width.
This parameter can be a value of @ref DMA_peripheral_data_size */
uint32_t DMA_MemoryDataSize; /*!< Specifies the Memory data width.
This parameter can be a value of @ref DMA_memory_data_size */
uint32_t DMA_Mode; /*!< Specifies the operation mode of the DMAy Channelx.
This parameter can be a value of @ref DMA_circular_normal_mode.
@note: The circular buffer mode cannot be used if the memory-to-memory
data transfer is configured on the selected Channel */
uint32_t DMA_Priority; /*!< Specifies the software priority for the DMAy Channelx.
This parameter can be a value of @ref DMA_priority_level */
uint32_t DMA_M2M; /*!< Specifies if the DMAy Channelx will be used in memory-to-memory transfer.
This parameter can be a value of @ref DMA_memory_to_memory */
}DMA_InitTypeDef;
/**
* @}
*/
/** @defgroup DMA_Exported_Constants
* @{
*/
#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Channel1) || \
((PERIPH) == DMA1_Channel2) || \
((PERIPH) == DMA1_Channel3) || \
((PERIPH) == DMA1_Channel4) || \
((PERIPH) == DMA1_Channel5) || \
((PERIPH) == DMA1_Channel6) || \
((PERIPH) == DMA1_Channel7) || \
((PERIPH) == DMA2_Channel1) || \
((PERIPH) == DMA2_Channel2) || \
((PERIPH) == DMA2_Channel3) || \
((PERIPH) == DMA2_Channel4) || \
((PERIPH) == DMA2_Channel5))
/** @defgroup DMA_data_transfer_direction
* @{
*/
#define DMA_DIR_PeripheralDST ((uint32_t)0x00000010)
#define DMA_DIR_PeripheralSRC ((uint32_t)0x00000000)
#define IS_DMA_DIR(DIR) (((DIR) == DMA_DIR_PeripheralDST) || \
((DIR) == DMA_DIR_PeripheralSRC))
/**
* @}
*/
/** @defgroup DMA_peripheral_incremented_mode
* @{
*/
#define DMA_PeripheralInc_Enable ((uint32_t)0x00000040)
#define DMA_PeripheralInc_Disable ((uint32_t)0x00000000)
#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \
((STATE) == DMA_PeripheralInc_Disable))
/**
* @}
*/
/** @defgroup DMA_memory_incremented_mode
* @{
*/
#define DMA_MemoryInc_Enable ((uint32_t)0x00000080)
#define DMA_MemoryInc_Disable ((uint32_t)0x00000000)
#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \
((STATE) == DMA_MemoryInc_Disable))
/**
* @}
*/
/** @defgroup DMA_peripheral_data_size
* @{
*/
#define DMA_PeripheralDataSize_Byte ((uint32_t)0x00000000)
#define DMA_PeripheralDataSize_HalfWord ((uint32_t)0x00000100)
#define DMA_PeripheralDataSize_Word ((uint32_t)0x00000200)
#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \
((SIZE) == DMA_PeripheralDataSize_HalfWord) || \
((SIZE) == DMA_PeripheralDataSize_Word))
/**
* @}
*/
/** @defgroup DMA_memory_data_size
* @{
*/
#define DMA_MemoryDataSize_Byte ((uint32_t)0x00000000)
#define DMA_MemoryDataSize_HalfWord ((uint32_t)0x00000400)
#define DMA_MemoryDataSize_Word ((uint32_t)0x00000800)
#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \
((SIZE) == DMA_MemoryDataSize_HalfWord) || \
((SIZE) == DMA_MemoryDataSize_Word))
/**
* @}
*/
/** @defgroup DMA_circular_normal_mode
* @{
*/
#define DMA_Mode_Circular ((uint32_t)0x00000020)
#define DMA_Mode_Normal ((uint32_t)0x00000000)
#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Circular) || ((MODE) == DMA_Mode_Normal))
/**
* @}
*/
/** @defgroup DMA_priority_level
* @{
*/
#define DMA_Priority_VeryHigh ((uint32_t)0x00003000)
#define DMA_Priority_High ((uint32_t)0x00002000)
#define DMA_Priority_Medium ((uint32_t)0x00001000)
#define DMA_Priority_Low ((uint32_t)0x00000000)
#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_VeryHigh) || \
((PRIORITY) == DMA_Priority_High) || \
((PRIORITY) == DMA_Priority_Medium) || \
((PRIORITY) == DMA_Priority_Low))
/**
* @}
*/
/** @defgroup DMA_memory_to_memory
* @{
*/
#define DMA_M2M_Enable ((uint32_t)0x00004000)
#define DMA_M2M_Disable ((uint32_t)0x00000000)
#define IS_DMA_M2M_STATE(STATE) (((STATE) == DMA_M2M_Enable) || ((STATE) == DMA_M2M_Disable))
/**
* @}
*/
/** @defgroup DMA_interrupts_definition
* @{
*/
#define DMA_IT_TC ((uint32_t)0x00000002)
#define DMA_IT_HT ((uint32_t)0x00000004)
#define DMA_IT_TE ((uint32_t)0x00000008)
#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00))
#define DMA1_IT_GL1 ((uint32_t)0x00000001)
#define DMA1_IT_TC1 ((uint32_t)0x00000002)
#define DMA1_IT_HT1 ((uint32_t)0x00000004)
#define DMA1_IT_TE1 ((uint32_t)0x00000008)
#define DMA1_IT_GL2 ((uint32_t)0x00000010)
#define DMA1_IT_TC2 ((uint32_t)0x00000020)
#define DMA1_IT_HT2 ((uint32_t)0x00000040)
#define DMA1_IT_TE2 ((uint32_t)0x00000080)
#define DMA1_IT_GL3 ((uint32_t)0x00000100)
#define DMA1_IT_TC3 ((uint32_t)0x00000200)
#define DMA1_IT_HT3 ((uint32_t)0x00000400)
#define DMA1_IT_TE3 ((uint32_t)0x00000800)
#define DMA1_IT_GL4 ((uint32_t)0x00001000)
#define DMA1_IT_TC4 ((uint32_t)0x00002000)
#define DMA1_IT_HT4 ((uint32_t)0x00004000)
#define DMA1_IT_TE4 ((uint32_t)0x00008000)
#define DMA1_IT_GL5 ((uint32_t)0x00010000)
#define DMA1_IT_TC5 ((uint32_t)0x00020000)
#define DMA1_IT_HT5 ((uint32_t)0x00040000)
#define DMA1_IT_TE5 ((uint32_t)0x00080000)
#define DMA1_IT_GL6 ((uint32_t)0x00100000)
#define DMA1_IT_TC6 ((uint32_t)0x00200000)
#define DMA1_IT_HT6 ((uint32_t)0x00400000)
#define DMA1_IT_TE6 ((uint32_t)0x00800000)
#define DMA1_IT_GL7 ((uint32_t)0x01000000)
#define DMA1_IT_TC7 ((uint32_t)0x02000000)
#define DMA1_IT_HT7 ((uint32_t)0x04000000)
#define DMA1_IT_TE7 ((uint32_t)0x08000000)
#define DMA2_IT_GL1 ((uint32_t)0x10000001)
#define DMA2_IT_TC1 ((uint32_t)0x10000002)
#define DMA2_IT_HT1 ((uint32_t)0x10000004)
#define DMA2_IT_TE1 ((uint32_t)0x10000008)
#define DMA2_IT_GL2 ((uint32_t)0x10000010)
#define DMA2_IT_TC2 ((uint32_t)0x10000020)
#define DMA2_IT_HT2 ((uint32_t)0x10000040)
#define DMA2_IT_TE2 ((uint32_t)0x10000080)
#define DMA2_IT_GL3 ((uint32_t)0x10000100)
#define DMA2_IT_TC3 ((uint32_t)0x10000200)
#define DMA2_IT_HT3 ((uint32_t)0x10000400)
#define DMA2_IT_TE3 ((uint32_t)0x10000800)
#define DMA2_IT_GL4 ((uint32_t)0x10001000)
#define DMA2_IT_TC4 ((uint32_t)0x10002000)
#define DMA2_IT_HT4 ((uint32_t)0x10004000)
#define DMA2_IT_TE4 ((uint32_t)0x10008000)
#define DMA2_IT_GL5 ((uint32_t)0x10010000)
#define DMA2_IT_TC5 ((uint32_t)0x10020000)
#define DMA2_IT_HT5 ((uint32_t)0x10040000)
#define DMA2_IT_TE5 ((uint32_t)0x10080000)
#define IS_DMA_CLEAR_IT(IT) (((((IT) & 0xF0000000) == 0x00) || (((IT) & 0xEFF00000) == 0x00)) && ((IT) != 0x00))
#define IS_DMA_GET_IT(IT) (((IT) == DMA1_IT_GL1) || ((IT) == DMA1_IT_TC1) || \
((IT) == DMA1_IT_HT1) || ((IT) == DMA1_IT_TE1) || \
((IT) == DMA1_IT_GL2) || ((IT) == DMA1_IT_TC2) || \
((IT) == DMA1_IT_HT2) || ((IT) == DMA1_IT_TE2) || \
((IT) == DMA1_IT_GL3) || ((IT) == DMA1_IT_TC3) || \
((IT) == DMA1_IT_HT3) || ((IT) == DMA1_IT_TE3) || \
((IT) == DMA1_IT_GL4) || ((IT) == DMA1_IT_TC4) || \
((IT) == DMA1_IT_HT4) || ((IT) == DMA1_IT_TE4) || \
((IT) == DMA1_IT_GL5) || ((IT) == DMA1_IT_TC5) || \
((IT) == DMA1_IT_HT5) || ((IT) == DMA1_IT_TE5) || \
((IT) == DMA1_IT_GL6) || ((IT) == DMA1_IT_TC6) || \
((IT) == DMA1_IT_HT6) || ((IT) == DMA1_IT_TE6) || \
((IT) == DMA1_IT_GL7) || ((IT) == DMA1_IT_TC7) || \
((IT) == DMA1_IT_HT7) || ((IT) == DMA1_IT_TE7) || \
((IT) == DMA2_IT_GL1) || ((IT) == DMA2_IT_TC1) || \
((IT) == DMA2_IT_HT1) || ((IT) == DMA2_IT_TE1) || \
((IT) == DMA2_IT_GL2) || ((IT) == DMA2_IT_TC2) || \
((IT) == DMA2_IT_HT2) || ((IT) == DMA2_IT_TE2) || \
((IT) == DMA2_IT_GL3) || ((IT) == DMA2_IT_TC3) || \
((IT) == DMA2_IT_HT3) || ((IT) == DMA2_IT_TE3) || \
((IT) == DMA2_IT_GL4) || ((IT) == DMA2_IT_TC4) || \
((IT) == DMA2_IT_HT4) || ((IT) == DMA2_IT_TE4) || \
((IT) == DMA2_IT_GL5) || ((IT) == DMA2_IT_TC5) || \
((IT) == DMA2_IT_HT5) || ((IT) == DMA2_IT_TE5))
/**
* @}
*/
/** @defgroup DMA_flags_definition
* @{
*/
#define DMA1_FLAG_GL1 ((uint32_t)0x00000001)
#define DMA1_FLAG_TC1 ((uint32_t)0x00000002)
#define DMA1_FLAG_HT1 ((uint32_t)0x00000004)
#define DMA1_FLAG_TE1 ((uint32_t)0x00000008)
#define DMA1_FLAG_GL2 ((uint32_t)0x00000010)
#define DMA1_FLAG_TC2 ((uint32_t)0x00000020)
#define DMA1_FLAG_HT2 ((uint32_t)0x00000040)
#define DMA1_FLAG_TE2 ((uint32_t)0x00000080)
#define DMA1_FLAG_GL3 ((uint32_t)0x00000100)
#define DMA1_FLAG_TC3 ((uint32_t)0x00000200)
#define DMA1_FLAG_HT3 ((uint32_t)0x00000400)
#define DMA1_FLAG_TE3 ((uint32_t)0x00000800)
#define DMA1_FLAG_GL4 ((uint32_t)0x00001000)
#define DMA1_FLAG_TC4 ((uint32_t)0x00002000)
#define DMA1_FLAG_HT4 ((uint32_t)0x00004000)
#define DMA1_FLAG_TE4 ((uint32_t)0x00008000)
#define DMA1_FLAG_GL5 ((uint32_t)0x00010000)
#define DMA1_FLAG_TC5 ((uint32_t)0x00020000)
#define DMA1_FLAG_HT5 ((uint32_t)0x00040000)
#define DMA1_FLAG_TE5 ((uint32_t)0x00080000)
#define DMA1_FLAG_GL6 ((uint32_t)0x00100000)
#define DMA1_FLAG_TC6 ((uint32_t)0x00200000)
#define DMA1_FLAG_HT6 ((uint32_t)0x00400000)
#define DMA1_FLAG_TE6 ((uint32_t)0x00800000)
#define DMA1_FLAG_GL7 ((uint32_t)0x01000000)
#define DMA1_FLAG_TC7 ((uint32_t)0x02000000)
#define DMA1_FLAG_HT7 ((uint32_t)0x04000000)
#define DMA1_FLAG_TE7 ((uint32_t)0x08000000)
#define DMA2_FLAG_GL1 ((uint32_t)0x10000001)
#define DMA2_FLAG_TC1 ((uint32_t)0x10000002)
#define DMA2_FLAG_HT1 ((uint32_t)0x10000004)
#define DMA2_FLAG_TE1 ((uint32_t)0x10000008)
#define DMA2_FLAG_GL2 ((uint32_t)0x10000010)
#define DMA2_FLAG_TC2 ((uint32_t)0x10000020)
#define DMA2_FLAG_HT2 ((uint32_t)0x10000040)
#define DMA2_FLAG_TE2 ((uint32_t)0x10000080)
#define DMA2_FLAG_GL3 ((uint32_t)0x10000100)
#define DMA2_FLAG_TC3 ((uint32_t)0x10000200)
#define DMA2_FLAG_HT3 ((uint32_t)0x10000400)
#define DMA2_FLAG_TE3 ((uint32_t)0x10000800)
#define DMA2_FLAG_GL4 ((uint32_t)0x10001000)
#define DMA2_FLAG_TC4 ((uint32_t)0x10002000)
#define DMA2_FLAG_HT4 ((uint32_t)0x10004000)
#define DMA2_FLAG_TE4 ((uint32_t)0x10008000)
#define DMA2_FLAG_GL5 ((uint32_t)0x10010000)
#define DMA2_FLAG_TC5 ((uint32_t)0x10020000)
#define DMA2_FLAG_HT5 ((uint32_t)0x10040000)
#define DMA2_FLAG_TE5 ((uint32_t)0x10080000)
#define IS_DMA_CLEAR_FLAG(FLAG) (((((FLAG) & 0xF0000000) == 0x00) || (((FLAG) & 0xEFF00000) == 0x00)) && ((FLAG) != 0x00))
#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA1_FLAG_GL1) || ((FLAG) == DMA1_FLAG_TC1) || \
((FLAG) == DMA1_FLAG_HT1) || ((FLAG) == DMA1_FLAG_TE1) || \
((FLAG) == DMA1_FLAG_GL2) || ((FLAG) == DMA1_FLAG_TC2) || \
((FLAG) == DMA1_FLAG_HT2) || ((FLAG) == DMA1_FLAG_TE2) || \
((FLAG) == DMA1_FLAG_GL3) || ((FLAG) == DMA1_FLAG_TC3) || \
((FLAG) == DMA1_FLAG_HT3) || ((FLAG) == DMA1_FLAG_TE3) || \
((FLAG) == DMA1_FLAG_GL4) || ((FLAG) == DMA1_FLAG_TC4) || \
((FLAG) == DMA1_FLAG_HT4) || ((FLAG) == DMA1_FLAG_TE4) || \
((FLAG) == DMA1_FLAG_GL5) || ((FLAG) == DMA1_FLAG_TC5) || \
((FLAG) == DMA1_FLAG_HT5) || ((FLAG) == DMA1_FLAG_TE5) || \
((FLAG) == DMA1_FLAG_GL6) || ((FLAG) == DMA1_FLAG_TC6) || \
((FLAG) == DMA1_FLAG_HT6) || ((FLAG) == DMA1_FLAG_TE6) || \
((FLAG) == DMA1_FLAG_GL7) || ((FLAG) == DMA1_FLAG_TC7) || \
((FLAG) == DMA1_FLAG_HT7) || ((FLAG) == DMA1_FLAG_TE7) || \
((FLAG) == DMA2_FLAG_GL1) || ((FLAG) == DMA2_FLAG_TC1) || \
((FLAG) == DMA2_FLAG_HT1) || ((FLAG) == DMA2_FLAG_TE1) || \
((FLAG) == DMA2_FLAG_GL2) || ((FLAG) == DMA2_FLAG_TC2) || \
((FLAG) == DMA2_FLAG_HT2) || ((FLAG) == DMA2_FLAG_TE2) || \
((FLAG) == DMA2_FLAG_GL3) || ((FLAG) == DMA2_FLAG_TC3) || \
((FLAG) == DMA2_FLAG_HT3) || ((FLAG) == DMA2_FLAG_TE3) || \
((FLAG) == DMA2_FLAG_GL4) || ((FLAG) == DMA2_FLAG_TC4) || \
((FLAG) == DMA2_FLAG_HT4) || ((FLAG) == DMA2_FLAG_TE4) || \
((FLAG) == DMA2_FLAG_GL5) || ((FLAG) == DMA2_FLAG_TC5) || \
((FLAG) == DMA2_FLAG_HT5) || ((FLAG) == DMA2_FLAG_TE5))
/**
* @}
*/
/** @defgroup DMA_Buffer_Size
* @{
*/
#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000))
/**
* @}
*/
/**
* @}
*/
/** @defgroup DMA_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup DMA_Exported_Functions
* @{
*/
void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx);
void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct);
void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct);
void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState);
void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState);
void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber);
uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx);
FlagStatus DMA_GetFlagStatus(uint32_t DMAy_FLAG);
void DMA_ClearFlag(uint32_t DMAy_FLAG);
ITStatus DMA_GetITStatus(uint32_t DMAy_IT);
void DMA_ClearITPendingBit(uint32_t DMAy_IT);
#ifdef __cplusplus
}
#endif
#endif /*__STM32F10x_DMA_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Wyświetl plik

@ -0,0 +1,426 @@
/**
******************************************************************************
* @file stm32f10x_flash.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the FLASH
* firmware library.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_FLASH_H
#define __STM32F10x_FLASH_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup FLASH
* @{
*/
/** @defgroup FLASH_Exported_Types
* @{
*/
/**
* @brief FLASH Status
*/
typedef enum
{
FLASH_BUSY = 1,
FLASH_ERROR_PG,
FLASH_ERROR_WRP,
FLASH_COMPLETE,
FLASH_TIMEOUT
}FLASH_Status;
/**
* @}
*/
/** @defgroup FLASH_Exported_Constants
* @{
*/
/** @defgroup Flash_Latency
* @{
*/
#define FLASH_Latency_0 ((uint32_t)0x00000000) /*!< FLASH Zero Latency cycle */
#define FLASH_Latency_1 ((uint32_t)0x00000001) /*!< FLASH One Latency cycle */
#define FLASH_Latency_2 ((uint32_t)0x00000002) /*!< FLASH Two Latency cycles */
#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \
((LATENCY) == FLASH_Latency_1) || \
((LATENCY) == FLASH_Latency_2))
/**
* @}
*/
/** @defgroup Half_Cycle_Enable_Disable
* @{
*/
#define FLASH_HalfCycleAccess_Enable ((uint32_t)0x00000008) /*!< FLASH Half Cycle Enable */
#define FLASH_HalfCycleAccess_Disable ((uint32_t)0x00000000) /*!< FLASH Half Cycle Disable */
#define IS_FLASH_HALFCYCLEACCESS_STATE(STATE) (((STATE) == FLASH_HalfCycleAccess_Enable) || \
((STATE) == FLASH_HalfCycleAccess_Disable))
/**
* @}
*/
/** @defgroup Prefetch_Buffer_Enable_Disable
* @{
*/
#define FLASH_PrefetchBuffer_Enable ((uint32_t)0x00000010) /*!< FLASH Prefetch Buffer Enable */
#define FLASH_PrefetchBuffer_Disable ((uint32_t)0x00000000) /*!< FLASH Prefetch Buffer Disable */
#define IS_FLASH_PREFETCHBUFFER_STATE(STATE) (((STATE) == FLASH_PrefetchBuffer_Enable) || \
((STATE) == FLASH_PrefetchBuffer_Disable))
/**
* @}
*/
/** @defgroup Option_Bytes_Write_Protection
* @{
*/
/* Values to be used with STM32 Low and Medium density devices */
#define FLASH_WRProt_Pages0to3 ((uint32_t)0x00000001) /*!< STM32 Low and Medium density devices: Write protection of page 0 to 3 */
#define FLASH_WRProt_Pages4to7 ((uint32_t)0x00000002) /*!< STM32 Low and Medium density devices: Write protection of page 4 to 7 */
#define FLASH_WRProt_Pages8to11 ((uint32_t)0x00000004) /*!< STM32 Low and Medium density devices: Write protection of page 8 to 11 */
#define FLASH_WRProt_Pages12to15 ((uint32_t)0x00000008) /*!< STM32 Low and Medium density devices: Write protection of page 12 to 15 */
#define FLASH_WRProt_Pages16to19 ((uint32_t)0x00000010) /*!< STM32 Low and Medium density devices: Write protection of page 16 to 19 */
#define FLASH_WRProt_Pages20to23 ((uint32_t)0x00000020) /*!< STM32 Low and Medium density devices: Write protection of page 20 to 23 */
#define FLASH_WRProt_Pages24to27 ((uint32_t)0x00000040) /*!< STM32 Low and Medium density devices: Write protection of page 24 to 27 */
#define FLASH_WRProt_Pages28to31 ((uint32_t)0x00000080) /*!< STM32 Low and Medium density devices: Write protection of page 28 to 31 */
/* Values to be used with STM32 Medium-density devices */
#define FLASH_WRProt_Pages32to35 ((uint32_t)0x00000100) /*!< STM32 Medium-density devices: Write protection of page 32 to 35 */
#define FLASH_WRProt_Pages36to39 ((uint32_t)0x00000200) /*!< STM32 Medium-density devices: Write protection of page 36 to 39 */
#define FLASH_WRProt_Pages40to43 ((uint32_t)0x00000400) /*!< STM32 Medium-density devices: Write protection of page 40 to 43 */
#define FLASH_WRProt_Pages44to47 ((uint32_t)0x00000800) /*!< STM32 Medium-density devices: Write protection of page 44 to 47 */
#define FLASH_WRProt_Pages48to51 ((uint32_t)0x00001000) /*!< STM32 Medium-density devices: Write protection of page 48 to 51 */
#define FLASH_WRProt_Pages52to55 ((uint32_t)0x00002000) /*!< STM32 Medium-density devices: Write protection of page 52 to 55 */
#define FLASH_WRProt_Pages56to59 ((uint32_t)0x00004000) /*!< STM32 Medium-density devices: Write protection of page 56 to 59 */
#define FLASH_WRProt_Pages60to63 ((uint32_t)0x00008000) /*!< STM32 Medium-density devices: Write protection of page 60 to 63 */
#define FLASH_WRProt_Pages64to67 ((uint32_t)0x00010000) /*!< STM32 Medium-density devices: Write protection of page 64 to 67 */
#define FLASH_WRProt_Pages68to71 ((uint32_t)0x00020000) /*!< STM32 Medium-density devices: Write protection of page 68 to 71 */
#define FLASH_WRProt_Pages72to75 ((uint32_t)0x00040000) /*!< STM32 Medium-density devices: Write protection of page 72 to 75 */
#define FLASH_WRProt_Pages76to79 ((uint32_t)0x00080000) /*!< STM32 Medium-density devices: Write protection of page 76 to 79 */
#define FLASH_WRProt_Pages80to83 ((uint32_t)0x00100000) /*!< STM32 Medium-density devices: Write protection of page 80 to 83 */
#define FLASH_WRProt_Pages84to87 ((uint32_t)0x00200000) /*!< STM32 Medium-density devices: Write protection of page 84 to 87 */
#define FLASH_WRProt_Pages88to91 ((uint32_t)0x00400000) /*!< STM32 Medium-density devices: Write protection of page 88 to 91 */
#define FLASH_WRProt_Pages92to95 ((uint32_t)0x00800000) /*!< STM32 Medium-density devices: Write protection of page 92 to 95 */
#define FLASH_WRProt_Pages96to99 ((uint32_t)0x01000000) /*!< STM32 Medium-density devices: Write protection of page 96 to 99 */
#define FLASH_WRProt_Pages100to103 ((uint32_t)0x02000000) /*!< STM32 Medium-density devices: Write protection of page 100 to 103 */
#define FLASH_WRProt_Pages104to107 ((uint32_t)0x04000000) /*!< STM32 Medium-density devices: Write protection of page 104 to 107 */
#define FLASH_WRProt_Pages108to111 ((uint32_t)0x08000000) /*!< STM32 Medium-density devices: Write protection of page 108 to 111 */
#define FLASH_WRProt_Pages112to115 ((uint32_t)0x10000000) /*!< STM32 Medium-density devices: Write protection of page 112 to 115 */
#define FLASH_WRProt_Pages116to119 ((uint32_t)0x20000000) /*!< STM32 Medium-density devices: Write protection of page 115 to 119 */
#define FLASH_WRProt_Pages120to123 ((uint32_t)0x40000000) /*!< STM32 Medium-density devices: Write protection of page 120 to 123 */
#define FLASH_WRProt_Pages124to127 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 124 to 127 */
/* Values to be used with STM32 High-density and STM32F10X Connectivity line devices */
#define FLASH_WRProt_Pages0to1 ((uint32_t)0x00000001) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 0 to 1 */
#define FLASH_WRProt_Pages2to3 ((uint32_t)0x00000002) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 2 to 3 */
#define FLASH_WRProt_Pages4to5 ((uint32_t)0x00000004) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 4 to 5 */
#define FLASH_WRProt_Pages6to7 ((uint32_t)0x00000008) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 6 to 7 */
#define FLASH_WRProt_Pages8to9 ((uint32_t)0x00000010) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 8 to 9 */
#define FLASH_WRProt_Pages10to11 ((uint32_t)0x00000020) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 10 to 11 */
#define FLASH_WRProt_Pages12to13 ((uint32_t)0x00000040) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 12 to 13 */
#define FLASH_WRProt_Pages14to15 ((uint32_t)0x00000080) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 14 to 15 */
#define FLASH_WRProt_Pages16to17 ((uint32_t)0x00000100) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 16 to 17 */
#define FLASH_WRProt_Pages18to19 ((uint32_t)0x00000200) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 18 to 19 */
#define FLASH_WRProt_Pages20to21 ((uint32_t)0x00000400) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 20 to 21 */
#define FLASH_WRProt_Pages22to23 ((uint32_t)0x00000800) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 22 to 23 */
#define FLASH_WRProt_Pages24to25 ((uint32_t)0x00001000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 24 to 25 */
#define FLASH_WRProt_Pages26to27 ((uint32_t)0x00002000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 26 to 27 */
#define FLASH_WRProt_Pages28to29 ((uint32_t)0x00004000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 28 to 29 */
#define FLASH_WRProt_Pages30to31 ((uint32_t)0x00008000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 30 to 31 */
#define FLASH_WRProt_Pages32to33 ((uint32_t)0x00010000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 32 to 33 */
#define FLASH_WRProt_Pages34to35 ((uint32_t)0x00020000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 34 to 35 */
#define FLASH_WRProt_Pages36to37 ((uint32_t)0x00040000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 36 to 37 */
#define FLASH_WRProt_Pages38to39 ((uint32_t)0x00080000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 38 to 39 */
#define FLASH_WRProt_Pages40to41 ((uint32_t)0x00100000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 40 to 41 */
#define FLASH_WRProt_Pages42to43 ((uint32_t)0x00200000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 42 to 43 */
#define FLASH_WRProt_Pages44to45 ((uint32_t)0x00400000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 44 to 45 */
#define FLASH_WRProt_Pages46to47 ((uint32_t)0x00800000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 46 to 47 */
#define FLASH_WRProt_Pages48to49 ((uint32_t)0x01000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 48 to 49 */
#define FLASH_WRProt_Pages50to51 ((uint32_t)0x02000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 50 to 51 */
#define FLASH_WRProt_Pages52to53 ((uint32_t)0x04000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 52 to 53 */
#define FLASH_WRProt_Pages54to55 ((uint32_t)0x08000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 54 to 55 */
#define FLASH_WRProt_Pages56to57 ((uint32_t)0x10000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 56 to 57 */
#define FLASH_WRProt_Pages58to59 ((uint32_t)0x20000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 58 to 59 */
#define FLASH_WRProt_Pages60to61 ((uint32_t)0x40000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 60 to 61 */
#define FLASH_WRProt_Pages62to127 ((uint32_t)0x80000000) /*!< STM32 Connectivity line devices: Write protection of page 62 to 127 */
#define FLASH_WRProt_Pages62to255 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 62 to 255 */
#define FLASH_WRProt_Pages62to511 ((uint32_t)0x80000000) /*!< STM32 XL-density devices: Write protection of page 62 to 511 */
#define FLASH_WRProt_AllPages ((uint32_t)0xFFFFFFFF) /*!< Write protection of all Pages */
#define IS_FLASH_WRPROT_PAGE(PAGE) (((PAGE) != 0x00000000))
#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF))
#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == 0x1FFFF804) || ((ADDRESS) == 0x1FFFF806))
/**
* @}
*/
/** @defgroup Option_Bytes_IWatchdog
* @{
*/
#define OB_IWDG_SW ((uint16_t)0x0001) /*!< Software IWDG selected */
#define OB_IWDG_HW ((uint16_t)0x0000) /*!< Hardware IWDG selected */
#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW))
/**
* @}
*/
/** @defgroup Option_Bytes_nRST_STOP
* @{
*/
#define OB_STOP_NoRST ((uint16_t)0x0002) /*!< No reset generated when entering in STOP */
#define OB_STOP_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STOP */
#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST))
/**
* @}
*/
/** @defgroup Option_Bytes_nRST_STDBY
* @{
*/
#define OB_STDBY_NoRST ((uint16_t)0x0004) /*!< No reset generated when entering in STANDBY */
#define OB_STDBY_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STANDBY */
#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST))
#ifdef STM32F10X_XL
/**
* @}
*/
/** @defgroup FLASH_Boot
* @{
*/
#define FLASH_BOOT_Bank1 ((uint16_t)0x0000) /*!< At startup, if boot pins are set in boot from user Flash position
and this parameter is selected the device will boot from Bank1(Default) */
#define FLASH_BOOT_Bank2 ((uint16_t)0x0001) /*!< At startup, if boot pins are set in boot from user Flash position
and this parameter is selected the device will boot from Bank 2 or Bank 1,
depending on the activation of the bank */
#define IS_FLASH_BOOT(BOOT) (((BOOT) == FLASH_BOOT_Bank1) || ((BOOT) == FLASH_BOOT_Bank2))
#endif
/**
* @}
*/
/** @defgroup FLASH_Interrupts
* @{
*/
#ifdef STM32F10X_XL
#define FLASH_IT_BANK2_ERROR ((uint32_t)0x80000400) /*!< FPEC BANK2 error interrupt source */
#define FLASH_IT_BANK2_EOP ((uint32_t)0x80001000) /*!< End of FLASH BANK2 Operation Interrupt source */
#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */
#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */
#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC BANK1 error interrupt source */
#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH BANK1 Operation Interrupt source */
#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0x7FFFEBFF) == 0x00000000) && (((IT) != 0x00000000)))
#else
#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC error interrupt source */
#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH Operation Interrupt source */
#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */
#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */
#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFFFFEBFF) == 0x00000000) && (((IT) != 0x00000000)))
#endif
/**
* @}
*/
/** @defgroup FLASH_Flags
* @{
*/
#ifdef STM32F10X_XL
#define FLASH_FLAG_BANK2_BSY ((uint32_t)0x80000001) /*!< FLASH BANK2 Busy flag */
#define FLASH_FLAG_BANK2_EOP ((uint32_t)0x80000020) /*!< FLASH BANK2 End of Operation flag */
#define FLASH_FLAG_BANK2_PGERR ((uint32_t)0x80000004) /*!< FLASH BANK2 Program error flag */
#define FLASH_FLAG_BANK2_WRPRTERR ((uint32_t)0x80000010) /*!< FLASH BANK2 Write protected error flag */
#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/
#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */
#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */
#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */
#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */
#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */
#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */
#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */
#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */
#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0x7FFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000))
#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \
((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \
((FLAG) == FLASH_FLAG_OPTERR)|| \
((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \
((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \
((FLAG) == FLASH_FLAG_BANK2_BSY) || ((FLAG) == FLASH_FLAG_BANK2_EOP) || \
((FLAG) == FLASH_FLAG_BANK2_PGERR) || ((FLAG) == FLASH_FLAG_BANK2_WRPRTERR))
#else
#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */
#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */
#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */
#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */
#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */
#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/
#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */
#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */
#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */
#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000))
#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \
((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \
((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \
((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \
((FLAG) == FLASH_FLAG_OPTERR))
#endif
/**
* @}
*/
/**
* @}
*/
/** @defgroup FLASH_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup FLASH_Exported_Functions
* @{
*/
/*------------ Functions used for all STM32F10x devices -----*/
void FLASH_SetLatency(uint32_t FLASH_Latency);
void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess);
void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer);
void FLASH_Unlock(void);
void FLASH_Lock(void);
FLASH_Status FLASH_ErasePage(uint32_t Page_Address);
FLASH_Status FLASH_EraseAllPages(void);
FLASH_Status FLASH_EraseOptionBytes(void);
FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data);
FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data);
FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data);
FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages);
FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState);
FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY);
uint32_t FLASH_GetUserOptionByte(void);
uint32_t FLASH_GetWriteProtectionOptionByte(void);
FlagStatus FLASH_GetReadOutProtectionStatus(void);
FlagStatus FLASH_GetPrefetchBufferStatus(void);
void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState);
FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG);
void FLASH_ClearFlag(uint32_t FLASH_FLAG);
FLASH_Status FLASH_GetStatus(void);
FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout);
/*------------ New function used for all STM32F10x devices -----*/
void FLASH_UnlockBank1(void);
void FLASH_LockBank1(void);
FLASH_Status FLASH_EraseAllBank1Pages(void);
FLASH_Status FLASH_GetBank1Status(void);
FLASH_Status FLASH_WaitForLastBank1Operation(uint32_t Timeout);
#ifdef STM32F10X_XL
/*---- New Functions used only with STM32F10x_XL density devices -----*/
void FLASH_UnlockBank2(void);
void FLASH_LockBank2(void);
FLASH_Status FLASH_EraseAllBank2Pages(void);
FLASH_Status FLASH_GetBank2Status(void);
FLASH_Status FLASH_WaitForLastBank2Operation(uint32_t Timeout);
FLASH_Status FLASH_BootConfig(uint16_t FLASH_BOOT);
#endif
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_FLASH_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Wyświetl plik

@ -0,0 +1,385 @@
/**
******************************************************************************
* @file stm32f10x_gpio.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the GPIO
* firmware library.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_GPIO_H
#define __STM32F10x_GPIO_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup GPIO
* @{
*/
/** @defgroup GPIO_Exported_Types
* @{
*/
#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \
((PERIPH) == GPIOB) || \
((PERIPH) == GPIOC) || \
((PERIPH) == GPIOD) || \
((PERIPH) == GPIOE) || \
((PERIPH) == GPIOF) || \
((PERIPH) == GPIOG))
/**
* @brief Output Maximum frequency selection
*/
typedef enum
{
GPIO_Speed_10MHz = 1,
GPIO_Speed_2MHz,
GPIO_Speed_50MHz
}GPIOSpeed_TypeDef;
#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_10MHz) || ((SPEED) == GPIO_Speed_2MHz) || \
((SPEED) == GPIO_Speed_50MHz))
/**
* @brief Configuration Mode enumeration
*/
typedef enum
{ GPIO_Mode_AIN = 0x0,
GPIO_Mode_IN_FLOATING = 0x04,
GPIO_Mode_IPD = 0x28,
GPIO_Mode_IPU = 0x48,
GPIO_Mode_Out_OD = 0x14,
GPIO_Mode_Out_PP = 0x10,
GPIO_Mode_AF_OD = 0x1C,
GPIO_Mode_AF_PP = 0x18
}GPIOMode_TypeDef;
#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_AIN) || ((MODE) == GPIO_Mode_IN_FLOATING) || \
((MODE) == GPIO_Mode_IPD) || ((MODE) == GPIO_Mode_IPU) || \
((MODE) == GPIO_Mode_Out_OD) || ((MODE) == GPIO_Mode_Out_PP) || \
((MODE) == GPIO_Mode_AF_OD) || ((MODE) == GPIO_Mode_AF_PP))
/**
* @brief GPIO Init structure definition
*/
typedef struct
{
uint16_t GPIO_Pin; /*!< Specifies the GPIO pins to be configured.
This parameter can be any value of @ref GPIO_pins_define */
GPIOSpeed_TypeDef GPIO_Speed; /*!< Specifies the speed for the selected pins.
This parameter can be a value of @ref GPIOSpeed_TypeDef */
GPIOMode_TypeDef GPIO_Mode; /*!< Specifies the operating mode for the selected pins.
This parameter can be a value of @ref GPIOMode_TypeDef */
}GPIO_InitTypeDef;
/**
* @brief Bit_SET and Bit_RESET enumeration
*/
typedef enum
{ Bit_RESET = 0,
Bit_SET
}BitAction;
#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET))
/**
* @}
*/
/** @defgroup GPIO_Exported_Constants
* @{
*/
/** @defgroup GPIO_pins_define
* @{
*/
#define GPIO_Pin_0 ((uint16_t)0x0001) /*!< Pin 0 selected */
#define GPIO_Pin_1 ((uint16_t)0x0002) /*!< Pin 1 selected */
#define GPIO_Pin_2 ((uint16_t)0x0004) /*!< Pin 2 selected */
#define GPIO_Pin_3 ((uint16_t)0x0008) /*!< Pin 3 selected */
#define GPIO_Pin_4 ((uint16_t)0x0010) /*!< Pin 4 selected */
#define GPIO_Pin_5 ((uint16_t)0x0020) /*!< Pin 5 selected */
#define GPIO_Pin_6 ((uint16_t)0x0040) /*!< Pin 6 selected */
#define GPIO_Pin_7 ((uint16_t)0x0080) /*!< Pin 7 selected */
#define GPIO_Pin_8 ((uint16_t)0x0100) /*!< Pin 8 selected */
#define GPIO_Pin_9 ((uint16_t)0x0200) /*!< Pin 9 selected */
#define GPIO_Pin_10 ((uint16_t)0x0400) /*!< Pin 10 selected */
#define GPIO_Pin_11 ((uint16_t)0x0800) /*!< Pin 11 selected */
#define GPIO_Pin_12 ((uint16_t)0x1000) /*!< Pin 12 selected */
#define GPIO_Pin_13 ((uint16_t)0x2000) /*!< Pin 13 selected */
#define GPIO_Pin_14 ((uint16_t)0x4000) /*!< Pin 14 selected */
#define GPIO_Pin_15 ((uint16_t)0x8000) /*!< Pin 15 selected */
#define GPIO_Pin_All ((uint16_t)0xFFFF) /*!< All pins selected */
#define IS_GPIO_PIN(PIN) ((((PIN) & (uint16_t)0x00) == 0x00) && ((PIN) != (uint16_t)0x00))
#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \
((PIN) == GPIO_Pin_1) || \
((PIN) == GPIO_Pin_2) || \
((PIN) == GPIO_Pin_3) || \
((PIN) == GPIO_Pin_4) || \
((PIN) == GPIO_Pin_5) || \
((PIN) == GPIO_Pin_6) || \
((PIN) == GPIO_Pin_7) || \
((PIN) == GPIO_Pin_8) || \
((PIN) == GPIO_Pin_9) || \
((PIN) == GPIO_Pin_10) || \
((PIN) == GPIO_Pin_11) || \
((PIN) == GPIO_Pin_12) || \
((PIN) == GPIO_Pin_13) || \
((PIN) == GPIO_Pin_14) || \
((PIN) == GPIO_Pin_15))
/**
* @}
*/
/** @defgroup GPIO_Remap_define
* @{
*/
#define GPIO_Remap_SPI1 ((uint32_t)0x00000001) /*!< SPI1 Alternate Function mapping */
#define GPIO_Remap_I2C1 ((uint32_t)0x00000002) /*!< I2C1 Alternate Function mapping */
#define GPIO_Remap_USART1 ((uint32_t)0x00000004) /*!< USART1 Alternate Function mapping */
#define GPIO_Remap_USART2 ((uint32_t)0x00000008) /*!< USART2 Alternate Function mapping */
#define GPIO_PartialRemap_USART3 ((uint32_t)0x00140010) /*!< USART3 Partial Alternate Function mapping */
#define GPIO_FullRemap_USART3 ((uint32_t)0x00140030) /*!< USART3 Full Alternate Function mapping */
#define GPIO_PartialRemap_TIM1 ((uint32_t)0x00160040) /*!< TIM1 Partial Alternate Function mapping */
#define GPIO_FullRemap_TIM1 ((uint32_t)0x001600C0) /*!< TIM1 Full Alternate Function mapping */
#define GPIO_PartialRemap1_TIM2 ((uint32_t)0x00180100) /*!< TIM2 Partial1 Alternate Function mapping */
#define GPIO_PartialRemap2_TIM2 ((uint32_t)0x00180200) /*!< TIM2 Partial2 Alternate Function mapping */
#define GPIO_FullRemap_TIM2 ((uint32_t)0x00180300) /*!< TIM2 Full Alternate Function mapping */
#define GPIO_PartialRemap_TIM3 ((uint32_t)0x001A0800) /*!< TIM3 Partial Alternate Function mapping */
#define GPIO_FullRemap_TIM3 ((uint32_t)0x001A0C00) /*!< TIM3 Full Alternate Function mapping */
#define GPIO_Remap_TIM4 ((uint32_t)0x00001000) /*!< TIM4 Alternate Function mapping */
#define GPIO_Remap1_CAN1 ((uint32_t)0x001D4000) /*!< CAN1 Alternate Function mapping */
#define GPIO_Remap2_CAN1 ((uint32_t)0x001D6000) /*!< CAN1 Alternate Function mapping */
#define GPIO_Remap_PD01 ((uint32_t)0x00008000) /*!< PD01 Alternate Function mapping */
#define GPIO_Remap_TIM5CH4_LSI ((uint32_t)0x00200001) /*!< LSI connected to TIM5 Channel4 input capture for calibration */
#define GPIO_Remap_ADC1_ETRGINJ ((uint32_t)0x00200002) /*!< ADC1 External Trigger Injected Conversion remapping */
#define GPIO_Remap_ADC1_ETRGREG ((uint32_t)0x00200004) /*!< ADC1 External Trigger Regular Conversion remapping */
#define GPIO_Remap_ADC2_ETRGINJ ((uint32_t)0x00200008) /*!< ADC2 External Trigger Injected Conversion remapping */
#define GPIO_Remap_ADC2_ETRGREG ((uint32_t)0x00200010) /*!< ADC2 External Trigger Regular Conversion remapping */
#define GPIO_Remap_ETH ((uint32_t)0x00200020) /*!< Ethernet remapping (only for Connectivity line devices) */
#define GPIO_Remap_CAN2 ((uint32_t)0x00200040) /*!< CAN2 remapping (only for Connectivity line devices) */
#define GPIO_Remap_SWJ_NoJTRST ((uint32_t)0x00300100) /*!< Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST */
#define GPIO_Remap_SWJ_JTAGDisable ((uint32_t)0x00300200) /*!< JTAG-DP Disabled and SW-DP Enabled */
#define GPIO_Remap_SWJ_Disable ((uint32_t)0x00300400) /*!< Full SWJ Disabled (JTAG-DP + SW-DP) */
#define GPIO_Remap_SPI3 ((uint32_t)0x00201100) /*!< SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices) */
#define GPIO_Remap_TIM2ITR1_PTP_SOF ((uint32_t)0x00202000) /*!< Ethernet PTP output or USB OTG SOF (Start of Frame) connected
to TIM2 Internal Trigger 1 for calibration
(only for Connectivity line devices) */
#define GPIO_Remap_PTP_PPS ((uint32_t)0x00204000) /*!< Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) */
#define GPIO_Remap_TIM15 ((uint32_t)0x80000001) /*!< TIM15 Alternate Function mapping (only for Value line devices) */
#define GPIO_Remap_TIM16 ((uint32_t)0x80000002) /*!< TIM16 Alternate Function mapping (only for Value line devices) */
#define GPIO_Remap_TIM17 ((uint32_t)0x80000004) /*!< TIM17 Alternate Function mapping (only for Value line devices) */
#define GPIO_Remap_CEC ((uint32_t)0x80000008) /*!< CEC Alternate Function mapping (only for Value line devices) */
#define GPIO_Remap_TIM1_DMA ((uint32_t)0x80000010) /*!< TIM1 DMA requests mapping (only for Value line devices) */
#define GPIO_Remap_TIM9 ((uint32_t)0x80000020) /*!< TIM9 Alternate Function mapping (only for XL-density devices) */
#define GPIO_Remap_TIM10 ((uint32_t)0x80000040) /*!< TIM10 Alternate Function mapping (only for XL-density devices) */
#define GPIO_Remap_TIM11 ((uint32_t)0x80000080) /*!< TIM11 Alternate Function mapping (only for XL-density devices) */
#define GPIO_Remap_TIM13 ((uint32_t)0x80000100) /*!< TIM13 Alternate Function mapping (only for High density Value line and XL-density devices) */
#define GPIO_Remap_TIM14 ((uint32_t)0x80000200) /*!< TIM14 Alternate Function mapping (only for High density Value line and XL-density devices) */
#define GPIO_Remap_FSMC_NADV ((uint32_t)0x80000400) /*!< FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices) */
#define GPIO_Remap_TIM67_DAC_DMA ((uint32_t)0x80000800) /*!< TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices) */
#define GPIO_Remap_TIM12 ((uint32_t)0x80001000) /*!< TIM12 Alternate Function mapping (only for High density Value line devices) */
#define GPIO_Remap_MISC ((uint32_t)0x80002000) /*!< Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping,
only for High density Value line devices) */
#define IS_GPIO_REMAP(REMAP) (((REMAP) == GPIO_Remap_SPI1) || ((REMAP) == GPIO_Remap_I2C1) || \
((REMAP) == GPIO_Remap_USART1) || ((REMAP) == GPIO_Remap_USART2) || \
((REMAP) == GPIO_PartialRemap_USART3) || ((REMAP) == GPIO_FullRemap_USART3) || \
((REMAP) == GPIO_PartialRemap_TIM1) || ((REMAP) == GPIO_FullRemap_TIM1) || \
((REMAP) == GPIO_PartialRemap1_TIM2) || ((REMAP) == GPIO_PartialRemap2_TIM2) || \
((REMAP) == GPIO_FullRemap_TIM2) || ((REMAP) == GPIO_PartialRemap_TIM3) || \
((REMAP) == GPIO_FullRemap_TIM3) || ((REMAP) == GPIO_Remap_TIM4) || \
((REMAP) == GPIO_Remap1_CAN1) || ((REMAP) == GPIO_Remap2_CAN1) || \
((REMAP) == GPIO_Remap_PD01) || ((REMAP) == GPIO_Remap_TIM5CH4_LSI) || \
((REMAP) == GPIO_Remap_ADC1_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC1_ETRGREG) || \
((REMAP) == GPIO_Remap_ADC2_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC2_ETRGREG) || \
((REMAP) == GPIO_Remap_ETH) ||((REMAP) == GPIO_Remap_CAN2) || \
((REMAP) == GPIO_Remap_SWJ_NoJTRST) || ((REMAP) == GPIO_Remap_SWJ_JTAGDisable) || \
((REMAP) == GPIO_Remap_SWJ_Disable)|| ((REMAP) == GPIO_Remap_SPI3) || \
((REMAP) == GPIO_Remap_TIM2ITR1_PTP_SOF) || ((REMAP) == GPIO_Remap_PTP_PPS) || \
((REMAP) == GPIO_Remap_TIM15) || ((REMAP) == GPIO_Remap_TIM16) || \
((REMAP) == GPIO_Remap_TIM17) || ((REMAP) == GPIO_Remap_CEC) || \
((REMAP) == GPIO_Remap_TIM1_DMA) || ((REMAP) == GPIO_Remap_TIM9) || \
((REMAP) == GPIO_Remap_TIM10) || ((REMAP) == GPIO_Remap_TIM11) || \
((REMAP) == GPIO_Remap_TIM13) || ((REMAP) == GPIO_Remap_TIM14) || \
((REMAP) == GPIO_Remap_FSMC_NADV) || ((REMAP) == GPIO_Remap_TIM67_DAC_DMA) || \
((REMAP) == GPIO_Remap_TIM12) || ((REMAP) == GPIO_Remap_MISC))
/**
* @}
*/
/** @defgroup GPIO_Port_Sources
* @{
*/
#define GPIO_PortSourceGPIOA ((uint8_t)0x00)
#define GPIO_PortSourceGPIOB ((uint8_t)0x01)
#define GPIO_PortSourceGPIOC ((uint8_t)0x02)
#define GPIO_PortSourceGPIOD ((uint8_t)0x03)
#define GPIO_PortSourceGPIOE ((uint8_t)0x04)
#define GPIO_PortSourceGPIOF ((uint8_t)0x05)
#define GPIO_PortSourceGPIOG ((uint8_t)0x06)
#define IS_GPIO_EVENTOUT_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \
((PORTSOURCE) == GPIO_PortSourceGPIOB) || \
((PORTSOURCE) == GPIO_PortSourceGPIOC) || \
((PORTSOURCE) == GPIO_PortSourceGPIOD) || \
((PORTSOURCE) == GPIO_PortSourceGPIOE))
#define IS_GPIO_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \
((PORTSOURCE) == GPIO_PortSourceGPIOB) || \
((PORTSOURCE) == GPIO_PortSourceGPIOC) || \
((PORTSOURCE) == GPIO_PortSourceGPIOD) || \
((PORTSOURCE) == GPIO_PortSourceGPIOE) || \
((PORTSOURCE) == GPIO_PortSourceGPIOF) || \
((PORTSOURCE) == GPIO_PortSourceGPIOG))
/**
* @}
*/
/** @defgroup GPIO_Pin_sources
* @{
*/
#define GPIO_PinSource0 ((uint8_t)0x00)
#define GPIO_PinSource1 ((uint8_t)0x01)
#define GPIO_PinSource2 ((uint8_t)0x02)
#define GPIO_PinSource3 ((uint8_t)0x03)
#define GPIO_PinSource4 ((uint8_t)0x04)
#define GPIO_PinSource5 ((uint8_t)0x05)
#define GPIO_PinSource6 ((uint8_t)0x06)
#define GPIO_PinSource7 ((uint8_t)0x07)
#define GPIO_PinSource8 ((uint8_t)0x08)
#define GPIO_PinSource9 ((uint8_t)0x09)
#define GPIO_PinSource10 ((uint8_t)0x0A)
#define GPIO_PinSource11 ((uint8_t)0x0B)
#define GPIO_PinSource12 ((uint8_t)0x0C)
#define GPIO_PinSource13 ((uint8_t)0x0D)
#define GPIO_PinSource14 ((uint8_t)0x0E)
#define GPIO_PinSource15 ((uint8_t)0x0F)
#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \
((PINSOURCE) == GPIO_PinSource1) || \
((PINSOURCE) == GPIO_PinSource2) || \
((PINSOURCE) == GPIO_PinSource3) || \
((PINSOURCE) == GPIO_PinSource4) || \
((PINSOURCE) == GPIO_PinSource5) || \
((PINSOURCE) == GPIO_PinSource6) || \
((PINSOURCE) == GPIO_PinSource7) || \
((PINSOURCE) == GPIO_PinSource8) || \
((PINSOURCE) == GPIO_PinSource9) || \
((PINSOURCE) == GPIO_PinSource10) || \
((PINSOURCE) == GPIO_PinSource11) || \
((PINSOURCE) == GPIO_PinSource12) || \
((PINSOURCE) == GPIO_PinSource13) || \
((PINSOURCE) == GPIO_PinSource14) || \
((PINSOURCE) == GPIO_PinSource15))
/**
* @}
*/
/** @defgroup Ethernet_Media_Interface
* @{
*/
#define GPIO_ETH_MediaInterface_MII ((u32)0x00000000)
#define GPIO_ETH_MediaInterface_RMII ((u32)0x00000001)
#define IS_GPIO_ETH_MEDIA_INTERFACE(INTERFACE) (((INTERFACE) == GPIO_ETH_MediaInterface_MII) || \
((INTERFACE) == GPIO_ETH_MediaInterface_RMII))
/**
* @}
*/
/**
* @}
*/
/** @defgroup GPIO_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup GPIO_Exported_Functions
* @{
*/
void GPIO_DeInit(GPIO_TypeDef* GPIOx);
void GPIO_AFIODeInit(void);
void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct);
void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct);
uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx);
uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx);
void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal);
void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal);
void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource);
void GPIO_EventOutputCmd(FunctionalState NewState);
void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState);
void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource);
void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_GPIO_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Wyświetl plik

@ -0,0 +1,686 @@
/**
******************************************************************************
* @file stm32f10x_i2c.h
* @author MCD Application Team
* @version V3.6.1
* @date 05-March-2012
* @brief This file contains all the functions prototypes for the I2C firmware
* library.
******************************************************************************
Released into the public domain.
This work is free: you can redistribute it and/or modify it under the terms of
Creative Commons Zero license v1.0
This work is licensed under the Creative Commons Zero 1.0 United States License.
To view a copy of this license, visit http://creativecommons.org/publicdomain/zero/1.0/
or send a letter to Creative Commons, 171 Second Street, Suite 300, San Francisco,
California, 94105, USA.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
or FITNESS FOR A PARTICULAR PURPOSE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_I2C_H
#define __STM32F10x_I2C_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup I2C
* @{
*/
/** @defgroup I2C_Exported_Types
* @{
*/
/**
* @brief I2C Init structure definition
*/
typedef struct
{
uint32_t I2C_ClockSpeed; /*!< Specifies the clock frequency.
This parameter must be set to a value lower than 400kHz */
uint16_t I2C_Mode; /*!< Specifies the I2C mode.
This parameter can be a value of @ref I2C_mode */
uint16_t I2C_DutyCycle; /*!< Specifies the I2C fast mode duty cycle.
This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */
uint16_t I2C_OwnAddress1; /*!< Specifies the first device own address.
This parameter can be a 7-bit or 10-bit address. */
uint16_t I2C_Ack; /*!< Enables or disables the acknowledgement.
This parameter can be a value of @ref I2C_acknowledgement */
uint16_t I2C_AcknowledgedAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged.
This parameter can be a value of @ref I2C_acknowledged_address */
}I2C_InitTypeDef;
/**
* @}
*/
/** @defgroup I2C_Exported_Constants
* @{
*/
#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C1) || \
((PERIPH) == I2C2))
/** @defgroup I2C_mode
* @{
*/
#define I2C_Mode_I2C ((uint16_t)0x0000)
#define I2C_Mode_SMBusDevice ((uint16_t)0x0002)
#define I2C_Mode_SMBusHost ((uint16_t)0x000A)
#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \
((MODE) == I2C_Mode_SMBusDevice) || \
((MODE) == I2C_Mode_SMBusHost))
/**
* @}
*/
/** @defgroup I2C_duty_cycle_in_fast_mode
* @{
*/
#define I2C_DutyCycle_16_9 ((uint16_t)0x4000) /*!< I2C fast mode Tlow/Thigh = 16/9 */
#define I2C_DutyCycle_2 ((uint16_t)0xBFFF) /*!< I2C fast mode Tlow/Thigh = 2 */
#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \
((CYCLE) == I2C_DutyCycle_2))
/**
* @}
*/
/** @defgroup I2C_acknowledgement
* @{
*/
#define I2C_Ack_Enable ((uint16_t)0x0400)
#define I2C_Ack_Disable ((uint16_t)0x0000)
#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \
((STATE) == I2C_Ack_Disable))
/**
* @}
*/
/** @defgroup I2C_transfer_direction
* @{
*/
#define I2C_Direction_Transmitter ((uint8_t)0x00)
#define I2C_Direction_Receiver ((uint8_t)0x01)
#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \
((DIRECTION) == I2C_Direction_Receiver))
/**
* @}
*/
/** @defgroup I2C_acknowledged_address
* @{
*/
#define I2C_AcknowledgedAddress_7bit ((uint16_t)0x4000)
#define I2C_AcknowledgedAddress_10bit ((uint16_t)0xC000)
#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \
((ADDRESS) == I2C_AcknowledgedAddress_10bit))
/**
* @}
*/
/** @defgroup I2C_registers
* @{
*/
#define I2C_Register_CR1 ((uint8_t)0x00)
#define I2C_Register_CR2 ((uint8_t)0x04)
#define I2C_Register_OAR1 ((uint8_t)0x08)
#define I2C_Register_OAR2 ((uint8_t)0x0C)
#define I2C_Register_DR ((uint8_t)0x10)
#define I2C_Register_SR1 ((uint8_t)0x14)
#define I2C_Register_SR2 ((uint8_t)0x18)
#define I2C_Register_CCR ((uint8_t)0x1C)
#define I2C_Register_TRISE ((uint8_t)0x20)
#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \
((REGISTER) == I2C_Register_CR2) || \
((REGISTER) == I2C_Register_OAR1) || \
((REGISTER) == I2C_Register_OAR2) || \
((REGISTER) == I2C_Register_DR) || \
((REGISTER) == I2C_Register_SR1) || \
((REGISTER) == I2C_Register_SR2) || \
((REGISTER) == I2C_Register_CCR) || \
((REGISTER) == I2C_Register_TRISE))
/**
* @}
*/
/** @defgroup I2C_SMBus_alert_pin_level
* @{
*/
#define I2C_SMBusAlert_Low ((uint16_t)0x2000)
#define I2C_SMBusAlert_High ((uint16_t)0xDFFF)
#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \
((ALERT) == I2C_SMBusAlert_High))
/**
* @}
*/
/** @defgroup I2C_PEC_position
* @{
*/
#define I2C_PECPosition_Next ((uint16_t)0x0800)
#define I2C_PECPosition_Current ((uint16_t)0xF7FF)
#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \
((POSITION) == I2C_PECPosition_Current))
/**
* @}
*/
/** @defgroup I2C_NCAK_position
* @{
*/
#define I2C_NACKPosition_Next ((uint16_t)0x0800)
#define I2C_NACKPosition_Current ((uint16_t)0xF7FF)
#define IS_I2C_NACK_POSITION(POSITION) (((POSITION) == I2C_NACKPosition_Next) || \
((POSITION) == I2C_NACKPosition_Current))
/**
* @}
*/
/** @defgroup I2C_interrupts_definition
* @{
*/
#define I2C_IT_BUF ((uint16_t)0x0400)
#define I2C_IT_EVT ((uint16_t)0x0200)
#define I2C_IT_ERR ((uint16_t)0x0100)
#define IS_I2C_CONFIG_IT(IT) ((((IT) & (uint16_t)0xF8FF) == 0x00) && ((IT) != 0x00))
/**
* @}
*/
/** @defgroup I2C_interrupts_definition
* @{
*/
#define I2C_IT_SMBALERT ((uint32_t)0x01008000)
#define I2C_IT_TIMEOUT ((uint32_t)0x01004000)
#define I2C_IT_PECERR ((uint32_t)0x01001000)
#define I2C_IT_OVR ((uint32_t)0x01000800)
#define I2C_IT_AF ((uint32_t)0x01000400)
#define I2C_IT_ARLO ((uint32_t)0x01000200)
#define I2C_IT_BERR ((uint32_t)0x01000100)
#define I2C_IT_TXE ((uint32_t)0x06000080)
#define I2C_IT_RXNE ((uint32_t)0x06000040)
#define I2C_IT_STOPF ((uint32_t)0x02000010)
#define I2C_IT_ADD10 ((uint32_t)0x02000008)
#define I2C_IT_BTF ((uint32_t)0x02000004)
#define I2C_IT_ADDR ((uint32_t)0x02000002)
#define I2C_IT_SB ((uint32_t)0x02000001)
#define IS_I2C_CLEAR_IT(IT) ((((IT) & (uint16_t)0x20FF) == 0x00) && ((IT) != (uint16_t)0x00))
#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \
((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \
((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \
((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \
((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \
((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \
((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB))
/**
* @}
*/
/** @defgroup I2C_flags_definition
* @{
*/
/**
* @brief SR2 register flags
*/
#define I2C_FLAG_DUALF ((uint32_t)0x00800000)
#define I2C_FLAG_SMBHOST ((uint32_t)0x00400000)
#define I2C_FLAG_SMBDEFAULT ((uint32_t)0x00200000)
#define I2C_FLAG_GENCALL ((uint32_t)0x00100000)
#define I2C_FLAG_TRA ((uint32_t)0x00040000)
#define I2C_FLAG_BUSY ((uint32_t)0x00020000)
#define I2C_FLAG_MSL ((uint32_t)0x00010000)
/**
* @brief SR1 register flags
*/
#define I2C_FLAG_SMBALERT ((uint32_t)0x10008000)
#define I2C_FLAG_TIMEOUT ((uint32_t)0x10004000)
#define I2C_FLAG_PECERR ((uint32_t)0x10001000)
#define I2C_FLAG_OVR ((uint32_t)0x10000800)
#define I2C_FLAG_AF ((uint32_t)0x10000400)
#define I2C_FLAG_ARLO ((uint32_t)0x10000200)
#define I2C_FLAG_BERR ((uint32_t)0x10000100)
#define I2C_FLAG_TXE ((uint32_t)0x10000080)
#define I2C_FLAG_RXNE ((uint32_t)0x10000040)
#define I2C_FLAG_STOPF ((uint32_t)0x10000010)
#define I2C_FLAG_ADD10 ((uint32_t)0x10000008)
#define I2C_FLAG_BTF ((uint32_t)0x10000004)
#define I2C_FLAG_ADDR ((uint32_t)0x10000002)
#define I2C_FLAG_SB ((uint32_t)0x10000001)
#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0x20FF) == 0x00) && ((FLAG) != (uint16_t)0x00))
#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \
((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \
((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \
((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \
((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \
((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \
((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \
((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \
((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \
((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \
((FLAG) == I2C_FLAG_SB))
/**
* @}
*/
/** @defgroup I2C_Events
* @{
*/
/*========================================
I2C Master Events (Events grouped in order of communication)
==========================================*/
/**
* @brief Communication start
*
* After sending the START condition (I2C_GenerateSTART() function) the master
* has to wait for this event. It means that the Start condition has been correctly
* released on the I2C bus (the bus is free, no other devices is communicating).
*
*/
/* --EV5 */
#define I2C_EVENT_MASTER_MODE_SELECT ((uint32_t)0x00030001) /* BUSY, MSL and SB flag */
/**
* @brief Address Acknowledge
*
* After checking on EV5 (start condition correctly released on the bus), the
* master sends the address of the slave(s) with which it will communicate
* (I2C_Send7bitAddress() function, it also determines the direction of the communication:
* Master transmitter or Receiver). Then the master has to wait that a slave acknowledges
* his address. If an acknowledge is sent on the bus, one of the following events will
* be set:
*
* 1) In case of Master Receiver (7-bit addressing): the I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED
* event is set.
*
* 2) In case of Master Transmitter (7-bit addressing): the I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED
* is set
*
* 3) In case of 10-Bit addressing mode, the master (just after generating the START
* and checking on EV5) has to send the header of 10-bit addressing mode (I2C_SendData()
* function). Then master should wait on EV9. It means that the 10-bit addressing
* header has been correctly sent on the bus. Then master should send the second part of
* the 10-bit address (LSB) using the function I2C_Send7bitAddress(). Then master
* should wait for event EV6.
*
*/
/* --EV6 */
#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED ((uint32_t)0x00070082) /* BUSY, MSL, ADDR, TXE and TRA flags */
#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED ((uint32_t)0x00030002) /* BUSY, MSL and ADDR flags */
/* --EV9 */
#define I2C_EVENT_MASTER_MODE_ADDRESS10 ((uint32_t)0x00030008) /* BUSY, MSL and ADD10 flags */
/**
* @brief Communication events
*
* If a communication is established (START condition generated and slave address
* acknowledged) then the master has to check on one of the following events for
* communication procedures:
*
* 1) Master Receiver mode: The master has to wait on the event EV7 then to read
* the data received from the slave (I2C_ReceiveData() function).
*
* 2) Master Transmitter mode: The master has to send data (I2C_SendData()
* function) then to wait on event EV8 or EV8_2.
* These two events are similar:
* - EV8 means that the data has been written in the data register and is
* being shifted out.
* - EV8_2 means that the data has been physically shifted out and output
* on the bus.
* In most cases, using EV8 is sufficient for the application.
* Using EV8_2 leads to a slower communication but ensure more reliable test.
* EV8_2 is also more suitable than EV8 for testing on the last data transmission
* (before Stop condition generation).
*
* @note In case the user software does not guarantee that this event EV7 is
* managed before the current byte end of transfer, then user may check on EV7
* and BTF flag at the same time (ie. (I2C_EVENT_MASTER_BYTE_RECEIVED | I2C_FLAG_BTF)).
* In this case the communication may be slower.
*
*/
/* Master RECEIVER mode -----------------------------*/
/* --EV7 */
#define I2C_EVENT_MASTER_BYTE_RECEIVED ((uint32_t)0x00030040) /* BUSY, MSL and RXNE flags */
/* Master TRANSMITTER mode --------------------------*/
/* --EV8 */
#define I2C_EVENT_MASTER_BYTE_TRANSMITTING ((uint32_t)0x00070080) /* TRA, BUSY, MSL, TXE flags */
/* --EV8_2 */
#define I2C_EVENT_MASTER_BYTE_TRANSMITTED ((uint32_t)0x00070084) /* TRA, BUSY, MSL, TXE and BTF flags */
/*========================================
I2C Slave Events (Events grouped in order of communication)
==========================================*/
/**
* @brief Communication start events
*
* Wait on one of these events at the start of the communication. It means that
* the I2C peripheral detected a Start condition on the bus (generated by master
* device) followed by the peripheral address. The peripheral generates an ACK
* condition on the bus (if the acknowledge feature is enabled through function
* I2C_AcknowledgeConfig()) and the events listed above are set :
*
* 1) In normal case (only one address managed by the slave), when the address
* sent by the master matches the own address of the peripheral (configured by
* I2C_OwnAddress1 field) the I2C_EVENT_SLAVE_XXX_ADDRESS_MATCHED event is set
* (where XXX could be TRANSMITTER or RECEIVER).
*
* 2) In case the address sent by the master matches the second address of the
* peripheral (configured by the function I2C_OwnAddress2Config() and enabled
* by the function I2C_DualAddressCmd()) the events I2C_EVENT_SLAVE_XXX_SECONDADDRESS_MATCHED
* (where XXX could be TRANSMITTER or RECEIVER) are set.
*
* 3) In case the address sent by the master is General Call (address 0x00) and
* if the General Call is enabled for the peripheral (using function I2C_GeneralCallCmd())
* the following event is set I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED.
*
*/
/* --EV1 (all the events below are variants of EV1) */
/* 1) Case of One Single Address managed by the slave */
#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((uint32_t)0x00020002) /* BUSY and ADDR flags */
#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */
/* 2) Case of Dual address managed by the slave */
#define I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED ((uint32_t)0x00820000) /* DUALF and BUSY flags */
#define I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((uint32_t)0x00860080) /* DUALF, TRA, BUSY and TXE flags */
/* 3) Case of General Call enabled for the slave */
#define I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED ((uint32_t)0x00120000) /* GENCALL and BUSY flags */
/**
* @brief Communication events
*
* Wait on one of these events when EV1 has already been checked and:
*
* - Slave RECEIVER mode:
* - EV2: When the application is expecting a data byte to be received.
* - EV4: When the application is expecting the end of the communication: master
* sends a stop condition and data transmission is stopped.
*
* - Slave Transmitter mode:
* - EV3: When a byte has been transmitted by the slave and the application is expecting
* the end of the byte transmission. The two events I2C_EVENT_SLAVE_BYTE_TRANSMITTED and
* I2C_EVENT_SLAVE_BYTE_TRANSMITTING are similar. The second one can optionally be
* used when the user software doesn't guarantee the EV3 is managed before the
* current byte end of transfer.
* - EV3_2: When the master sends a NACK in order to tell slave that data transmission
* shall end (before sending the STOP condition). In this case slave has to stop sending
* data bytes and expect a Stop condition on the bus.
*
* @note In case the user software does not guarantee that the event EV2 is
* managed before the current byte end of transfer, then user may check on EV2
* and BTF flag at the same time (ie. (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_BTF)).
* In this case the communication may be slower.
*
*/
/* Slave RECEIVER mode --------------------------*/
/* --EV2 */
#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((uint32_t)0x00020040) /* BUSY and RXNE flags */
/* --EV4 */
#define I2C_EVENT_SLAVE_STOP_DETECTED ((uint32_t)0x00000010) /* STOPF flag */
/* Slave TRANSMITTER mode -----------------------*/
/* --EV3 */
#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((uint32_t)0x00060084) /* TRA, BUSY, TXE and BTF flags */
#define I2C_EVENT_SLAVE_BYTE_TRANSMITTING ((uint32_t)0x00060080) /* TRA, BUSY and TXE flags */
/* --EV3_2 */
#define I2C_EVENT_SLAVE_ACK_FAILURE ((uint32_t)0x00000400) /* AF flag */
/*=========================== End of Events Description ==========================================*/
#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \
((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \
((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \
((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \
((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \
((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \
((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \
((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \
((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \
((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \
((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \
((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \
((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \
((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \
((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \
((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \
((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \
((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTING) || \
((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \
((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE))
/**
* @}
*/
/** @defgroup I2C_own_address1
* @{
*/
#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF)
/**
* @}
*/
/** @defgroup I2C_clock_speed
* @{
*/
#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000))
/**
* @}
*/
/**
* @}
*/
/** @defgroup I2C_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup I2C_Exported_Functions
* @{
*/
void I2C_DeInit(I2C_TypeDef* I2Cx);
void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct);
void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct);
void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address);
void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState);
void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data);
uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx);
void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction);
uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register);
void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_NACKPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_NACKPosition);
void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert);
void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition);
void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx);
void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle);
/**
* @brief
****************************************************************************************
*
* I2C State Monitoring Functions
*
****************************************************************************************
* This I2C driver provides three different ways for I2C state monitoring
* depending on the application requirements and constraints:
*
*
* 1) Basic state monitoring:
* Using I2C_CheckEvent() function:
* It compares the status registers (SR1 and SR2) content to a given event
* (can be the combination of one or more flags).
* It returns SUCCESS if the current status includes the given flags
* and returns ERROR if one or more flags are missing in the current status.
* - When to use:
* - This function is suitable for most applications as well as for startup
* activity since the events are fully described in the product reference manual
* (RM0008).
* - It is also suitable for users who need to define their own events.
* - Limitations:
* - If an error occurs (ie. error flags are set besides to the monitored flags),
* the I2C_CheckEvent() function may return SUCCESS despite the communication
* hold or corrupted real state.
* In this case, it is advised to use error interrupts to monitor the error
* events and handle them in the interrupt IRQ handler.
*
* @note
* For error management, it is advised to use the following functions:
* - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR).
* - I2Cx_ER_IRQHandler() which is called when the error interrupt occurs.
* Where x is the peripheral instance (I2C1, I2C2 ...)
* - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into I2Cx_ER_IRQHandler()
* in order to determine which error occurred.
* - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd()
* and/or I2C_GenerateStop() in order to clear the error flag and source,
* and return to correct communication status.
*
*
* 2) Advanced state monitoring:
* Using the function I2C_GetLastEvent() which returns the image of both status
* registers in a single word (uint32_t) (Status Register 2 value is shifted left
* by 16 bits and concatenated to Status Register 1).
* - When to use:
* - This function is suitable for the same applications above but it allows to
* overcome the limitations of I2C_GetFlagStatus() function (see below).
* The returned value could be compared to events already defined in the
* library (stm32f10x_i2c.h) or to custom values defined by user.
* - This function is suitable when multiple flags are monitored at the same time.
* - At the opposite of I2C_CheckEvent() function, this function allows user to
* choose when an event is accepted (when all events flags are set and no
* other flags are set or just when the needed flags are set like
* I2C_CheckEvent() function).
* - Limitations:
* - User may need to define his own events.
* - Same remark concerning the error management is applicable for this
* function if user decides to check only regular communication flags (and
* ignores error flags).
*
*
* 3) Flag-based state monitoring:
* Using the function I2C_GetFlagStatus() which simply returns the status of
* one single flag (ie. I2C_FLAG_RXNE ...).
* - When to use:
* - This function could be used for specific applications or in debug phase.
* - It is suitable when only one flag checking is needed (most I2C events
* are monitored through multiple flags).
* - Limitations:
* - When calling this function, the Status register is accessed. Some flags are
* cleared when the status register is accessed. So checking the status
* of one Flag, may clear other ones.
* - Function may need to be called twice or more in order to monitor one
* single event.
*
*/
/**
*
* 1) Basic state monitoring
*******************************************************************************
*/
ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT);
/**
*
* 2) Advanced state monitoring
*******************************************************************************
*/
uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx);
/**
*
* 3) Flag-based state monitoring
*******************************************************************************
*/
FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG);
/**
*
*******************************************************************************
*/
void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG);
ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT);
void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT);
#ifdef __cplusplus
}
#endif
#endif /*__STM32F10x_I2C_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

Wyświetl plik

@ -0,0 +1,156 @@
/**
******************************************************************************
* @file stm32f10x_pwr.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the PWR firmware
* library.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_PWR_H
#define __STM32F10x_PWR_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup PWR
* @{
*/
/** @defgroup PWR_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup PWR_Exported_Constants
* @{
*/
/** @defgroup PVD_detection_level
* @{
*/
#define PWR_PVDLevel_2V2 ((uint32_t)0x00000000)
#define PWR_PVDLevel_2V3 ((uint32_t)0x00000020)
#define PWR_PVDLevel_2V4 ((uint32_t)0x00000040)
#define PWR_PVDLevel_2V5 ((uint32_t)0x00000060)
#define PWR_PVDLevel_2V6 ((uint32_t)0x00000080)
#define PWR_PVDLevel_2V7 ((uint32_t)0x000000A0)
#define PWR_PVDLevel_2V8 ((uint32_t)0x000000C0)
#define PWR_PVDLevel_2V9 ((uint32_t)0x000000E0)
#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_2V2) || ((LEVEL) == PWR_PVDLevel_2V3)|| \
((LEVEL) == PWR_PVDLevel_2V4) || ((LEVEL) == PWR_PVDLevel_2V5)|| \
((LEVEL) == PWR_PVDLevel_2V6) || ((LEVEL) == PWR_PVDLevel_2V7)|| \
((LEVEL) == PWR_PVDLevel_2V8) || ((LEVEL) == PWR_PVDLevel_2V9))
/**
* @}
*/
/** @defgroup Regulator_state_is_STOP_mode
* @{
*/
#define PWR_Regulator_ON ((uint32_t)0x00000000)
#define PWR_Regulator_LowPower ((uint32_t)0x00000001)
#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \
((REGULATOR) == PWR_Regulator_LowPower))
/**
* @}
*/
/** @defgroup STOP_mode_entry
* @{
*/
#define PWR_STOPEntry_WFI ((uint8_t)0x01)
#define PWR_STOPEntry_WFE ((uint8_t)0x02)
#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE))
/**
* @}
*/
/** @defgroup PWR_Flag
* @{
*/
#define PWR_FLAG_WU ((uint32_t)0x00000001)
#define PWR_FLAG_SB ((uint32_t)0x00000002)
#define PWR_FLAG_PVDO ((uint32_t)0x00000004)
#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \
((FLAG) == PWR_FLAG_PVDO))
#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB))
/**
* @}
*/
/**
* @}
*/
/** @defgroup PWR_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup PWR_Exported_Functions
* @{
*/
void PWR_DeInit(void);
void PWR_BackupAccessCmd(FunctionalState NewState);
void PWR_PVDCmd(FunctionalState NewState);
void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel);
void PWR_WakeUpPinCmd(FunctionalState NewState);
void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry);
void PWR_EnterSTANDBYMode(void);
FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG);
void PWR_ClearFlag(uint32_t PWR_FLAG);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_PWR_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Wyświetl plik

@ -0,0 +1,727 @@
/**
******************************************************************************
* @file stm32f10x_rcc.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the RCC firmware
* library.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_RCC_H
#define __STM32F10x_RCC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup RCC
* @{
*/
/** @defgroup RCC_Exported_Types
* @{
*/
typedef struct
{
uint32_t SYSCLK_Frequency; /*!< returns SYSCLK clock frequency expressed in Hz */
uint32_t HCLK_Frequency; /*!< returns HCLK clock frequency expressed in Hz */
uint32_t PCLK1_Frequency; /*!< returns PCLK1 clock frequency expressed in Hz */
uint32_t PCLK2_Frequency; /*!< returns PCLK2 clock frequency expressed in Hz */
uint32_t ADCCLK_Frequency; /*!< returns ADCCLK clock frequency expressed in Hz */
}RCC_ClocksTypeDef;
/**
* @}
*/
/** @defgroup RCC_Exported_Constants
* @{
*/
/** @defgroup HSE_configuration
* @{
*/
#define RCC_HSE_OFF ((uint32_t)0x00000000)
#define RCC_HSE_ON ((uint32_t)0x00010000)
#define RCC_HSE_Bypass ((uint32_t)0x00040000)
#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \
((HSE) == RCC_HSE_Bypass))
/**
* @}
*/
/** @defgroup PLL_entry_clock_source
* @{
*/
#define RCC_PLLSource_HSI_Div2 ((uint32_t)0x00000000)
#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_CL)
#define RCC_PLLSource_HSE_Div1 ((uint32_t)0x00010000)
#define RCC_PLLSource_HSE_Div2 ((uint32_t)0x00030000)
#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \
((SOURCE) == RCC_PLLSource_HSE_Div1) || \
((SOURCE) == RCC_PLLSource_HSE_Div2))
#else
#define RCC_PLLSource_PREDIV1 ((uint32_t)0x00010000)
#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \
((SOURCE) == RCC_PLLSource_PREDIV1))
#endif /* STM32F10X_CL */
/**
* @}
*/
/** @defgroup PLL_multiplication_factor
* @{
*/
#ifndef STM32F10X_CL
#define RCC_PLLMul_2 ((uint32_t)0x00000000)
#define RCC_PLLMul_3 ((uint32_t)0x00040000)
#define RCC_PLLMul_4 ((uint32_t)0x00080000)
#define RCC_PLLMul_5 ((uint32_t)0x000C0000)
#define RCC_PLLMul_6 ((uint32_t)0x00100000)
#define RCC_PLLMul_7 ((uint32_t)0x00140000)
#define RCC_PLLMul_8 ((uint32_t)0x00180000)
#define RCC_PLLMul_9 ((uint32_t)0x001C0000)
#define RCC_PLLMul_10 ((uint32_t)0x00200000)
#define RCC_PLLMul_11 ((uint32_t)0x00240000)
#define RCC_PLLMul_12 ((uint32_t)0x00280000)
#define RCC_PLLMul_13 ((uint32_t)0x002C0000)
#define RCC_PLLMul_14 ((uint32_t)0x00300000)
#define RCC_PLLMul_15 ((uint32_t)0x00340000)
#define RCC_PLLMul_16 ((uint32_t)0x00380000)
#define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3) || \
((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \
((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \
((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \
((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \
((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \
((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \
((MUL) == RCC_PLLMul_16))
#else
#define RCC_PLLMul_4 ((uint32_t)0x00080000)
#define RCC_PLLMul_5 ((uint32_t)0x000C0000)
#define RCC_PLLMul_6 ((uint32_t)0x00100000)
#define RCC_PLLMul_7 ((uint32_t)0x00140000)
#define RCC_PLLMul_8 ((uint32_t)0x00180000)
#define RCC_PLLMul_9 ((uint32_t)0x001C0000)
#define RCC_PLLMul_6_5 ((uint32_t)0x00340000)
#define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \
((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \
((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \
((MUL) == RCC_PLLMul_6_5))
#endif /* STM32F10X_CL */
/**
* @}
*/
/** @defgroup PREDIV1_division_factor
* @{
*/
#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL)
#define RCC_PREDIV1_Div1 ((uint32_t)0x00000000)
#define RCC_PREDIV1_Div2 ((uint32_t)0x00000001)
#define RCC_PREDIV1_Div3 ((uint32_t)0x00000002)
#define RCC_PREDIV1_Div4 ((uint32_t)0x00000003)
#define RCC_PREDIV1_Div5 ((uint32_t)0x00000004)
#define RCC_PREDIV1_Div6 ((uint32_t)0x00000005)
#define RCC_PREDIV1_Div7 ((uint32_t)0x00000006)
#define RCC_PREDIV1_Div8 ((uint32_t)0x00000007)
#define RCC_PREDIV1_Div9 ((uint32_t)0x00000008)
#define RCC_PREDIV1_Div10 ((uint32_t)0x00000009)
#define RCC_PREDIV1_Div11 ((uint32_t)0x0000000A)
#define RCC_PREDIV1_Div12 ((uint32_t)0x0000000B)
#define RCC_PREDIV1_Div13 ((uint32_t)0x0000000C)
#define RCC_PREDIV1_Div14 ((uint32_t)0x0000000D)
#define RCC_PREDIV1_Div15 ((uint32_t)0x0000000E)
#define RCC_PREDIV1_Div16 ((uint32_t)0x0000000F)
#define IS_RCC_PREDIV1(PREDIV1) (((PREDIV1) == RCC_PREDIV1_Div1) || ((PREDIV1) == RCC_PREDIV1_Div2) || \
((PREDIV1) == RCC_PREDIV1_Div3) || ((PREDIV1) == RCC_PREDIV1_Div4) || \
((PREDIV1) == RCC_PREDIV1_Div5) || ((PREDIV1) == RCC_PREDIV1_Div6) || \
((PREDIV1) == RCC_PREDIV1_Div7) || ((PREDIV1) == RCC_PREDIV1_Div8) || \
((PREDIV1) == RCC_PREDIV1_Div9) || ((PREDIV1) == RCC_PREDIV1_Div10) || \
((PREDIV1) == RCC_PREDIV1_Div11) || ((PREDIV1) == RCC_PREDIV1_Div12) || \
((PREDIV1) == RCC_PREDIV1_Div13) || ((PREDIV1) == RCC_PREDIV1_Div14) || \
((PREDIV1) == RCC_PREDIV1_Div15) || ((PREDIV1) == RCC_PREDIV1_Div16))
#endif
/**
* @}
*/
/** @defgroup PREDIV1_clock_source
* @{
*/
#ifdef STM32F10X_CL
/* PREDIV1 clock source (for STM32 connectivity line devices) */
#define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000)
#define RCC_PREDIV1_Source_PLL2 ((uint32_t)0x00010000)
#define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE) || \
((SOURCE) == RCC_PREDIV1_Source_PLL2))
#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
/* PREDIV1 clock source (for STM32 Value line devices) */
#define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000)
#define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE))
#endif
/**
* @}
*/
#ifdef STM32F10X_CL
/** @defgroup PREDIV2_division_factor
* @{
*/
#define RCC_PREDIV2_Div1 ((uint32_t)0x00000000)
#define RCC_PREDIV2_Div2 ((uint32_t)0x00000010)
#define RCC_PREDIV2_Div3 ((uint32_t)0x00000020)
#define RCC_PREDIV2_Div4 ((uint32_t)0x00000030)
#define RCC_PREDIV2_Div5 ((uint32_t)0x00000040)
#define RCC_PREDIV2_Div6 ((uint32_t)0x00000050)
#define RCC_PREDIV2_Div7 ((uint32_t)0x00000060)
#define RCC_PREDIV2_Div8 ((uint32_t)0x00000070)
#define RCC_PREDIV2_Div9 ((uint32_t)0x00000080)
#define RCC_PREDIV2_Div10 ((uint32_t)0x00000090)
#define RCC_PREDIV2_Div11 ((uint32_t)0x000000A0)
#define RCC_PREDIV2_Div12 ((uint32_t)0x000000B0)
#define RCC_PREDIV2_Div13 ((uint32_t)0x000000C0)
#define RCC_PREDIV2_Div14 ((uint32_t)0x000000D0)
#define RCC_PREDIV2_Div15 ((uint32_t)0x000000E0)
#define RCC_PREDIV2_Div16 ((uint32_t)0x000000F0)
#define IS_RCC_PREDIV2(PREDIV2) (((PREDIV2) == RCC_PREDIV2_Div1) || ((PREDIV2) == RCC_PREDIV2_Div2) || \
((PREDIV2) == RCC_PREDIV2_Div3) || ((PREDIV2) == RCC_PREDIV2_Div4) || \
((PREDIV2) == RCC_PREDIV2_Div5) || ((PREDIV2) == RCC_PREDIV2_Div6) || \
((PREDIV2) == RCC_PREDIV2_Div7) || ((PREDIV2) == RCC_PREDIV2_Div8) || \
((PREDIV2) == RCC_PREDIV2_Div9) || ((PREDIV2) == RCC_PREDIV2_Div10) || \
((PREDIV2) == RCC_PREDIV2_Div11) || ((PREDIV2) == RCC_PREDIV2_Div12) || \
((PREDIV2) == RCC_PREDIV2_Div13) || ((PREDIV2) == RCC_PREDIV2_Div14) || \
((PREDIV2) == RCC_PREDIV2_Div15) || ((PREDIV2) == RCC_PREDIV2_Div16))
/**
* @}
*/
/** @defgroup PLL2_multiplication_factor
* @{
*/
#define RCC_PLL2Mul_8 ((uint32_t)0x00000600)
#define RCC_PLL2Mul_9 ((uint32_t)0x00000700)
#define RCC_PLL2Mul_10 ((uint32_t)0x00000800)
#define RCC_PLL2Mul_11 ((uint32_t)0x00000900)
#define RCC_PLL2Mul_12 ((uint32_t)0x00000A00)
#define RCC_PLL2Mul_13 ((uint32_t)0x00000B00)
#define RCC_PLL2Mul_14 ((uint32_t)0x00000C00)
#define RCC_PLL2Mul_16 ((uint32_t)0x00000E00)
#define RCC_PLL2Mul_20 ((uint32_t)0x00000F00)
#define IS_RCC_PLL2_MUL(MUL) (((MUL) == RCC_PLL2Mul_8) || ((MUL) == RCC_PLL2Mul_9) || \
((MUL) == RCC_PLL2Mul_10) || ((MUL) == RCC_PLL2Mul_11) || \
((MUL) == RCC_PLL2Mul_12) || ((MUL) == RCC_PLL2Mul_13) || \
((MUL) == RCC_PLL2Mul_14) || ((MUL) == RCC_PLL2Mul_16) || \
((MUL) == RCC_PLL2Mul_20))
/**
* @}
*/
/** @defgroup PLL3_multiplication_factor
* @{
*/
#define RCC_PLL3Mul_8 ((uint32_t)0x00006000)
#define RCC_PLL3Mul_9 ((uint32_t)0x00007000)
#define RCC_PLL3Mul_10 ((uint32_t)0x00008000)
#define RCC_PLL3Mul_11 ((uint32_t)0x00009000)
#define RCC_PLL3Mul_12 ((uint32_t)0x0000A000)
#define RCC_PLL3Mul_13 ((uint32_t)0x0000B000)
#define RCC_PLL3Mul_14 ((uint32_t)0x0000C000)
#define RCC_PLL3Mul_16 ((uint32_t)0x0000E000)
#define RCC_PLL3Mul_20 ((uint32_t)0x0000F000)
#define IS_RCC_PLL3_MUL(MUL) (((MUL) == RCC_PLL3Mul_8) || ((MUL) == RCC_PLL3Mul_9) || \
((MUL) == RCC_PLL3Mul_10) || ((MUL) == RCC_PLL3Mul_11) || \
((MUL) == RCC_PLL3Mul_12) || ((MUL) == RCC_PLL3Mul_13) || \
((MUL) == RCC_PLL3Mul_14) || ((MUL) == RCC_PLL3Mul_16) || \
((MUL) == RCC_PLL3Mul_20))
/**
* @}
*/
#endif /* STM32F10X_CL */
/** @defgroup System_clock_source
* @{
*/
#define RCC_SYSCLKSource_HSI ((uint32_t)0x00000000)
#define RCC_SYSCLKSource_HSE ((uint32_t)0x00000001)
#define RCC_SYSCLKSource_PLLCLK ((uint32_t)0x00000002)
#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \
((SOURCE) == RCC_SYSCLKSource_HSE) || \
((SOURCE) == RCC_SYSCLKSource_PLLCLK))
/**
* @}
*/
/** @defgroup AHB_clock_source
* @{
*/
#define RCC_SYSCLK_Div1 ((uint32_t)0x00000000)
#define RCC_SYSCLK_Div2 ((uint32_t)0x00000080)
#define RCC_SYSCLK_Div4 ((uint32_t)0x00000090)
#define RCC_SYSCLK_Div8 ((uint32_t)0x000000A0)
#define RCC_SYSCLK_Div16 ((uint32_t)0x000000B0)
#define RCC_SYSCLK_Div64 ((uint32_t)0x000000C0)
#define RCC_SYSCLK_Div128 ((uint32_t)0x000000D0)
#define RCC_SYSCLK_Div256 ((uint32_t)0x000000E0)
#define RCC_SYSCLK_Div512 ((uint32_t)0x000000F0)
#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \
((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \
((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \
((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \
((HCLK) == RCC_SYSCLK_Div512))
/**
* @}
*/
/** @defgroup APB1_APB2_clock_source
* @{
*/
#define RCC_HCLK_Div1 ((uint32_t)0x00000000)
#define RCC_HCLK_Div2 ((uint32_t)0x00000400)
#define RCC_HCLK_Div4 ((uint32_t)0x00000500)
#define RCC_HCLK_Div8 ((uint32_t)0x00000600)
#define RCC_HCLK_Div16 ((uint32_t)0x00000700)
#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \
((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \
((PCLK) == RCC_HCLK_Div16))
/**
* @}
*/
/** @defgroup RCC_Interrupt_source
* @{
*/
#define RCC_IT_LSIRDY ((uint8_t)0x01)
#define RCC_IT_LSERDY ((uint8_t)0x02)
#define RCC_IT_HSIRDY ((uint8_t)0x04)
#define RCC_IT_HSERDY ((uint8_t)0x08)
#define RCC_IT_PLLRDY ((uint8_t)0x10)
#define RCC_IT_CSS ((uint8_t)0x80)
#ifndef STM32F10X_CL
#define IS_RCC_IT(IT) ((((IT) & (uint8_t)0xE0) == 0x00) && ((IT) != 0x00))
#define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \
((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \
((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS))
#define IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x60) == 0x00) && ((IT) != 0x00))
#else
#define RCC_IT_PLL2RDY ((uint8_t)0x20)
#define RCC_IT_PLL3RDY ((uint8_t)0x40)
#define IS_RCC_IT(IT) ((((IT) & (uint8_t)0x80) == 0x00) && ((IT) != 0x00))
#define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \
((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \
((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS) || \
((IT) == RCC_IT_PLL2RDY) || ((IT) == RCC_IT_PLL3RDY))
#define IS_RCC_CLEAR_IT(IT) ((IT) != 0x00)
#endif /* STM32F10X_CL */
/**
* @}
*/
#ifndef STM32F10X_CL
/** @defgroup USB_Device_clock_source
* @{
*/
#define RCC_USBCLKSource_PLLCLK_1Div5 ((uint8_t)0x00)
#define RCC_USBCLKSource_PLLCLK_Div1 ((uint8_t)0x01)
#define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \
((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1))
/**
* @}
*/
#else
/** @defgroup USB_OTG_FS_clock_source
* @{
*/
#define RCC_OTGFSCLKSource_PLLVCO_Div3 ((uint8_t)0x00)
#define RCC_OTGFSCLKSource_PLLVCO_Div2 ((uint8_t)0x01)
#define IS_RCC_OTGFSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div3) || \
((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div2))
/**
* @}
*/
#endif /* STM32F10X_CL */
#ifdef STM32F10X_CL
/** @defgroup I2S2_clock_source
* @{
*/
#define RCC_I2S2CLKSource_SYSCLK ((uint8_t)0x00)
#define RCC_I2S2CLKSource_PLL3_VCO ((uint8_t)0x01)
#define IS_RCC_I2S2CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_SYSCLK) || \
((SOURCE) == RCC_I2S2CLKSource_PLL3_VCO))
/**
* @}
*/
/** @defgroup I2S3_clock_source
* @{
*/
#define RCC_I2S3CLKSource_SYSCLK ((uint8_t)0x00)
#define RCC_I2S3CLKSource_PLL3_VCO ((uint8_t)0x01)
#define IS_RCC_I2S3CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S3CLKSource_SYSCLK) || \
((SOURCE) == RCC_I2S3CLKSource_PLL3_VCO))
/**
* @}
*/
#endif /* STM32F10X_CL */
/** @defgroup ADC_clock_source
* @{
*/
#define RCC_PCLK2_Div2 ((uint32_t)0x00000000)
#define RCC_PCLK2_Div4 ((uint32_t)0x00004000)
#define RCC_PCLK2_Div6 ((uint32_t)0x00008000)
#define RCC_PCLK2_Div8 ((uint32_t)0x0000C000)
#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_PCLK2_Div2) || ((ADCCLK) == RCC_PCLK2_Div4) || \
((ADCCLK) == RCC_PCLK2_Div6) || ((ADCCLK) == RCC_PCLK2_Div8))
/**
* @}
*/
/** @defgroup LSE_configuration
* @{
*/
#define RCC_LSE_OFF ((uint8_t)0x00)
#define RCC_LSE_ON ((uint8_t)0x01)
#define RCC_LSE_Bypass ((uint8_t)0x04)
#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \
((LSE) == RCC_LSE_Bypass))
/**
* @}
*/
/** @defgroup RTC_clock_source
* @{
*/
#define RCC_RTCCLKSource_LSE ((uint32_t)0x00000100)
#define RCC_RTCCLKSource_LSI ((uint32_t)0x00000200)
#define RCC_RTCCLKSource_HSE_Div128 ((uint32_t)0x00000300)
#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \
((SOURCE) == RCC_RTCCLKSource_LSI) || \
((SOURCE) == RCC_RTCCLKSource_HSE_Div128))
/**
* @}
*/
/** @defgroup AHB_peripheral
* @{
*/
#define RCC_AHBPeriph_DMA1 ((uint32_t)0x00000001)
#define RCC_AHBPeriph_DMA2 ((uint32_t)0x00000002)
#define RCC_AHBPeriph_SRAM ((uint32_t)0x00000004)
#define RCC_AHBPeriph_FLITF ((uint32_t)0x00000010)
#define RCC_AHBPeriph_CRC ((uint32_t)0x00000040)
#ifndef STM32F10X_CL
#define RCC_AHBPeriph_FSMC ((uint32_t)0x00000100)
#define RCC_AHBPeriph_SDIO ((uint32_t)0x00000400)
#define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFAA8) == 0x00) && ((PERIPH) != 0x00))
#else
#define RCC_AHBPeriph_OTG_FS ((uint32_t)0x00001000)
#define RCC_AHBPeriph_ETH_MAC ((uint32_t)0x00004000)
#define RCC_AHBPeriph_ETH_MAC_Tx ((uint32_t)0x00008000)
#define RCC_AHBPeriph_ETH_MAC_Rx ((uint32_t)0x00010000)
#define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFE2FA8) == 0x00) && ((PERIPH) != 0x00))
#define IS_RCC_AHB_PERIPH_RESET(PERIPH) ((((PERIPH) & 0xFFFFAFFF) == 0x00) && ((PERIPH) != 0x00))
#endif /* STM32F10X_CL */
/**
* @}
*/
/** @defgroup APB2_peripheral
* @{
*/
#define RCC_APB2Periph_AFIO ((uint32_t)0x00000001)
#define RCC_APB2Periph_GPIOA ((uint32_t)0x00000004)
#define RCC_APB2Periph_GPIOB ((uint32_t)0x00000008)
#define RCC_APB2Periph_GPIOC ((uint32_t)0x00000010)
#define RCC_APB2Periph_GPIOD ((uint32_t)0x00000020)
#define RCC_APB2Periph_GPIOE ((uint32_t)0x00000040)
#define RCC_APB2Periph_GPIOF ((uint32_t)0x00000080)
#define RCC_APB2Periph_GPIOG ((uint32_t)0x00000100)
#define RCC_APB2Periph_ADC1 ((uint32_t)0x00000200)
#define RCC_APB2Periph_ADC2 ((uint32_t)0x00000400)
#define RCC_APB2Periph_TIM1 ((uint32_t)0x00000800)
#define RCC_APB2Periph_SPI1 ((uint32_t)0x00001000)
#define RCC_APB2Periph_TIM8 ((uint32_t)0x00002000)
#define RCC_APB2Periph_USART1 ((uint32_t)0x00004000)
#define RCC_APB2Periph_ADC3 ((uint32_t)0x00008000)
#define RCC_APB2Periph_TIM15 ((uint32_t)0x00010000)
#define RCC_APB2Periph_TIM16 ((uint32_t)0x00020000)
#define RCC_APB2Periph_TIM17 ((uint32_t)0x00040000)
#define RCC_APB2Periph_TIM9 ((uint32_t)0x00080000)
#define RCC_APB2Periph_TIM10 ((uint32_t)0x00100000)
#define RCC_APB2Periph_TIM11 ((uint32_t)0x00200000)
#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFC00002) == 0x00) && ((PERIPH) != 0x00))
/**
* @}
*/
/** @defgroup APB1_peripheral
* @{
*/
#define RCC_APB1Periph_TIM2 ((uint32_t)0x00000001)
#define RCC_APB1Periph_TIM3 ((uint32_t)0x00000002)
#define RCC_APB1Periph_TIM4 ((uint32_t)0x00000004)
#define RCC_APB1Periph_TIM5 ((uint32_t)0x00000008)
#define RCC_APB1Periph_TIM6 ((uint32_t)0x00000010)
#define RCC_APB1Periph_TIM7 ((uint32_t)0x00000020)
#define RCC_APB1Periph_TIM12 ((uint32_t)0x00000040)
#define RCC_APB1Periph_TIM13 ((uint32_t)0x00000080)
#define RCC_APB1Periph_TIM14 ((uint32_t)0x00000100)
#define RCC_APB1Periph_WWDG ((uint32_t)0x00000800)
#define RCC_APB1Periph_SPI2 ((uint32_t)0x00004000)
#define RCC_APB1Periph_SPI3 ((uint32_t)0x00008000)
#define RCC_APB1Periph_USART2 ((uint32_t)0x00020000)
#define RCC_APB1Periph_USART3 ((uint32_t)0x00040000)
#define RCC_APB1Periph_UART4 ((uint32_t)0x00080000)
#define RCC_APB1Periph_UART5 ((uint32_t)0x00100000)
#define RCC_APB1Periph_I2C1 ((uint32_t)0x00200000)
#define RCC_APB1Periph_I2C2 ((uint32_t)0x00400000)
#define RCC_APB1Periph_USB ((uint32_t)0x00800000)
#define RCC_APB1Periph_CAN1 ((uint32_t)0x02000000)
#define RCC_APB1Periph_CAN2 ((uint32_t)0x04000000)
#define RCC_APB1Periph_BKP ((uint32_t)0x08000000)
#define RCC_APB1Periph_PWR ((uint32_t)0x10000000)
#define RCC_APB1Periph_DAC ((uint32_t)0x20000000)
#define RCC_APB1Periph_CEC ((uint32_t)0x40000000)
#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0x81013600) == 0x00) && ((PERIPH) != 0x00))
/**
* @}
*/
/** @defgroup Clock_source_to_output_on_MCO_pin
* @{
*/
#define RCC_MCO_NoClock ((uint8_t)0x00)
#define RCC_MCO_SYSCLK ((uint8_t)0x04)
#define RCC_MCO_HSI ((uint8_t)0x05)
#define RCC_MCO_HSE ((uint8_t)0x06)
#define RCC_MCO_PLLCLK_Div2 ((uint8_t)0x07)
#ifndef STM32F10X_CL
#define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \
((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \
((MCO) == RCC_MCO_PLLCLK_Div2))
#else
#define RCC_MCO_PLL2CLK ((uint8_t)0x08)
#define RCC_MCO_PLL3CLK_Div2 ((uint8_t)0x09)
#define RCC_MCO_XT1 ((uint8_t)0x0A)
#define RCC_MCO_PLL3CLK ((uint8_t)0x0B)
#define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \
((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \
((MCO) == RCC_MCO_PLLCLK_Div2) || ((MCO) == RCC_MCO_PLL2CLK) || \
((MCO) == RCC_MCO_PLL3CLK_Div2) || ((MCO) == RCC_MCO_XT1) || \
((MCO) == RCC_MCO_PLL3CLK))
#endif /* STM32F10X_CL */
/**
* @}
*/
/** @defgroup RCC_Flag
* @{
*/
#define RCC_FLAG_HSIRDY ((uint8_t)0x21)
#define RCC_FLAG_HSERDY ((uint8_t)0x31)
#define RCC_FLAG_PLLRDY ((uint8_t)0x39)
#define RCC_FLAG_LSERDY ((uint8_t)0x41)
#define RCC_FLAG_LSIRDY ((uint8_t)0x61)
#define RCC_FLAG_PINRST ((uint8_t)0x7A)
#define RCC_FLAG_PORRST ((uint8_t)0x7B)
#define RCC_FLAG_SFTRST ((uint8_t)0x7C)
#define RCC_FLAG_IWDGRST ((uint8_t)0x7D)
#define RCC_FLAG_WWDGRST ((uint8_t)0x7E)
#define RCC_FLAG_LPWRRST ((uint8_t)0x7F)
#ifndef STM32F10X_CL
#define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \
((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \
((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \
((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \
((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \
((FLAG) == RCC_FLAG_LPWRRST))
#else
#define RCC_FLAG_PLL2RDY ((uint8_t)0x3B)
#define RCC_FLAG_PLL3RDY ((uint8_t)0x3D)
#define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \
((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \
((FLAG) == RCC_FLAG_PLL2RDY) || ((FLAG) == RCC_FLAG_PLL3RDY) || \
((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \
((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \
((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \
((FLAG) == RCC_FLAG_LPWRRST))
#endif /* STM32F10X_CL */
#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F)
/**
* @}
*/
/**
* @}
*/
/** @defgroup RCC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup RCC_Exported_Functions
* @{
*/
void RCC_DeInit(void);
void RCC_HSEConfig(uint32_t RCC_HSE);
ErrorStatus RCC_WaitForHSEStartUp(void);
void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue);
void RCC_HSICmd(FunctionalState NewState);
void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul);
void RCC_PLLCmd(FunctionalState NewState);
#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL)
void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div);
#endif
#ifdef STM32F10X_CL
void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div);
void RCC_PLL2Config(uint32_t RCC_PLL2Mul);
void RCC_PLL2Cmd(FunctionalState NewState);
void RCC_PLL3Config(uint32_t RCC_PLL3Mul);
void RCC_PLL3Cmd(FunctionalState NewState);
#endif /* STM32F10X_CL */
void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource);
uint8_t RCC_GetSYSCLKSource(void);
void RCC_HCLKConfig(uint32_t RCC_SYSCLK);
void RCC_PCLK1Config(uint32_t RCC_HCLK);
void RCC_PCLK2Config(uint32_t RCC_HCLK);
void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState);
#ifndef STM32F10X_CL
void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource);
#else
void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource);
#endif /* STM32F10X_CL */
void RCC_ADCCLKConfig(uint32_t RCC_PCLK2);
#ifdef STM32F10X_CL
void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource);
void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource);
#endif /* STM32F10X_CL */
void RCC_LSEConfig(uint8_t RCC_LSE);
void RCC_LSICmd(FunctionalState NewState);
void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource);
void RCC_RTCCLKCmd(FunctionalState NewState);
void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks);
void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState);
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
#ifdef STM32F10X_CL
void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState);
#endif /* STM32F10X_CL */
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
void RCC_BackupResetCmd(FunctionalState NewState);
void RCC_ClockSecuritySystemCmd(FunctionalState NewState);
void RCC_MCOConfig(uint8_t RCC_MCO);
FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG);
void RCC_ClearFlag(void);
ITStatus RCC_GetITStatus(uint8_t RCC_IT);
void RCC_ClearITPendingBit(uint8_t RCC_IT);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_RCC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Wyświetl plik

@ -0,0 +1,487 @@
/**
******************************************************************************
* @file stm32f10x_spi.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the SPI firmware
* library.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_SPI_H
#define __STM32F10x_SPI_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup SPI
* @{
*/
/** @defgroup SPI_Exported_Types
* @{
*/
/**
* @brief SPI Init structure definition
*/
typedef struct
{
uint16_t SPI_Direction; /*!< Specifies the SPI unidirectional or bidirectional data mode.
This parameter can be a value of @ref SPI_data_direction */
uint16_t SPI_Mode; /*!< Specifies the SPI operating mode.
This parameter can be a value of @ref SPI_mode */
uint16_t SPI_DataSize; /*!< Specifies the SPI data size.
This parameter can be a value of @ref SPI_data_size */
uint16_t SPI_CPOL; /*!< Specifies the serial clock steady state.
This parameter can be a value of @ref SPI_Clock_Polarity */
uint16_t SPI_CPHA; /*!< Specifies the clock active edge for the bit capture.
This parameter can be a value of @ref SPI_Clock_Phase */
uint16_t SPI_NSS; /*!< Specifies whether the NSS signal is managed by
hardware (NSS pin) or by software using the SSI bit.
This parameter can be a value of @ref SPI_Slave_Select_management */
uint16_t SPI_BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be
used to configure the transmit and receive SCK clock.
This parameter can be a value of @ref SPI_BaudRate_Prescaler.
@note The communication clock is derived from the master
clock. The slave clock does not need to be set. */
uint16_t SPI_FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit.
This parameter can be a value of @ref SPI_MSB_LSB_transmission */
uint16_t SPI_CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. */
}SPI_InitTypeDef;
/**
* @brief I2S Init structure definition
*/
typedef struct
{
uint16_t I2S_Mode; /*!< Specifies the I2S operating mode.
This parameter can be a value of @ref I2S_Mode */
uint16_t I2S_Standard; /*!< Specifies the standard used for the I2S communication.
This parameter can be a value of @ref I2S_Standard */
uint16_t I2S_DataFormat; /*!< Specifies the data format for the I2S communication.
This parameter can be a value of @ref I2S_Data_Format */
uint16_t I2S_MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not.
This parameter can be a value of @ref I2S_MCLK_Output */
uint32_t I2S_AudioFreq; /*!< Specifies the frequency selected for the I2S communication.
This parameter can be a value of @ref I2S_Audio_Frequency */
uint16_t I2S_CPOL; /*!< Specifies the idle state of the I2S clock.
This parameter can be a value of @ref I2S_Clock_Polarity */
}I2S_InitTypeDef;
/**
* @}
*/
/** @defgroup SPI_Exported_Constants
* @{
*/
#define IS_SPI_ALL_PERIPH(PERIPH) (((PERIPH) == SPI1) || \
((PERIPH) == SPI2) || \
((PERIPH) == SPI3))
#define IS_SPI_23_PERIPH(PERIPH) (((PERIPH) == SPI2) || \
((PERIPH) == SPI3))
/** @defgroup SPI_data_direction
* @{
*/
#define SPI_Direction_2Lines_FullDuplex ((uint16_t)0x0000)
#define SPI_Direction_2Lines_RxOnly ((uint16_t)0x0400)
#define SPI_Direction_1Line_Rx ((uint16_t)0x8000)
#define SPI_Direction_1Line_Tx ((uint16_t)0xC000)
#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \
((MODE) == SPI_Direction_2Lines_RxOnly) || \
((MODE) == SPI_Direction_1Line_Rx) || \
((MODE) == SPI_Direction_1Line_Tx))
/**
* @}
*/
/** @defgroup SPI_mode
* @{
*/
#define SPI_Mode_Master ((uint16_t)0x0104)
#define SPI_Mode_Slave ((uint16_t)0x0000)
#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \
((MODE) == SPI_Mode_Slave))
/**
* @}
*/
/** @defgroup SPI_data_size
* @{
*/
#define SPI_DataSize_16b ((uint16_t)0x0800)
#define SPI_DataSize_8b ((uint16_t)0x0000)
#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \
((DATASIZE) == SPI_DataSize_8b))
/**
* @}
*/
/** @defgroup SPI_Clock_Polarity
* @{
*/
#define SPI_CPOL_Low ((uint16_t)0x0000)
#define SPI_CPOL_High ((uint16_t)0x0002)
#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \
((CPOL) == SPI_CPOL_High))
/**
* @}
*/
/** @defgroup SPI_Clock_Phase
* @{
*/
#define SPI_CPHA_1Edge ((uint16_t)0x0000)
#define SPI_CPHA_2Edge ((uint16_t)0x0001)
#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \
((CPHA) == SPI_CPHA_2Edge))
/**
* @}
*/
/** @defgroup SPI_Slave_Select_management
* @{
*/
#define SPI_NSS_Soft ((uint16_t)0x0200)
#define SPI_NSS_Hard ((uint16_t)0x0000)
#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \
((NSS) == SPI_NSS_Hard))
/**
* @}
*/
/** @defgroup SPI_BaudRate_Prescaler
* @{
*/
#define SPI_BaudRatePrescaler_2 ((uint16_t)0x0000)
#define SPI_BaudRatePrescaler_4 ((uint16_t)0x0008)
#define SPI_BaudRatePrescaler_8 ((uint16_t)0x0010)
#define SPI_BaudRatePrescaler_16 ((uint16_t)0x0018)
#define SPI_BaudRatePrescaler_32 ((uint16_t)0x0020)
#define SPI_BaudRatePrescaler_64 ((uint16_t)0x0028)
#define SPI_BaudRatePrescaler_128 ((uint16_t)0x0030)
#define SPI_BaudRatePrescaler_256 ((uint16_t)0x0038)
#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \
((PRESCALER) == SPI_BaudRatePrescaler_4) || \
((PRESCALER) == SPI_BaudRatePrescaler_8) || \
((PRESCALER) == SPI_BaudRatePrescaler_16) || \
((PRESCALER) == SPI_BaudRatePrescaler_32) || \
((PRESCALER) == SPI_BaudRatePrescaler_64) || \
((PRESCALER) == SPI_BaudRatePrescaler_128) || \
((PRESCALER) == SPI_BaudRatePrescaler_256))
/**
* @}
*/
/** @defgroup SPI_MSB_LSB_transmission
* @{
*/
#define SPI_FirstBit_MSB ((uint16_t)0x0000)
#define SPI_FirstBit_LSB ((uint16_t)0x0080)
#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \
((BIT) == SPI_FirstBit_LSB))
/**
* @}
*/
/** @defgroup I2S_Mode
* @{
*/
#define I2S_Mode_SlaveTx ((uint16_t)0x0000)
#define I2S_Mode_SlaveRx ((uint16_t)0x0100)
#define I2S_Mode_MasterTx ((uint16_t)0x0200)
#define I2S_Mode_MasterRx ((uint16_t)0x0300)
#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \
((MODE) == I2S_Mode_SlaveRx) || \
((MODE) == I2S_Mode_MasterTx) || \
((MODE) == I2S_Mode_MasterRx) )
/**
* @}
*/
/** @defgroup I2S_Standard
* @{
*/
#define I2S_Standard_Phillips ((uint16_t)0x0000)
#define I2S_Standard_MSB ((uint16_t)0x0010)
#define I2S_Standard_LSB ((uint16_t)0x0020)
#define I2S_Standard_PCMShort ((uint16_t)0x0030)
#define I2S_Standard_PCMLong ((uint16_t)0x00B0)
#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \
((STANDARD) == I2S_Standard_MSB) || \
((STANDARD) == I2S_Standard_LSB) || \
((STANDARD) == I2S_Standard_PCMShort) || \
((STANDARD) == I2S_Standard_PCMLong))
/**
* @}
*/
/** @defgroup I2S_Data_Format
* @{
*/
#define I2S_DataFormat_16b ((uint16_t)0x0000)
#define I2S_DataFormat_16bextended ((uint16_t)0x0001)
#define I2S_DataFormat_24b ((uint16_t)0x0003)
#define I2S_DataFormat_32b ((uint16_t)0x0005)
#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \
((FORMAT) == I2S_DataFormat_16bextended) || \
((FORMAT) == I2S_DataFormat_24b) || \
((FORMAT) == I2S_DataFormat_32b))
/**
* @}
*/
/** @defgroup I2S_MCLK_Output
* @{
*/
#define I2S_MCLKOutput_Enable ((uint16_t)0x0200)
#define I2S_MCLKOutput_Disable ((uint16_t)0x0000)
#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \
((OUTPUT) == I2S_MCLKOutput_Disable))
/**
* @}
*/
/** @defgroup I2S_Audio_Frequency
* @{
*/
#define I2S_AudioFreq_192k ((uint32_t)192000)
#define I2S_AudioFreq_96k ((uint32_t)96000)
#define I2S_AudioFreq_48k ((uint32_t)48000)
#define I2S_AudioFreq_44k ((uint32_t)44100)
#define I2S_AudioFreq_32k ((uint32_t)32000)
#define I2S_AudioFreq_22k ((uint32_t)22050)
#define I2S_AudioFreq_16k ((uint32_t)16000)
#define I2S_AudioFreq_11k ((uint32_t)11025)
#define I2S_AudioFreq_8k ((uint32_t)8000)
#define I2S_AudioFreq_Default ((uint32_t)2)
#define IS_I2S_AUDIO_FREQ(FREQ) ((((FREQ) >= I2S_AudioFreq_8k) && \
((FREQ) <= I2S_AudioFreq_192k)) || \
((FREQ) == I2S_AudioFreq_Default))
/**
* @}
*/
/** @defgroup I2S_Clock_Polarity
* @{
*/
#define I2S_CPOL_Low ((uint16_t)0x0000)
#define I2S_CPOL_High ((uint16_t)0x0008)
#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \
((CPOL) == I2S_CPOL_High))
/**
* @}
*/
/** @defgroup SPI_I2S_DMA_transfer_requests
* @{
*/
#define SPI_I2S_DMAReq_Tx ((uint16_t)0x0002)
#define SPI_I2S_DMAReq_Rx ((uint16_t)0x0001)
#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFFFC) == 0x00) && ((DMAREQ) != 0x00))
/**
* @}
*/
/** @defgroup SPI_NSS_internal_software_management
* @{
*/
#define SPI_NSSInternalSoft_Set ((uint16_t)0x0100)
#define SPI_NSSInternalSoft_Reset ((uint16_t)0xFEFF)
#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \
((INTERNAL) == SPI_NSSInternalSoft_Reset))
/**
* @}
*/
/** @defgroup SPI_CRC_Transmit_Receive
* @{
*/
#define SPI_CRC_Tx ((uint8_t)0x00)
#define SPI_CRC_Rx ((uint8_t)0x01)
#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx))
/**
* @}
*/
/** @defgroup SPI_direction_transmit_receive
* @{
*/
#define SPI_Direction_Rx ((uint16_t)0xBFFF)
#define SPI_Direction_Tx ((uint16_t)0x4000)
#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \
((DIRECTION) == SPI_Direction_Tx))
/**
* @}
*/
/** @defgroup SPI_I2S_interrupts_definition
* @{
*/
#define SPI_I2S_IT_TXE ((uint8_t)0x71)
#define SPI_I2S_IT_RXNE ((uint8_t)0x60)
#define SPI_I2S_IT_ERR ((uint8_t)0x50)
#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \
((IT) == SPI_I2S_IT_RXNE) || \
((IT) == SPI_I2S_IT_ERR))
#define SPI_I2S_IT_OVR ((uint8_t)0x56)
#define SPI_IT_MODF ((uint8_t)0x55)
#define SPI_IT_CRCERR ((uint8_t)0x54)
#define I2S_IT_UDR ((uint8_t)0x53)
#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_IT_CRCERR))
#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE) || ((IT) == SPI_I2S_IT_TXE) || \
((IT) == I2S_IT_UDR) || ((IT) == SPI_IT_CRCERR) || \
((IT) == SPI_IT_MODF) || ((IT) == SPI_I2S_IT_OVR))
/**
* @}
*/
/** @defgroup SPI_I2S_flags_definition
* @{
*/
#define SPI_I2S_FLAG_RXNE ((uint16_t)0x0001)
#define SPI_I2S_FLAG_TXE ((uint16_t)0x0002)
#define I2S_FLAG_CHSIDE ((uint16_t)0x0004)
#define I2S_FLAG_UDR ((uint16_t)0x0008)
#define SPI_FLAG_CRCERR ((uint16_t)0x0010)
#define SPI_FLAG_MODF ((uint16_t)0x0020)
#define SPI_I2S_FLAG_OVR ((uint16_t)0x0040)
#define SPI_I2S_FLAG_BSY ((uint16_t)0x0080)
#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR))
#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \
((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \
((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \
((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE))
/**
* @}
*/
/** @defgroup SPI_CRC_polynomial
* @{
*/
#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1)
/**
* @}
*/
/**
* @}
*/
/** @defgroup SPI_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup SPI_Exported_Functions
* @{
*/
void SPI_I2S_DeInit(SPI_TypeDef* SPIx);
void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct);
void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct);
void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct);
void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct);
void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState);
void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState);
void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data);
uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx);
void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft);
void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState);
void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize);
void SPI_TransmitCRC(SPI_TypeDef* SPIx);
void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState);
uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC);
uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx);
void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction);
FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
#ifdef __cplusplus
}
#endif
#endif /*__STM32F10x_SPI_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,412 @@
/**
******************************************************************************
* @file stm32f10x_usart.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the USART
* firmware library.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_USART_H
#define __STM32F10x_USART_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup USART
* @{
*/
/** @defgroup USART_Exported_Types
* @{
*/
/**
* @brief USART Init Structure definition
*/
typedef struct
{
uint32_t USART_BaudRate; /*!< This member configures the USART communication baud rate.
The baud rate is computed using the following formula:
- IntegerDivider = ((PCLKx) / (16 * (USART_InitStruct->USART_BaudRate)))
- FractionalDivider = ((IntegerDivider - ((u32) IntegerDivider)) * 16) + 0.5 */
uint16_t USART_WordLength; /*!< Specifies the number of data bits transmitted or received in a frame.
This parameter can be a value of @ref USART_Word_Length */
uint16_t USART_StopBits; /*!< Specifies the number of stop bits transmitted.
This parameter can be a value of @ref USART_Stop_Bits */
uint16_t USART_Parity; /*!< Specifies the parity mode.
This parameter can be a value of @ref USART_Parity
@note When parity is enabled, the computed parity is inserted
at the MSB position of the transmitted data (9th bit when
the word length is set to 9 data bits; 8th bit when the
word length is set to 8 data bits). */
uint16_t USART_Mode; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled.
This parameter can be a value of @ref USART_Mode */
uint16_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled
or disabled.
This parameter can be a value of @ref USART_Hardware_Flow_Control */
} USART_InitTypeDef;
/**
* @brief USART Clock Init Structure definition
*/
typedef struct
{
uint16_t USART_Clock; /*!< Specifies whether the USART clock is enabled or disabled.
This parameter can be a value of @ref USART_Clock */
uint16_t USART_CPOL; /*!< Specifies the steady state value of the serial clock.
This parameter can be a value of @ref USART_Clock_Polarity */
uint16_t USART_CPHA; /*!< Specifies the clock transition on which the bit capture is made.
This parameter can be a value of @ref USART_Clock_Phase */
uint16_t USART_LastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted
data bit (MSB) has to be output on the SCLK pin in synchronous mode.
This parameter can be a value of @ref USART_Last_Bit */
} USART_ClockInitTypeDef;
/**
* @}
*/
/** @defgroup USART_Exported_Constants
* @{
*/
#define IS_USART_ALL_PERIPH(PERIPH) (((PERIPH) == USART1) || \
((PERIPH) == USART2) || \
((PERIPH) == USART3) || \
((PERIPH) == UART4) || \
((PERIPH) == UART5))
#define IS_USART_123_PERIPH(PERIPH) (((PERIPH) == USART1) || \
((PERIPH) == USART2) || \
((PERIPH) == USART3))
#define IS_USART_1234_PERIPH(PERIPH) (((PERIPH) == USART1) || \
((PERIPH) == USART2) || \
((PERIPH) == USART3) || \
((PERIPH) == UART4))
/** @defgroup USART_Word_Length
* @{
*/
#define USART_WordLength_8b ((uint16_t)0x0000)
#define USART_WordLength_9b ((uint16_t)0x1000)
#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \
((LENGTH) == USART_WordLength_9b))
/**
* @}
*/
/** @defgroup USART_Stop_Bits
* @{
*/
#define USART_StopBits_1 ((uint16_t)0x0000)
#define USART_StopBits_0_5 ((uint16_t)0x1000)
#define USART_StopBits_2 ((uint16_t)0x2000)
#define USART_StopBits_1_5 ((uint16_t)0x3000)
#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \
((STOPBITS) == USART_StopBits_0_5) || \
((STOPBITS) == USART_StopBits_2) || \
((STOPBITS) == USART_StopBits_1_5))
/**
* @}
*/
/** @defgroup USART_Parity
* @{
*/
#define USART_Parity_No ((uint16_t)0x0000)
#define USART_Parity_Even ((uint16_t)0x0400)
#define USART_Parity_Odd ((uint16_t)0x0600)
#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \
((PARITY) == USART_Parity_Even) || \
((PARITY) == USART_Parity_Odd))
/**
* @}
*/
/** @defgroup USART_Mode
* @{
*/
#define USART_Mode_Rx ((uint16_t)0x0004)
#define USART_Mode_Tx ((uint16_t)0x0008)
#define IS_USART_MODE(MODE) ((((MODE) & (uint16_t)0xFFF3) == 0x00) && ((MODE) != (uint16_t)0x00))
/**
* @}
*/
/** @defgroup USART_Hardware_Flow_Control
* @{
*/
#define USART_HardwareFlowControl_None ((uint16_t)0x0000)
#define USART_HardwareFlowControl_RTS ((uint16_t)0x0100)
#define USART_HardwareFlowControl_CTS ((uint16_t)0x0200)
#define USART_HardwareFlowControl_RTS_CTS ((uint16_t)0x0300)
#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\
(((CONTROL) == USART_HardwareFlowControl_None) || \
((CONTROL) == USART_HardwareFlowControl_RTS) || \
((CONTROL) == USART_HardwareFlowControl_CTS) || \
((CONTROL) == USART_HardwareFlowControl_RTS_CTS))
/**
* @}
*/
/** @defgroup USART_Clock
* @{
*/
#define USART_Clock_Disable ((uint16_t)0x0000)
#define USART_Clock_Enable ((uint16_t)0x0800)
#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \
((CLOCK) == USART_Clock_Enable))
/**
* @}
*/
/** @defgroup USART_Clock_Polarity
* @{
*/
#define USART_CPOL_Low ((uint16_t)0x0000)
#define USART_CPOL_High ((uint16_t)0x0400)
#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High))
/**
* @}
*/
/** @defgroup USART_Clock_Phase
* @{
*/
#define USART_CPHA_1Edge ((uint16_t)0x0000)
#define USART_CPHA_2Edge ((uint16_t)0x0200)
#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge))
/**
* @}
*/
/** @defgroup USART_Last_Bit
* @{
*/
#define USART_LastBit_Disable ((uint16_t)0x0000)
#define USART_LastBit_Enable ((uint16_t)0x0100)
#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \
((LASTBIT) == USART_LastBit_Enable))
/**
* @}
*/
/** @defgroup USART_Interrupt_definition
* @{
*/
#define USART_IT_PE ((uint16_t)0x0028)
#define USART_IT_TXE ((uint16_t)0x0727)
#define USART_IT_TC ((uint16_t)0x0626)
#define USART_IT_RXNE ((uint16_t)0x0525)
#define USART_IT_IDLE ((uint16_t)0x0424)
#define USART_IT_LBD ((uint16_t)0x0846)
#define USART_IT_CTS ((uint16_t)0x096A)
#define USART_IT_ERR ((uint16_t)0x0060)
#define USART_IT_ORE ((uint16_t)0x0360)
#define USART_IT_NE ((uint16_t)0x0260)
#define USART_IT_FE ((uint16_t)0x0160)
#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR))
#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \
((IT) == USART_IT_NE) || ((IT) == USART_IT_FE))
#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS))
/**
* @}
*/
/** @defgroup USART_DMA_Requests
* @{
*/
#define USART_DMAReq_Tx ((uint16_t)0x0080)
#define USART_DMAReq_Rx ((uint16_t)0x0040)
#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFF3F) == 0x00) && ((DMAREQ) != (uint16_t)0x00))
/**
* @}
*/
/** @defgroup USART_WakeUp_methods
* @{
*/
#define USART_WakeUp_IdleLine ((uint16_t)0x0000)
#define USART_WakeUp_AddressMark ((uint16_t)0x0800)
#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \
((WAKEUP) == USART_WakeUp_AddressMark))
/**
* @}
*/
/** @defgroup USART_LIN_Break_Detection_Length
* @{
*/
#define USART_LINBreakDetectLength_10b ((uint16_t)0x0000)
#define USART_LINBreakDetectLength_11b ((uint16_t)0x0020)
#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \
(((LENGTH) == USART_LINBreakDetectLength_10b) || \
((LENGTH) == USART_LINBreakDetectLength_11b))
/**
* @}
*/
/** @defgroup USART_IrDA_Low_Power
* @{
*/
#define USART_IrDAMode_LowPower ((uint16_t)0x0004)
#define USART_IrDAMode_Normal ((uint16_t)0x0000)
#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \
((MODE) == USART_IrDAMode_Normal))
/**
* @}
*/
/** @defgroup USART_Flags
* @{
*/
#define USART_FLAG_CTS ((uint16_t)0x0200)
#define USART_FLAG_LBD ((uint16_t)0x0100)
#define USART_FLAG_TXE ((uint16_t)0x0080)
#define USART_FLAG_TC ((uint16_t)0x0040)
#define USART_FLAG_RXNE ((uint16_t)0x0020)
#define USART_FLAG_IDLE ((uint16_t)0x0010)
#define USART_FLAG_ORE ((uint16_t)0x0008)
#define USART_FLAG_NE ((uint16_t)0x0004)
#define USART_FLAG_FE ((uint16_t)0x0002)
#define USART_FLAG_PE ((uint16_t)0x0001)
#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \
((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \
((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \
((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \
((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE))
#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFC9F) == 0x00) && ((FLAG) != (uint16_t)0x00))
#define IS_USART_PERIPH_FLAG(PERIPH, USART_FLAG) ((((*(uint32_t*)&(PERIPH)) != UART4_BASE) &&\
((*(uint32_t*)&(PERIPH)) != UART5_BASE)) \
|| ((USART_FLAG) != USART_FLAG_CTS))
#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x0044AA21))
#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF)
#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF)
/**
* @}
*/
/**
* @}
*/
/** @defgroup USART_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USART_Exported_Functions
* @{
*/
void USART_DeInit(USART_TypeDef* USARTx);
void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct);
void USART_StructInit(USART_InitTypeDef* USART_InitStruct);
void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct);
void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct);
void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState);
void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState);
void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address);
void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp);
void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength);
void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_SendData(USART_TypeDef* USARTx, uint16_t Data);
uint16_t USART_ReceiveData(USART_TypeDef* USARTx);
void USART_SendBreak(USART_TypeDef* USARTx);
void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime);
void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler);
void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode);
void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState);
FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG);
void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG);
ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT);
void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_USART_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Wyświetl plik

@ -0,0 +1,225 @@
/**
******************************************************************************
* @file misc.c
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file provides all the miscellaneous firmware functions (add-on
* to CMSIS functions).
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "misc.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @defgroup MISC
* @brief MISC driver modules
* @{
*/
/** @defgroup MISC_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup MISC_Private_Defines
* @{
*/
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
/**
* @}
*/
/** @defgroup MISC_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup MISC_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup MISC_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup MISC_Private_Functions
* @{
*/
/**
* @brief Configures the priority grouping: pre-emption priority and subpriority.
* @param NVIC_PriorityGroup: specifies the priority grouping bits length.
* This parameter can be one of the following values:
* @arg NVIC_PriorityGroup_0: 0 bits for pre-emption priority
* 4 bits for subpriority
* @arg NVIC_PriorityGroup_1: 1 bits for pre-emption priority
* 3 bits for subpriority
* @arg NVIC_PriorityGroup_2: 2 bits for pre-emption priority
* 2 bits for subpriority
* @arg NVIC_PriorityGroup_3: 3 bits for pre-emption priority
* 1 bits for subpriority
* @arg NVIC_PriorityGroup_4: 4 bits for pre-emption priority
* 0 bits for subpriority
* @retval None
*/
void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup)
{
/* Check the parameters */
assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup));
/* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */
SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup;
}
/**
* @brief Initializes the NVIC peripheral according to the specified
* parameters in the NVIC_InitStruct.
* @param NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure that contains
* the configuration information for the specified NVIC peripheral.
* @retval None
*/
void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct)
{
uint32_t tmppriority = 0x00, tmppre = 0x00, tmpsub = 0x0F;
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd));
assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority));
assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority));
if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE)
{
/* Compute the Corresponding IRQ Priority --------------------------------*/
tmppriority = (0x700 - ((SCB->AIRCR) & (uint32_t)0x700))>> 0x08;
tmppre = (0x4 - tmppriority);
tmpsub = tmpsub >> tmppriority;
tmppriority = (uint32_t)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre;
tmppriority |= NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub;
tmppriority = tmppriority << 0x04;
NVIC->IP[NVIC_InitStruct->NVIC_IRQChannel] = tmppriority;
/* Enable the Selected IRQ Channels --------------------------------------*/
NVIC->ISER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] =
(uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F);
}
else
{
/* Disable the Selected IRQ Channels -------------------------------------*/
NVIC->ICER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] =
(uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F);
}
}
/**
* @brief Sets the vector table location and Offset.
* @param NVIC_VectTab: specifies if the vector table is in RAM or FLASH memory.
* This parameter can be one of the following values:
* @arg NVIC_VectTab_RAM
* @arg NVIC_VectTab_FLASH
* @param Offset: Vector Table base offset field. This value must be a multiple
* of 0x200.
* @retval None
*/
void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset)
{
/* Check the parameters */
assert_param(IS_NVIC_VECTTAB(NVIC_VectTab));
assert_param(IS_NVIC_OFFSET(Offset));
SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80);
}
/**
* @brief Selects the condition for the system to enter low power mode.
* @param LowPowerMode: Specifies the new mode for the system to enter low power mode.
* This parameter can be one of the following values:
* @arg NVIC_LP_SEVONPEND
* @arg NVIC_LP_SLEEPDEEP
* @arg NVIC_LP_SLEEPONEXIT
* @param NewState: new state of LP condition. This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_NVIC_LP(LowPowerMode));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
SCB->SCR |= LowPowerMode;
}
else
{
SCB->SCR &= (uint32_t)(~(uint32_t)LowPowerMode);
}
}
/**
* @brief Configures the SysTick clock source.
* @param SysTick_CLKSource: specifies the SysTick clock source.
* This parameter can be one of the following values:
* @arg SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source.
* @arg SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source.
* @retval None
*/
void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource)
{
/* Check the parameters */
assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource));
if (SysTick_CLKSource == SysTick_CLKSource_HCLK)
{
SysTick->CTRL |= SysTick_CLKSource_HCLK;
}
else
{
SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8;
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,714 @@
/**
******************************************************************************
* @file stm32f10x_dma.c
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file provides all the DMA firmware functions.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_dma.h"
#include "stm32f10x_rcc.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @defgroup DMA
* @brief DMA driver modules
* @{
*/
/** @defgroup DMA_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup DMA_Private_Defines
* @{
*/
/* DMA1 Channelx interrupt pending bit masks */
#define DMA1_Channel1_IT_Mask ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1))
#define DMA1_Channel2_IT_Mask ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2))
#define DMA1_Channel3_IT_Mask ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3))
#define DMA1_Channel4_IT_Mask ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4))
#define DMA1_Channel5_IT_Mask ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5))
#define DMA1_Channel6_IT_Mask ((uint32_t)(DMA_ISR_GIF6 | DMA_ISR_TCIF6 | DMA_ISR_HTIF6 | DMA_ISR_TEIF6))
#define DMA1_Channel7_IT_Mask ((uint32_t)(DMA_ISR_GIF7 | DMA_ISR_TCIF7 | DMA_ISR_HTIF7 | DMA_ISR_TEIF7))
/* DMA2 Channelx interrupt pending bit masks */
#define DMA2_Channel1_IT_Mask ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1))
#define DMA2_Channel2_IT_Mask ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2))
#define DMA2_Channel3_IT_Mask ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3))
#define DMA2_Channel4_IT_Mask ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4))
#define DMA2_Channel5_IT_Mask ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5))
/* DMA2 FLAG mask */
#define FLAG_Mask ((uint32_t)0x10000000)
/* DMA registers Masks */
#define CCR_CLEAR_Mask ((uint32_t)0xFFFF800F)
/**
* @}
*/
/** @defgroup DMA_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup DMA_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup DMA_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup DMA_Private_Functions
* @{
*/
/**
* @brief Deinitializes the DMAy Channelx registers to their default reset
* values.
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
* @retval None
*/
void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx)
{
/* Check the parameters */
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
/* Disable the selected DMAy Channelx */
DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR1_EN);
/* Reset DMAy Channelx control register */
DMAy_Channelx->CCR = 0;
/* Reset DMAy Channelx remaining bytes register */
DMAy_Channelx->CNDTR = 0;
/* Reset DMAy Channelx peripheral address register */
DMAy_Channelx->CPAR = 0;
/* Reset DMAy Channelx memory address register */
DMAy_Channelx->CMAR = 0;
if (DMAy_Channelx == DMA1_Channel1)
{
/* Reset interrupt pending bits for DMA1 Channel1 */
DMA1->IFCR |= DMA1_Channel1_IT_Mask;
}
else if (DMAy_Channelx == DMA1_Channel2)
{
/* Reset interrupt pending bits for DMA1 Channel2 */
DMA1->IFCR |= DMA1_Channel2_IT_Mask;
}
else if (DMAy_Channelx == DMA1_Channel3)
{
/* Reset interrupt pending bits for DMA1 Channel3 */
DMA1->IFCR |= DMA1_Channel3_IT_Mask;
}
else if (DMAy_Channelx == DMA1_Channel4)
{
/* Reset interrupt pending bits for DMA1 Channel4 */
DMA1->IFCR |= DMA1_Channel4_IT_Mask;
}
else if (DMAy_Channelx == DMA1_Channel5)
{
/* Reset interrupt pending bits for DMA1 Channel5 */
DMA1->IFCR |= DMA1_Channel5_IT_Mask;
}
else if (DMAy_Channelx == DMA1_Channel6)
{
/* Reset interrupt pending bits for DMA1 Channel6 */
DMA1->IFCR |= DMA1_Channel6_IT_Mask;
}
else if (DMAy_Channelx == DMA1_Channel7)
{
/* Reset interrupt pending bits for DMA1 Channel7 */
DMA1->IFCR |= DMA1_Channel7_IT_Mask;
}
else if (DMAy_Channelx == DMA2_Channel1)
{
/* Reset interrupt pending bits for DMA2 Channel1 */
DMA2->IFCR |= DMA2_Channel1_IT_Mask;
}
else if (DMAy_Channelx == DMA2_Channel2)
{
/* Reset interrupt pending bits for DMA2 Channel2 */
DMA2->IFCR |= DMA2_Channel2_IT_Mask;
}
else if (DMAy_Channelx == DMA2_Channel3)
{
/* Reset interrupt pending bits for DMA2 Channel3 */
DMA2->IFCR |= DMA2_Channel3_IT_Mask;
}
else if (DMAy_Channelx == DMA2_Channel4)
{
/* Reset interrupt pending bits for DMA2 Channel4 */
DMA2->IFCR |= DMA2_Channel4_IT_Mask;
}
else
{
if (DMAy_Channelx == DMA2_Channel5)
{
/* Reset interrupt pending bits for DMA2 Channel5 */
DMA2->IFCR |= DMA2_Channel5_IT_Mask;
}
}
}
/**
* @brief Initializes the DMAy Channelx according to the specified
* parameters in the DMA_InitStruct.
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
* @param DMA_InitStruct: pointer to a DMA_InitTypeDef structure that
* contains the configuration information for the specified DMA Channel.
* @retval None
*/
void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
assert_param(IS_DMA_DIR(DMA_InitStruct->DMA_DIR));
assert_param(IS_DMA_BUFFER_SIZE(DMA_InitStruct->DMA_BufferSize));
assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc));
assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc));
assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize));
assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize));
assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode));
assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority));
assert_param(IS_DMA_M2M_STATE(DMA_InitStruct->DMA_M2M));
/*--------------------------- DMAy Channelx CCR Configuration -----------------*/
/* Get the DMAy_Channelx CCR value */
tmpreg = DMAy_Channelx->CCR;
/* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */
tmpreg &= CCR_CLEAR_Mask;
/* Configure DMAy Channelx: data transfer, data size, priority level and mode */
/* Set DIR bit according to DMA_DIR value */
/* Set CIRC bit according to DMA_Mode value */
/* Set PINC bit according to DMA_PeripheralInc value */
/* Set MINC bit according to DMA_MemoryInc value */
/* Set PSIZE bits according to DMA_PeripheralDataSize value */
/* Set MSIZE bits according to DMA_MemoryDataSize value */
/* Set PL bits according to DMA_Priority value */
/* Set the MEM2MEM bit according to DMA_M2M value */
tmpreg |= DMA_InitStruct->DMA_DIR | DMA_InitStruct->DMA_Mode |
DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc |
DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize |
DMA_InitStruct->DMA_Priority | DMA_InitStruct->DMA_M2M;
/* Write to DMAy Channelx CCR */
DMAy_Channelx->CCR = tmpreg;
/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/
/* Write to DMAy Channelx CNDTR */
DMAy_Channelx->CNDTR = DMA_InitStruct->DMA_BufferSize;
/*--------------------------- DMAy Channelx CPAR Configuration ----------------*/
/* Write to DMAy Channelx CPAR */
DMAy_Channelx->CPAR = DMA_InitStruct->DMA_PeripheralBaseAddr;
/*--------------------------- DMAy Channelx CMAR Configuration ----------------*/
/* Write to DMAy Channelx CMAR */
DMAy_Channelx->CMAR = DMA_InitStruct->DMA_MemoryBaseAddr;
}
/**
* @brief Fills each DMA_InitStruct member with its default value.
* @param DMA_InitStruct : pointer to a DMA_InitTypeDef structure which will
* be initialized.
* @retval None
*/
void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct)
{
/*-------------- Reset DMA init structure parameters values ------------------*/
/* Initialize the DMA_PeripheralBaseAddr member */
DMA_InitStruct->DMA_PeripheralBaseAddr = 0;
/* Initialize the DMA_MemoryBaseAddr member */
DMA_InitStruct->DMA_MemoryBaseAddr = 0;
/* Initialize the DMA_DIR member */
DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralSRC;
/* Initialize the DMA_BufferSize member */
DMA_InitStruct->DMA_BufferSize = 0;
/* Initialize the DMA_PeripheralInc member */
DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable;
/* Initialize the DMA_MemoryInc member */
DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable;
/* Initialize the DMA_PeripheralDataSize member */
DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
/* Initialize the DMA_MemoryDataSize member */
DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
/* Initialize the DMA_Mode member */
DMA_InitStruct->DMA_Mode = DMA_Mode_Normal;
/* Initialize the DMA_Priority member */
DMA_InitStruct->DMA_Priority = DMA_Priority_Low;
/* Initialize the DMA_M2M member */
DMA_InitStruct->DMA_M2M = DMA_M2M_Disable;
}
/**
* @brief Enables or disables the specified DMAy Channelx.
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
* @param NewState: new state of the DMAy Channelx.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected DMAy Channelx */
DMAy_Channelx->CCR |= DMA_CCR1_EN;
}
else
{
/* Disable the selected DMAy Channelx */
DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR1_EN);
}
}
/**
* @brief Enables or disables the specified DMAy Channelx interrupts.
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
* @param DMA_IT: specifies the DMA interrupts sources to be enabled
* or disabled.
* This parameter can be any combination of the following values:
* @arg DMA_IT_TC: Transfer complete interrupt mask
* @arg DMA_IT_HT: Half transfer interrupt mask
* @arg DMA_IT_TE: Transfer error interrupt mask
* @param NewState: new state of the specified DMA interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
assert_param(IS_DMA_CONFIG_IT(DMA_IT));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected DMA interrupts */
DMAy_Channelx->CCR |= DMA_IT;
}
else
{
/* Disable the selected DMA interrupts */
DMAy_Channelx->CCR &= ~DMA_IT;
}
}
/**
* @brief Sets the number of data units in the current DMAy Channelx transfer.
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
* @param DataNumber: The number of data units in the current DMAy Channelx
* transfer.
* @note This function can only be used when the DMAy_Channelx is disabled.
* @retval None.
*/
void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber)
{
/* Check the parameters */
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/
/* Write to DMAy Channelx CNDTR */
DMAy_Channelx->CNDTR = DataNumber;
}
/**
* @brief Returns the number of remaining data units in the current
* DMAy Channelx transfer.
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
* @retval The number of remaining data units in the current DMAy Channelx
* transfer.
*/
uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx)
{
/* Check the parameters */
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
/* Return the number of remaining data units for DMAy Channelx */
return ((uint16_t)(DMAy_Channelx->CNDTR));
}
/**
* @brief Checks whether the specified DMAy Channelx flag is set or not.
* @param DMAy_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag.
* @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
* @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
* @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
* @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag.
* @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
* @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
* @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
* @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag.
* @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
* @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
* @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
* @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag.
* @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
* @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
* @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
* @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag.
* @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
* @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
* @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
* @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag.
* @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
* @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
* @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
* @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag.
* @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
* @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
* @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
* @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag.
* @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
* @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
* @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
* @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag.
* @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
* @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
* @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
* @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag.
* @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
* @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
* @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
* @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag.
* @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
* @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
* @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
* @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag.
* @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
* @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
* @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
* @retval The new state of DMAy_FLAG (SET or RESET).
*/
FlagStatus DMA_GetFlagStatus(uint32_t DMAy_FLAG)
{
FlagStatus bitstatus = RESET;
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_DMA_GET_FLAG(DMAy_FLAG));
/* Calculate the used DMAy */
if ((DMAy_FLAG & FLAG_Mask) != (uint32_t)RESET)
{
/* Get DMA2 ISR register value */
tmpreg = DMA2->ISR ;
}
else
{
/* Get DMA1 ISR register value */
tmpreg = DMA1->ISR ;
}
/* Check the status of the specified DMAy flag */
if ((tmpreg & DMAy_FLAG) != (uint32_t)RESET)
{
/* DMAy_FLAG is set */
bitstatus = SET;
}
else
{
/* DMAy_FLAG is reset */
bitstatus = RESET;
}
/* Return the DMAy_FLAG status */
return bitstatus;
}
/**
* @brief Clears the DMAy Channelx's pending flags.
* @param DMAy_FLAG: specifies the flag to clear.
* This parameter can be any combination (for the same DMA) of the following values:
* @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag.
* @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
* @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
* @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
* @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag.
* @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
* @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
* @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
* @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag.
* @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
* @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
* @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
* @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag.
* @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
* @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
* @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
* @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag.
* @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
* @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
* @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
* @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag.
* @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
* @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
* @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
* @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag.
* @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
* @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
* @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
* @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag.
* @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
* @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
* @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
* @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag.
* @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
* @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
* @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
* @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag.
* @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
* @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
* @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
* @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag.
* @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
* @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
* @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
* @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag.
* @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
* @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
* @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
* @retval None
*/
void DMA_ClearFlag(uint32_t DMAy_FLAG)
{
/* Check the parameters */
assert_param(IS_DMA_CLEAR_FLAG(DMAy_FLAG));
/* Calculate the used DMAy */
if ((DMAy_FLAG & FLAG_Mask) != (uint32_t)RESET)
{
/* Clear the selected DMAy flags */
DMA2->IFCR = DMAy_FLAG;
}
else
{
/* Clear the selected DMAy flags */
DMA1->IFCR = DMAy_FLAG;
}
}
/**
* @brief Checks whether the specified DMAy Channelx interrupt has occurred or not.
* @param DMAy_IT: specifies the DMAy interrupt source to check.
* This parameter can be one of the following values:
* @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt.
* @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt.
* @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt.
* @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt.
* @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt.
* @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt.
* @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt.
* @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt.
* @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt.
* @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt.
* @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt.
* @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt.
* @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt.
* @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt.
* @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt.
* @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt.
* @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt.
* @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt.
* @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt.
* @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt.
* @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt.
* @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt.
* @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt.
* @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt.
* @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt.
* @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt.
* @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt.
* @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt.
* @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt.
* @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt.
* @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt.
* @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt.
* @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt.
* @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt.
* @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt.
* @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt.
* @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt.
* @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt.
* @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt.
* @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt.
* @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt.
* @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt.
* @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt.
* @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt.
* @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt.
* @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt.
* @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt.
* @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt.
* @retval The new state of DMAy_IT (SET or RESET).
*/
ITStatus DMA_GetITStatus(uint32_t DMAy_IT)
{
ITStatus bitstatus = RESET;
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_DMA_GET_IT(DMAy_IT));
/* Calculate the used DMA */
if ((DMAy_IT & FLAG_Mask) != (uint32_t)RESET)
{
/* Get DMA2 ISR register value */
tmpreg = DMA2->ISR;
}
else
{
/* Get DMA1 ISR register value */
tmpreg = DMA1->ISR;
}
/* Check the status of the specified DMAy interrupt */
if ((tmpreg & DMAy_IT) != (uint32_t)RESET)
{
/* DMAy_IT is set */
bitstatus = SET;
}
else
{
/* DMAy_IT is reset */
bitstatus = RESET;
}
/* Return the DMA_IT status */
return bitstatus;
}
/**
* @brief Clears the DMAy Channelx's interrupt pending bits.
* @param DMAy_IT: specifies the DMAy interrupt pending bit to clear.
* This parameter can be any combination (for the same DMA) of the following values:
* @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt.
* @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt.
* @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt.
* @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt.
* @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt.
* @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt.
* @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt.
* @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt.
* @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt.
* @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt.
* @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt.
* @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt.
* @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt.
* @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt.
* @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt.
* @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt.
* @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt.
* @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt.
* @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt.
* @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt.
* @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt.
* @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt.
* @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt.
* @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt.
* @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt.
* @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt.
* @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt.
* @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt.
* @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt.
* @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt.
* @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt.
* @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt.
* @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt.
* @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt.
* @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt.
* @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt.
* @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt.
* @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt.
* @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt.
* @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt.
* @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt.
* @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt.
* @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt.
* @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt.
* @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt.
* @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt.
* @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt.
* @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt.
* @retval None
*/
void DMA_ClearITPendingBit(uint32_t DMAy_IT)
{
/* Check the parameters */
assert_param(IS_DMA_CLEAR_IT(DMAy_IT));
/* Calculate the used DMAy */
if ((DMAy_IT & FLAG_Mask) != (uint32_t)RESET)
{
/* Clear the selected DMAy interrupt pending bits */
DMA2->IFCR = DMAy_IT;
}
else
{
/* Clear the selected DMAy interrupt pending bits */
DMA1->IFCR = DMAy_IT;
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,650 @@
/**
******************************************************************************
* @file stm32f10x_gpio.c
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file provides all the GPIO firmware functions.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_gpio.h"
#include "stm32f10x_rcc.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @defgroup GPIO
* @brief GPIO driver modules
* @{
*/
/** @defgroup GPIO_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup GPIO_Private_Defines
* @{
*/
/* ------------ RCC registers bit address in the alias region ----------------*/
#define AFIO_OFFSET (AFIO_BASE - PERIPH_BASE)
/* --- EVENTCR Register -----*/
/* Alias word address of EVOE bit */
#define EVCR_OFFSET (AFIO_OFFSET + 0x00)
#define EVOE_BitNumber ((uint8_t)0x07)
#define EVCR_EVOE_BB (PERIPH_BB_BASE + (EVCR_OFFSET * 32) + (EVOE_BitNumber * 4))
/* --- MAPR Register ---*/
/* Alias word address of MII_RMII_SEL bit */
#define MAPR_OFFSET (AFIO_OFFSET + 0x04)
#define MII_RMII_SEL_BitNumber ((u8)0x17)
#define MAPR_MII_RMII_SEL_BB (PERIPH_BB_BASE + (MAPR_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4))
#define EVCR_PORTPINCONFIG_MASK ((uint16_t)0xFF80)
#define LSB_MASK ((uint16_t)0xFFFF)
#define DBGAFR_POSITION_MASK ((uint32_t)0x000F0000)
#define DBGAFR_SWJCFG_MASK ((uint32_t)0xF0FFFFFF)
#define DBGAFR_LOCATION_MASK ((uint32_t)0x00200000)
#define DBGAFR_NUMBITS_MASK ((uint32_t)0x00100000)
/**
* @}
*/
/** @defgroup GPIO_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup GPIO_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup GPIO_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup GPIO_Private_Functions
* @{
*/
/**
* @brief Deinitializes the GPIOx peripheral registers to their default reset values.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @retval None
*/
void GPIO_DeInit(GPIO_TypeDef* GPIOx)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
if (GPIOx == GPIOA)
{
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, DISABLE);
}
else if (GPIOx == GPIOB)
{
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, DISABLE);
}
else if (GPIOx == GPIOC)
{
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, DISABLE);
}
else if (GPIOx == GPIOD)
{
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, DISABLE);
}
else if (GPIOx == GPIOE)
{
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, DISABLE);
}
else if (GPIOx == GPIOF)
{
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, DISABLE);
}
else
{
if (GPIOx == GPIOG)
{
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, DISABLE);
}
}
}
/**
* @brief Deinitializes the Alternate Functions (remap, event control
* and EXTI configuration) registers to their default reset values.
* @param None
* @retval None
*/
void GPIO_AFIODeInit(void)
{
RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, DISABLE);
}
/**
* @brief Initializes the GPIOx peripheral according to the specified
* parameters in the GPIO_InitStruct.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that
* contains the configuration information for the specified GPIO peripheral.
* @retval None
*/
void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct)
{
uint32_t currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00;
uint32_t tmpreg = 0x00, pinmask = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode));
assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin));
/*---------------------------- GPIO Mode Configuration -----------------------*/
currentmode = ((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x0F);
if ((((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x10)) != 0x00)
{
/* Check the parameters */
assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed));
/* Output mode */
currentmode |= (uint32_t)GPIO_InitStruct->GPIO_Speed;
}
/*---------------------------- GPIO CRL Configuration ------------------------*/
/* Configure the eight low port pins */
if (((uint32_t)GPIO_InitStruct->GPIO_Pin & ((uint32_t)0x00FF)) != 0x00)
{
tmpreg = GPIOx->CRL;
for (pinpos = 0x00; pinpos < 0x08; pinpos++)
{
pos = ((uint32_t)0x01) << pinpos;
/* Get the port pins position */
currentpin = (GPIO_InitStruct->GPIO_Pin) & pos;
if (currentpin == pos)
{
pos = pinpos << 2;
/* Clear the corresponding low control register bits */
pinmask = ((uint32_t)0x0F) << pos;
tmpreg &= ~pinmask;
/* Write the mode configuration in the corresponding bits */
tmpreg |= (currentmode << pos);
/* Reset the corresponding ODR bit */
if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD)
{
GPIOx->BRR = (((uint32_t)0x01) << pinpos);
}
else
{
/* Set the corresponding ODR bit */
if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU)
{
GPIOx->BSRR = (((uint32_t)0x01) << pinpos);
}
}
}
}
GPIOx->CRL = tmpreg;
}
/*---------------------------- GPIO CRH Configuration ------------------------*/
/* Configure the eight high port pins */
if (GPIO_InitStruct->GPIO_Pin > 0x00FF)
{
tmpreg = GPIOx->CRH;
for (pinpos = 0x00; pinpos < 0x08; pinpos++)
{
pos = (((uint32_t)0x01) << (pinpos + 0x08));
/* Get the port pins position */
currentpin = ((GPIO_InitStruct->GPIO_Pin) & pos);
if (currentpin == pos)
{
pos = pinpos << 2;
/* Clear the corresponding high control register bits */
pinmask = ((uint32_t)0x0F) << pos;
tmpreg &= ~pinmask;
/* Write the mode configuration in the corresponding bits */
tmpreg |= (currentmode << pos);
/* Reset the corresponding ODR bit */
if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD)
{
GPIOx->BRR = (((uint32_t)0x01) << (pinpos + 0x08));
}
/* Set the corresponding ODR bit */
if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU)
{
GPIOx->BSRR = (((uint32_t)0x01) << (pinpos + 0x08));
}
}
}
GPIOx->CRH = tmpreg;
}
}
/**
* @brief Fills each GPIO_InitStruct member with its default value.
* @param GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure which will
* be initialized.
* @retval None
*/
void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct)
{
/* Reset GPIO init structure parameters values */
GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All;
GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz;
GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN_FLOATING;
}
/**
* @brief Reads the specified input port pin.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bit to read.
* This parameter can be GPIO_Pin_x where x can be (0..15).
* @retval The input port pin value.
*/
uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
uint8_t bitstatus = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET)
{
bitstatus = (uint8_t)Bit_SET;
}
else
{
bitstatus = (uint8_t)Bit_RESET;
}
return bitstatus;
}
/**
* @brief Reads the specified GPIO input data port.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @retval GPIO input data port value.
*/
uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
return ((uint16_t)GPIOx->IDR);
}
/**
* @brief Reads the specified output data port bit.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bit to read.
* This parameter can be GPIO_Pin_x where x can be (0..15).
* @retval The output port pin value.
*/
uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
uint8_t bitstatus = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
if ((GPIOx->ODR & GPIO_Pin) != (uint32_t)Bit_RESET)
{
bitstatus = (uint8_t)Bit_SET;
}
else
{
bitstatus = (uint8_t)Bit_RESET;
}
return bitstatus;
}
/**
* @brief Reads the specified GPIO output data port.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @retval GPIO output data port value.
*/
uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
return ((uint16_t)GPIOx->ODR);
}
/**
* @brief Sets the selected data port bits.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bits to be written.
* This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
* @retval None
*/
void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN(GPIO_Pin));
GPIOx->BSRR = GPIO_Pin;
}
/**
* @brief Clears the selected data port bits.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bits to be written.
* This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
* @retval None
*/
void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN(GPIO_Pin));
GPIOx->BRR = GPIO_Pin;
}
/**
* @brief Sets or clears the selected data port bit.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bit to be written.
* This parameter can be one of GPIO_Pin_x where x can be (0..15).
* @param BitVal: specifies the value to be written to the selected bit.
* This parameter can be one of the BitAction enum values:
* @arg Bit_RESET: to clear the port pin
* @arg Bit_SET: to set the port pin
* @retval None
*/
void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
assert_param(IS_GPIO_BIT_ACTION(BitVal));
if (BitVal != Bit_RESET)
{
GPIOx->BSRR = GPIO_Pin;
}
else
{
GPIOx->BRR = GPIO_Pin;
}
}
/**
* @brief Writes data to the specified GPIO data port.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param PortVal: specifies the value to be written to the port output data register.
* @retval None
*/
void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
GPIOx->ODR = PortVal;
}
/**
* @brief Locks GPIO Pins configuration registers.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bit to be written.
* This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
* @retval None
*/
void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
uint32_t tmp = 0x00010000;
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN(GPIO_Pin));
tmp |= GPIO_Pin;
/* Set LCKK bit */
GPIOx->LCKR = tmp;
/* Reset LCKK bit */
GPIOx->LCKR = GPIO_Pin;
/* Set LCKK bit */
GPIOx->LCKR = tmp;
/* Read LCKK bit*/
tmp = GPIOx->LCKR;
/* Read LCKK bit*/
tmp = GPIOx->LCKR;
}
/**
* @brief Selects the GPIO pin used as Event output.
* @param GPIO_PortSource: selects the GPIO port to be used as source
* for Event output.
* This parameter can be GPIO_PortSourceGPIOx where x can be (A..E).
* @param GPIO_PinSource: specifies the pin for the Event output.
* This parameter can be GPIO_PinSourcex where x can be (0..15).
* @retval None
*/
void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource)
{
uint32_t tmpreg = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_EVENTOUT_PORT_SOURCE(GPIO_PortSource));
assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
tmpreg = AFIO->EVCR;
/* Clear the PORT[6:4] and PIN[3:0] bits */
tmpreg &= EVCR_PORTPINCONFIG_MASK;
tmpreg |= (uint32_t)GPIO_PortSource << 0x04;
tmpreg |= GPIO_PinSource;
AFIO->EVCR = tmpreg;
}
/**
* @brief Enables or disables the Event Output.
* @param NewState: new state of the Event output.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void GPIO_EventOutputCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(__IO uint32_t *) EVCR_EVOE_BB = (uint32_t)NewState;
}
/**
* @brief Changes the mapping of the specified pin.
* @param GPIO_Remap: selects the pin to remap.
* This parameter can be one of the following values:
* @arg GPIO_Remap_SPI1 : SPI1 Alternate Function mapping
* @arg GPIO_Remap_I2C1 : I2C1 Alternate Function mapping
* @arg GPIO_Remap_USART1 : USART1 Alternate Function mapping
* @arg GPIO_Remap_USART2 : USART2 Alternate Function mapping
* @arg GPIO_PartialRemap_USART3 : USART3 Partial Alternate Function mapping
* @arg GPIO_FullRemap_USART3 : USART3 Full Alternate Function mapping
* @arg GPIO_PartialRemap_TIM1 : TIM1 Partial Alternate Function mapping
* @arg GPIO_FullRemap_TIM1 : TIM1 Full Alternate Function mapping
* @arg GPIO_PartialRemap1_TIM2 : TIM2 Partial1 Alternate Function mapping
* @arg GPIO_PartialRemap2_TIM2 : TIM2 Partial2 Alternate Function mapping
* @arg GPIO_FullRemap_TIM2 : TIM2 Full Alternate Function mapping
* @arg GPIO_PartialRemap_TIM3 : TIM3 Partial Alternate Function mapping
* @arg GPIO_FullRemap_TIM3 : TIM3 Full Alternate Function mapping
* @arg GPIO_Remap_TIM4 : TIM4 Alternate Function mapping
* @arg GPIO_Remap1_CAN1 : CAN1 Alternate Function mapping
* @arg GPIO_Remap2_CAN1 : CAN1 Alternate Function mapping
* @arg GPIO_Remap_PD01 : PD01 Alternate Function mapping
* @arg GPIO_Remap_TIM5CH4_LSI : LSI connected to TIM5 Channel4 input capture for calibration
* @arg GPIO_Remap_ADC1_ETRGINJ : ADC1 External Trigger Injected Conversion remapping
* @arg GPIO_Remap_ADC1_ETRGREG : ADC1 External Trigger Regular Conversion remapping
* @arg GPIO_Remap_ADC2_ETRGINJ : ADC2 External Trigger Injected Conversion remapping
* @arg GPIO_Remap_ADC2_ETRGREG : ADC2 External Trigger Regular Conversion remapping
* @arg GPIO_Remap_ETH : Ethernet remapping (only for Connectivity line devices)
* @arg GPIO_Remap_CAN2 : CAN2 remapping (only for Connectivity line devices)
* @arg GPIO_Remap_SWJ_NoJTRST : Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST
* @arg GPIO_Remap_SWJ_JTAGDisable : JTAG-DP Disabled and SW-DP Enabled
* @arg GPIO_Remap_SWJ_Disable : Full SWJ Disabled (JTAG-DP + SW-DP)
* @arg GPIO_Remap_SPI3 : SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices)
* When the SPI3/I2S3 is remapped using this function, the SWJ is configured
* to Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST.
* @arg GPIO_Remap_TIM2ITR1_PTP_SOF : Ethernet PTP output or USB OTG SOF (Start of Frame) connected
* to TIM2 Internal Trigger 1 for calibration (only for Connectivity line devices)
* If the GPIO_Remap_TIM2ITR1_PTP_SOF is enabled the TIM2 ITR1 is connected to
* Ethernet PTP output. When Reset TIM2 ITR1 is connected to USB OTG SOF output.
* @arg GPIO_Remap_PTP_PPS : Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices)
* @arg GPIO_Remap_TIM15 : TIM15 Alternate Function mapping (only for Value line devices)
* @arg GPIO_Remap_TIM16 : TIM16 Alternate Function mapping (only for Value line devices)
* @arg GPIO_Remap_TIM17 : TIM17 Alternate Function mapping (only for Value line devices)
* @arg GPIO_Remap_CEC : CEC Alternate Function mapping (only for Value line devices)
* @arg GPIO_Remap_TIM1_DMA : TIM1 DMA requests mapping (only for Value line devices)
* @arg GPIO_Remap_TIM9 : TIM9 Alternate Function mapping (only for XL-density devices)
* @arg GPIO_Remap_TIM10 : TIM10 Alternate Function mapping (only for XL-density devices)
* @arg GPIO_Remap_TIM11 : TIM11 Alternate Function mapping (only for XL-density devices)
* @arg GPIO_Remap_TIM13 : TIM13 Alternate Function mapping (only for High density Value line and XL-density devices)
* @arg GPIO_Remap_TIM14 : TIM14 Alternate Function mapping (only for High density Value line and XL-density devices)
* @arg GPIO_Remap_FSMC_NADV : FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices)
* @arg GPIO_Remap_TIM67_DAC_DMA : TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices)
* @arg GPIO_Remap_TIM12 : TIM12 Alternate Function mapping (only for High density Value line devices)
* @arg GPIO_Remap_MISC : Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping,
* only for High density Value line devices)
* @param NewState: new state of the port pin remapping.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState)
{
uint32_t tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_REMAP(GPIO_Remap));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if((GPIO_Remap & 0x80000000) == 0x80000000)
{
tmpreg = AFIO->MAPR2;
}
else
{
tmpreg = AFIO->MAPR;
}
tmpmask = (GPIO_Remap & DBGAFR_POSITION_MASK) >> 0x10;
tmp = GPIO_Remap & LSB_MASK;
if ((GPIO_Remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK))
{
tmpreg &= DBGAFR_SWJCFG_MASK;
AFIO->MAPR &= DBGAFR_SWJCFG_MASK;
}
else if ((GPIO_Remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK)
{
tmp1 = ((uint32_t)0x03) << tmpmask;
tmpreg &= ~tmp1;
tmpreg |= ~DBGAFR_SWJCFG_MASK;
}
else
{
tmpreg &= ~(tmp << ((GPIO_Remap >> 0x15)*0x10));
tmpreg |= ~DBGAFR_SWJCFG_MASK;
}
if (NewState != DISABLE)
{
tmpreg |= (tmp << ((GPIO_Remap >> 0x15)*0x10));
}
if((GPIO_Remap & 0x80000000) == 0x80000000)
{
AFIO->MAPR2 = tmpreg;
}
else
{
AFIO->MAPR = tmpreg;
}
}
/**
* @brief Selects the GPIO pin used as EXTI Line.
* @param GPIO_PortSource: selects the GPIO port to be used as source for EXTI lines.
* This parameter can be GPIO_PortSourceGPIOx where x can be (A..G).
* @param GPIO_PinSource: specifies the EXTI line to be configured.
* This parameter can be GPIO_PinSourcex where x can be (0..15).
* @retval None
*/
void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource)
{
uint32_t tmp = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_EXTI_PORT_SOURCE(GPIO_PortSource));
assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
tmp = ((uint32_t)0x0F) << (0x04 * (GPIO_PinSource & (uint8_t)0x03));
AFIO->EXTICR[GPIO_PinSource >> 0x02] &= ~tmp;
AFIO->EXTICR[GPIO_PinSource >> 0x02] |= (((uint32_t)GPIO_PortSource) << (0x04 * (GPIO_PinSource & (uint8_t)0x03)));
}
/**
* @brief Selects the Ethernet media interface.
* @note This function applies only to STM32 Connectivity line devices.
* @param GPIO_ETH_MediaInterface: specifies the Media Interface mode.
* This parameter can be one of the following values:
* @arg GPIO_ETH_MediaInterface_MII: MII mode
* @arg GPIO_ETH_MediaInterface_RMII: RMII mode
* @retval None
*/
void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface)
{
assert_param(IS_GPIO_ETH_MEDIA_INTERFACE(GPIO_ETH_MediaInterface));
/* Configure MII_RMII selection bit */
*(__IO uint32_t *) MAPR_MII_RMII_SEL_BB = GPIO_ETH_MediaInterface;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,307 @@
/**
******************************************************************************
* @file stm32f10x_pwr.c
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file provides all the PWR firmware functions.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_pwr.h"
#include "stm32f10x_rcc.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @defgroup PWR
* @brief PWR driver modules
* @{
*/
/** @defgroup PWR_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup PWR_Private_Defines
* @{
*/
/* --------- PWR registers bit address in the alias region ---------- */
#define PWR_OFFSET (PWR_BASE - PERIPH_BASE)
/* --- CR Register ---*/
/* Alias word address of DBP bit */
#define CR_OFFSET (PWR_OFFSET + 0x00)
#define DBP_BitNumber 0x08
#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4))
/* Alias word address of PVDE bit */
#define PVDE_BitNumber 0x04
#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4))
/* --- CSR Register ---*/
/* Alias word address of EWUP bit */
#define CSR_OFFSET (PWR_OFFSET + 0x04)
#define EWUP_BitNumber 0x08
#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4))
/* ------------------ PWR registers bit mask ------------------------ */
/* CR register bit mask */
#define CR_DS_MASK ((uint32_t)0xFFFFFFFC)
#define CR_PLS_MASK ((uint32_t)0xFFFFFF1F)
/**
* @}
*/
/** @defgroup PWR_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup PWR_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup PWR_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup PWR_Private_Functions
* @{
*/
/**
* @brief Deinitializes the PWR peripheral registers to their default reset values.
* @param None
* @retval None
*/
void PWR_DeInit(void)
{
RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE);
}
/**
* @brief Enables or disables access to the RTC and backup registers.
* @param NewState: new state of the access to the RTC and backup registers.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void PWR_BackupAccessCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(__IO uint32_t *) CR_DBP_BB = (uint32_t)NewState;
}
/**
* @brief Enables or disables the Power Voltage Detector(PVD).
* @param NewState: new state of the PVD.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void PWR_PVDCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(__IO uint32_t *) CR_PVDE_BB = (uint32_t)NewState;
}
/**
* @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD).
* @param PWR_PVDLevel: specifies the PVD detection level
* This parameter can be one of the following values:
* @arg PWR_PVDLevel_2V2: PVD detection level set to 2.2V
* @arg PWR_PVDLevel_2V3: PVD detection level set to 2.3V
* @arg PWR_PVDLevel_2V4: PVD detection level set to 2.4V
* @arg PWR_PVDLevel_2V5: PVD detection level set to 2.5V
* @arg PWR_PVDLevel_2V6: PVD detection level set to 2.6V
* @arg PWR_PVDLevel_2V7: PVD detection level set to 2.7V
* @arg PWR_PVDLevel_2V8: PVD detection level set to 2.8V
* @arg PWR_PVDLevel_2V9: PVD detection level set to 2.9V
* @retval None
*/
void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel));
tmpreg = PWR->CR;
/* Clear PLS[7:5] bits */
tmpreg &= CR_PLS_MASK;
/* Set PLS[7:5] bits according to PWR_PVDLevel value */
tmpreg |= PWR_PVDLevel;
/* Store the new value */
PWR->CR = tmpreg;
}
/**
* @brief Enables or disables the WakeUp Pin functionality.
* @param NewState: new state of the WakeUp Pin functionality.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void PWR_WakeUpPinCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(__IO uint32_t *) CSR_EWUP_BB = (uint32_t)NewState;
}
/**
* @brief Enters STOP mode.
* @param PWR_Regulator: specifies the regulator state in STOP mode.
* This parameter can be one of the following values:
* @arg PWR_Regulator_ON: STOP mode with regulator ON
* @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode
* @param PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction.
* This parameter can be one of the following values:
* @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
* @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
* @retval None
*/
void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_PWR_REGULATOR(PWR_Regulator));
assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry));
/* Select the regulator state in STOP mode ---------------------------------*/
tmpreg = PWR->CR;
/* Clear PDDS and LPDS bits */
tmpreg &= CR_DS_MASK;
/* Set LPDS bit according to PWR_Regulator value */
tmpreg |= PWR_Regulator;
/* Store the new value */
PWR->CR = tmpreg;
/* Set SLEEPDEEP bit of Cortex System Control Register */
SCB->SCR |= SCB_SCR_SLEEPDEEP;
/* Select STOP mode entry --------------------------------------------------*/
if(PWR_STOPEntry == PWR_STOPEntry_WFI)
{
/* Request Wait For Interrupt */
__WFI();
}
else
{
/* Request Wait For Event */
__WFE();
}
/* Reset SLEEPDEEP bit of Cortex System Control Register */
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP);
}
/**
* @brief Enters STANDBY mode.
* @param None
* @retval None
*/
void PWR_EnterSTANDBYMode(void)
{
/* Clear Wake-up flag */
PWR->CR |= PWR_CR_CWUF;
/* Select STANDBY mode */
PWR->CR |= PWR_CR_PDDS;
/* Set SLEEPDEEP bit of Cortex System Control Register */
SCB->SCR |= SCB_SCR_SLEEPDEEP;
/* This option is used to ensure that store operations are completed */
#if defined ( __CC_ARM )
__force_stores();
#endif
/* Request Wait For Interrupt */
__WFI();
}
/**
* @brief Checks whether the specified PWR flag is set or not.
* @param PWR_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* @arg PWR_FLAG_WU: Wake Up flag
* @arg PWR_FLAG_SB: StandBy flag
* @arg PWR_FLAG_PVDO: PVD Output
* @retval The new state of PWR_FLAG (SET or RESET).
*/
FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_PWR_GET_FLAG(PWR_FLAG));
if ((PWR->CSR & PWR_FLAG) != (uint32_t)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
/* Return the flag status */
return bitstatus;
}
/**
* @brief Clears the PWR's pending flags.
* @param PWR_FLAG: specifies the flag to clear.
* This parameter can be one of the following values:
* @arg PWR_FLAG_WU: Wake Up flag
* @arg PWR_FLAG_SB: StandBy flag
* @retval None
*/
void PWR_ClearFlag(uint32_t PWR_FLAG)
{
/* Check the parameters */
assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG));
PWR->CR |= PWR_FLAG << 2;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,908 @@
/**
******************************************************************************
* @file stm32f10x_spi.c
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file provides all the SPI firmware functions.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_spi.h"
#include "stm32f10x_rcc.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @defgroup SPI
* @brief SPI driver modules
* @{
*/
/** @defgroup SPI_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup SPI_Private_Defines
* @{
*/
/* SPI SPE mask */
#define CR1_SPE_Set ((uint16_t)0x0040)
#define CR1_SPE_Reset ((uint16_t)0xFFBF)
/* I2S I2SE mask */
#define I2SCFGR_I2SE_Set ((uint16_t)0x0400)
#define I2SCFGR_I2SE_Reset ((uint16_t)0xFBFF)
/* SPI CRCNext mask */
#define CR1_CRCNext_Set ((uint16_t)0x1000)
/* SPI CRCEN mask */
#define CR1_CRCEN_Set ((uint16_t)0x2000)
#define CR1_CRCEN_Reset ((uint16_t)0xDFFF)
/* SPI SSOE mask */
#define CR2_SSOE_Set ((uint16_t)0x0004)
#define CR2_SSOE_Reset ((uint16_t)0xFFFB)
/* SPI registers Masks */
#define CR1_CLEAR_Mask ((uint16_t)0x3040)
#define I2SCFGR_CLEAR_Mask ((uint16_t)0xF040)
/* SPI or I2S mode selection masks */
#define SPI_Mode_Select ((uint16_t)0xF7FF)
#define I2S_Mode_Select ((uint16_t)0x0800)
/* I2S clock source selection masks */
#define I2S2_CLOCK_SRC ((uint32_t)(0x00020000))
#define I2S3_CLOCK_SRC ((uint32_t)(0x00040000))
#define I2S_MUL_MASK ((uint32_t)(0x0000F000))
#define I2S_DIV_MASK ((uint32_t)(0x000000F0))
/**
* @}
*/
/** @defgroup SPI_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup SPI_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup SPI_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup SPI_Private_Functions
* @{
*/
/**
* @brief Deinitializes the SPIx peripheral registers to their default
* reset values (Affects also the I2Ss).
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @retval None
*/
void SPI_I2S_DeInit(SPI_TypeDef* SPIx)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
if (SPIx == SPI1)
{
/* Enable SPI1 reset state */
RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE);
/* Release SPI1 from reset state */
RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE);
}
else if (SPIx == SPI2)
{
/* Enable SPI2 reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE);
/* Release SPI2 from reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE);
}
else
{
if (SPIx == SPI3)
{
/* Enable SPI3 reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE);
/* Release SPI3 from reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE);
}
}
}
/**
* @brief Initializes the SPIx peripheral according to the specified
* parameters in the SPI_InitStruct.
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure that
* contains the configuration information for the specified SPI peripheral.
* @retval None
*/
void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct)
{
uint16_t tmpreg = 0;
/* check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
/* Check the SPI parameters */
assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction));
assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode));
assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize));
assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL));
assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA));
assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS));
assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler));
assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit));
assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial));
/*---------------------------- SPIx CR1 Configuration ------------------------*/
/* Get the SPIx CR1 value */
tmpreg = SPIx->CR1;
/* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */
tmpreg &= CR1_CLEAR_Mask;
/* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler
master/salve mode, CPOL and CPHA */
/* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */
/* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */
/* Set LSBFirst bit according to SPI_FirstBit value */
/* Set BR bits according to SPI_BaudRatePrescaler value */
/* Set CPOL bit according to SPI_CPOL value */
/* Set CPHA bit according to SPI_CPHA value */
tmpreg |= (uint16_t)((uint32_t)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode |
SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL |
SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS |
SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit);
/* Write to SPIx CR1 */
SPIx->CR1 = tmpreg;
/* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */
SPIx->I2SCFGR &= SPI_Mode_Select;
/*---------------------------- SPIx CRCPOLY Configuration --------------------*/
/* Write to SPIx CRCPOLY */
SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial;
}
/**
* @brief Initializes the SPIx peripheral according to the specified
* parameters in the I2S_InitStruct.
* @param SPIx: where x can be 2 or 3 to select the SPI peripheral
* (configured in I2S mode).
* @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that
* contains the configuration information for the specified SPI peripheral
* configured in I2S mode.
* @note
* The function calculates the optimal prescaler needed to obtain the most
* accurate audio frequency (depending on the I2S clock source, the PLL values
* and the product configuration). But in case the prescaler value is greater
* than 511, the default value (0x02) will be configured instead. *
* @retval None
*/
void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct)
{
uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1;
uint32_t tmp = 0;
RCC_ClocksTypeDef RCC_Clocks;
uint32_t sourceclock = 0;
/* Check the I2S parameters */
assert_param(IS_SPI_23_PERIPH(SPIx));
assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode));
assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard));
assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat));
assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput));
assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq));
assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL));
/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/
/* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
SPIx->I2SCFGR &= I2SCFGR_CLEAR_Mask;
SPIx->I2SPR = 0x0002;
/* Get the I2SCFGR register value */
tmpreg = SPIx->I2SCFGR;
/* If the default value has to be written, reinitialize i2sdiv and i2sodd*/
if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default)
{
i2sodd = (uint16_t)0;
i2sdiv = (uint16_t)2;
}
/* If the requested audio frequency is not the default, compute the prescaler */
else
{
/* Check the frame length (For the Prescaler computing) */
if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b)
{
/* Packet length is 16 bits */
packetlength = 1;
}
else
{
/* Packet length is 32 bits */
packetlength = 2;
}
/* Get the I2S clock source mask depending on the peripheral number */
if(((uint32_t)SPIx) == SPI2_BASE)
{
/* The mask is relative to I2S2 */
tmp = I2S2_CLOCK_SRC;
}
else
{
/* The mask is relative to I2S3 */
tmp = I2S3_CLOCK_SRC;
}
/* Check the I2S clock source configuration depending on the Device:
Only Connectivity line devices have the PLL3 VCO clock */
#ifdef STM32F10X_CL
if((RCC->CFGR2 & tmp) != 0)
{
/* Get the configuration bits of RCC PLL3 multiplier */
tmp = (uint32_t)((RCC->CFGR2 & I2S_MUL_MASK) >> 12);
/* Get the value of the PLL3 multiplier */
if((tmp > 5) && (tmp < 15))
{
/* Multiplier is between 8 and 14 (value 15 is forbidden) */
tmp += 2;
}
else
{
if (tmp == 15)
{
/* Multiplier is 20 */
tmp = 20;
}
}
/* Get the PREDIV2 value */
sourceclock = (uint32_t)(((RCC->CFGR2 & I2S_DIV_MASK) >> 4) + 1);
/* Calculate the Source Clock frequency based on PLL3 and PREDIV2 values */
sourceclock = (uint32_t) ((HSE_Value / sourceclock) * tmp * 2);
}
else
{
/* I2S Clock source is System clock: Get System Clock frequency */
RCC_GetClocksFreq(&RCC_Clocks);
/* Get the source clock value: based on System Clock value */
sourceclock = RCC_Clocks.SYSCLK_Frequency;
}
#else /* STM32F10X_HD */
/* I2S Clock source is System clock: Get System Clock frequency */
RCC_GetClocksFreq(&RCC_Clocks);
/* Get the source clock value: based on System Clock value */
sourceclock = RCC_Clocks.SYSCLK_Frequency;
#endif /* STM32F10X_CL */
/* Compute the Real divider depending on the MCLK output state with a floating point */
if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable)
{
/* MCLK output is enabled */
tmp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5);
}
else
{
/* MCLK output is disabled */
tmp = (uint16_t)(((((sourceclock / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5);
}
/* Remove the floating point */
tmp = tmp / 10;
/* Check the parity of the divider */
i2sodd = (uint16_t)(tmp & (uint16_t)0x0001);
/* Compute the i2sdiv prescaler */
i2sdiv = (uint16_t)((tmp - i2sodd) / 2);
/* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */
i2sodd = (uint16_t) (i2sodd << 8);
}
/* Test if the divider is 1 or 0 or greater than 0xFF */
if ((i2sdiv < 2) || (i2sdiv > 0xFF))
{
/* Set the default values */
i2sdiv = 2;
i2sodd = 0;
}
/* Write to SPIx I2SPR register the computed value */
SPIx->I2SPR = (uint16_t)(i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput));
/* Configure the I2S with the SPI_InitStruct values */
tmpreg |= (uint16_t)(I2S_Mode_Select | (uint16_t)(I2S_InitStruct->I2S_Mode | \
(uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \
(uint16_t)I2S_InitStruct->I2S_CPOL))));
/* Write to SPIx I2SCFGR */
SPIx->I2SCFGR = tmpreg;
}
/**
* @brief Fills each SPI_InitStruct member with its default value.
* @param SPI_InitStruct : pointer to a SPI_InitTypeDef structure which will be initialized.
* @retval None
*/
void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct)
{
/*--------------- Reset SPI init structure parameters values -----------------*/
/* Initialize the SPI_Direction member */
SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex;
/* initialize the SPI_Mode member */
SPI_InitStruct->SPI_Mode = SPI_Mode_Slave;
/* initialize the SPI_DataSize member */
SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b;
/* Initialize the SPI_CPOL member */
SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low;
/* Initialize the SPI_CPHA member */
SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge;
/* Initialize the SPI_NSS member */
SPI_InitStruct->SPI_NSS = SPI_NSS_Hard;
/* Initialize the SPI_BaudRatePrescaler member */
SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2;
/* Initialize the SPI_FirstBit member */
SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB;
/* Initialize the SPI_CRCPolynomial member */
SPI_InitStruct->SPI_CRCPolynomial = 7;
}
/**
* @brief Fills each I2S_InitStruct member with its default value.
* @param I2S_InitStruct : pointer to a I2S_InitTypeDef structure which will be initialized.
* @retval None
*/
void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct)
{
/*--------------- Reset I2S init structure parameters values -----------------*/
/* Initialize the I2S_Mode member */
I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx;
/* Initialize the I2S_Standard member */
I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips;
/* Initialize the I2S_DataFormat member */
I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b;
/* Initialize the I2S_MCLKOutput member */
I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable;
/* Initialize the I2S_AudioFreq member */
I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default;
/* Initialize the I2S_CPOL member */
I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low;
}
/**
* @brief Enables or disables the specified SPI peripheral.
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @param NewState: new state of the SPIx peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected SPI peripheral */
SPIx->CR1 |= CR1_SPE_Set;
}
else
{
/* Disable the selected SPI peripheral */
SPIx->CR1 &= CR1_SPE_Reset;
}
}
/**
* @brief Enables or disables the specified SPI peripheral (in I2S mode).
* @param SPIx: where x can be 2 or 3 to select the SPI peripheral.
* @param NewState: new state of the SPIx peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_SPI_23_PERIPH(SPIx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected SPI peripheral (in I2S mode) */
SPIx->I2SCFGR |= I2SCFGR_I2SE_Set;
}
else
{
/* Disable the selected SPI peripheral (in I2S mode) */
SPIx->I2SCFGR &= I2SCFGR_I2SE_Reset;
}
}
/**
* @brief Enables or disables the specified SPI/I2S interrupts.
* @param SPIx: where x can be
* - 1, 2 or 3 in SPI mode
* - 2 or 3 in I2S mode
* @param SPI_I2S_IT: specifies the SPI/I2S interrupt source to be enabled or disabled.
* This parameter can be one of the following values:
* @arg SPI_I2S_IT_TXE: Tx buffer empty interrupt mask
* @arg SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask
* @arg SPI_I2S_IT_ERR: Error interrupt mask
* @param NewState: new state of the specified SPI/I2S interrupt.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState)
{
uint16_t itpos = 0, itmask = 0 ;
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT));
/* Get the SPI/I2S IT index */
itpos = SPI_I2S_IT >> 4;
/* Set the IT mask */
itmask = (uint16_t)1 << (uint16_t)itpos;
if (NewState != DISABLE)
{
/* Enable the selected SPI/I2S interrupt */
SPIx->CR2 |= itmask;
}
else
{
/* Disable the selected SPI/I2S interrupt */
SPIx->CR2 &= (uint16_t)~itmask;
}
}
/**
* @brief Enables or disables the SPIx/I2Sx DMA interface.
* @param SPIx: where x can be
* - 1, 2 or 3 in SPI mode
* - 2 or 3 in I2S mode
* @param SPI_I2S_DMAReq: specifies the SPI/I2S DMA transfer request to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request
* @arg SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request
* @param NewState: new state of the selected SPI/I2S DMA transfer request.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq));
if (NewState != DISABLE)
{
/* Enable the selected SPI/I2S DMA requests */
SPIx->CR2 |= SPI_I2S_DMAReq;
}
else
{
/* Disable the selected SPI/I2S DMA requests */
SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq;
}
}
/**
* @brief Transmits a Data through the SPIx/I2Sx peripheral.
* @param SPIx: where x can be
* - 1, 2 or 3 in SPI mode
* - 2 or 3 in I2S mode
* @param Data : Data to be transmitted.
* @retval None
*/
void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
/* Write in the DR register the data to be sent */
SPIx->DR = Data;
}
/**
* @brief Returns the most recent received data by the SPIx/I2Sx peripheral.
* @param SPIx: where x can be
* - 1, 2 or 3 in SPI mode
* - 2 or 3 in I2S mode
* @retval The value of the received data.
*/
uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
/* Return the data in the DR register */
return SPIx->DR;
}
/**
* @brief Configures internally by software the NSS pin for the selected SPI.
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @param SPI_NSSInternalSoft: specifies the SPI NSS internal state.
* This parameter can be one of the following values:
* @arg SPI_NSSInternalSoft_Set: Set NSS pin internally
* @arg SPI_NSSInternalSoft_Reset: Reset NSS pin internally
* @retval None
*/
void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft));
if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset)
{
/* Set NSS pin internally by software */
SPIx->CR1 |= SPI_NSSInternalSoft_Set;
}
else
{
/* Reset NSS pin internally by software */
SPIx->CR1 &= SPI_NSSInternalSoft_Reset;
}
}
/**
* @brief Enables or disables the SS output for the selected SPI.
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @param NewState: new state of the SPIx SS output.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected SPI SS output */
SPIx->CR2 |= CR2_SSOE_Set;
}
else
{
/* Disable the selected SPI SS output */
SPIx->CR2 &= CR2_SSOE_Reset;
}
}
/**
* @brief Configures the data size for the selected SPI.
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @param SPI_DataSize: specifies the SPI data size.
* This parameter can be one of the following values:
* @arg SPI_DataSize_16b: Set data frame format to 16bit
* @arg SPI_DataSize_8b: Set data frame format to 8bit
* @retval None
*/
void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_SPI_DATASIZE(SPI_DataSize));
/* Clear DFF bit */
SPIx->CR1 &= (uint16_t)~SPI_DataSize_16b;
/* Set new DFF bit value */
SPIx->CR1 |= SPI_DataSize;
}
/**
* @brief Transmit the SPIx CRC value.
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @retval None
*/
void SPI_TransmitCRC(SPI_TypeDef* SPIx)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
/* Enable the selected SPI CRC transmission */
SPIx->CR1 |= CR1_CRCNext_Set;
}
/**
* @brief Enables or disables the CRC value calculation of the transferred bytes.
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @param NewState: new state of the SPIx CRC value calculation.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected SPI CRC calculation */
SPIx->CR1 |= CR1_CRCEN_Set;
}
else
{
/* Disable the selected SPI CRC calculation */
SPIx->CR1 &= CR1_CRCEN_Reset;
}
}
/**
* @brief Returns the transmit or the receive CRC register value for the specified SPI.
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @param SPI_CRC: specifies the CRC register to be read.
* This parameter can be one of the following values:
* @arg SPI_CRC_Tx: Selects Tx CRC register
* @arg SPI_CRC_Rx: Selects Rx CRC register
* @retval The selected CRC register value..
*/
uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC)
{
uint16_t crcreg = 0;
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_SPI_CRC(SPI_CRC));
if (SPI_CRC != SPI_CRC_Rx)
{
/* Get the Tx CRC register */
crcreg = SPIx->TXCRCR;
}
else
{
/* Get the Rx CRC register */
crcreg = SPIx->RXCRCR;
}
/* Return the selected CRC register */
return crcreg;
}
/**
* @brief Returns the CRC Polynomial register value for the specified SPI.
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @retval The CRC Polynomial register value.
*/
uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
/* Return the CRC polynomial register */
return SPIx->CRCPR;
}
/**
* @brief Selects the data transfer direction in bi-directional mode for the specified SPI.
* @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
* @param SPI_Direction: specifies the data transfer direction in bi-directional mode.
* This parameter can be one of the following values:
* @arg SPI_Direction_Tx: Selects Tx transmission direction
* @arg SPI_Direction_Rx: Selects Rx receive direction
* @retval None
*/
void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_SPI_DIRECTION(SPI_Direction));
if (SPI_Direction == SPI_Direction_Tx)
{
/* Set the Tx only mode */
SPIx->CR1 |= SPI_Direction_Tx;
}
else
{
/* Set the Rx only mode */
SPIx->CR1 &= SPI_Direction_Rx;
}
}
/**
* @brief Checks whether the specified SPI/I2S flag is set or not.
* @param SPIx: where x can be
* - 1, 2 or 3 in SPI mode
* - 2 or 3 in I2S mode
* @param SPI_I2S_FLAG: specifies the SPI/I2S flag to check.
* This parameter can be one of the following values:
* @arg SPI_I2S_FLAG_TXE: Transmit buffer empty flag.
* @arg SPI_I2S_FLAG_RXNE: Receive buffer not empty flag.
* @arg SPI_I2S_FLAG_BSY: Busy flag.
* @arg SPI_I2S_FLAG_OVR: Overrun flag.
* @arg SPI_FLAG_MODF: Mode Fault flag.
* @arg SPI_FLAG_CRCERR: CRC Error flag.
* @arg I2S_FLAG_UDR: Underrun Error flag.
* @arg I2S_FLAG_CHSIDE: Channel Side flag.
* @retval The new state of SPI_I2S_FLAG (SET or RESET).
*/
FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG));
/* Check the status of the specified SPI/I2S flag */
if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET)
{
/* SPI_I2S_FLAG is set */
bitstatus = SET;
}
else
{
/* SPI_I2S_FLAG is reset */
bitstatus = RESET;
}
/* Return the SPI_I2S_FLAG status */
return bitstatus;
}
/**
* @brief Clears the SPIx CRC Error (CRCERR) flag.
* @param SPIx: where x can be
* - 1, 2 or 3 in SPI mode
* @param SPI_I2S_FLAG: specifies the SPI flag to clear.
* This function clears only CRCERR flag.
* @note
* - OVR (OverRun error) flag is cleared by software sequence: a read
* operation to SPI_DR register (SPI_I2S_ReceiveData()) followed by a read
* operation to SPI_SR register (SPI_I2S_GetFlagStatus()).
* - UDR (UnderRun error) flag is cleared by a read operation to
* SPI_SR register (SPI_I2S_GetFlagStatus()).
* - MODF (Mode Fault) flag is cleared by software sequence: a read/write
* operation to SPI_SR register (SPI_I2S_GetFlagStatus()) followed by a
* write operation to SPI_CR1 register (SPI_Cmd() to enable the SPI).
* @retval None
*/
void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG)
{
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG));
/* Clear the selected SPI CRC Error (CRCERR) flag */
SPIx->SR = (uint16_t)~SPI_I2S_FLAG;
}
/**
* @brief Checks whether the specified SPI/I2S interrupt has occurred or not.
* @param SPIx: where x can be
* - 1, 2 or 3 in SPI mode
* - 2 or 3 in I2S mode
* @param SPI_I2S_IT: specifies the SPI/I2S interrupt source to check.
* This parameter can be one of the following values:
* @arg SPI_I2S_IT_TXE: Transmit buffer empty interrupt.
* @arg SPI_I2S_IT_RXNE: Receive buffer not empty interrupt.
* @arg SPI_I2S_IT_OVR: Overrun interrupt.
* @arg SPI_IT_MODF: Mode Fault interrupt.
* @arg SPI_IT_CRCERR: CRC Error interrupt.
* @arg I2S_IT_UDR: Underrun Error interrupt.
* @retval The new state of SPI_I2S_IT (SET or RESET).
*/
ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT)
{
ITStatus bitstatus = RESET;
uint16_t itpos = 0, itmask = 0, enablestatus = 0;
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT));
/* Get the SPI/I2S IT index */
itpos = 0x01 << (SPI_I2S_IT & 0x0F);
/* Get the SPI/I2S IT mask */
itmask = SPI_I2S_IT >> 4;
/* Set the IT mask */
itmask = 0x01 << itmask;
/* Get the SPI_I2S_IT enable bit status */
enablestatus = (SPIx->CR2 & itmask) ;
/* Check the status of the specified SPI/I2S interrupt */
if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus)
{
/* SPI_I2S_IT is set */
bitstatus = SET;
}
else
{
/* SPI_I2S_IT is reset */
bitstatus = RESET;
}
/* Return the SPI_I2S_IT status */
return bitstatus;
}
/**
* @brief Clears the SPIx CRC Error (CRCERR) interrupt pending bit.
* @param SPIx: where x can be
* - 1, 2 or 3 in SPI mode
* @param SPI_I2S_IT: specifies the SPI interrupt pending bit to clear.
* This function clears only CRCERR interrupt pending bit.
* @note
* - OVR (OverRun Error) interrupt pending bit is cleared by software
* sequence: a read operation to SPI_DR register (SPI_I2S_ReceiveData())
* followed by a read operation to SPI_SR register (SPI_I2S_GetITStatus()).
* - UDR (UnderRun Error) interrupt pending bit is cleared by a read
* operation to SPI_SR register (SPI_I2S_GetITStatus()).
* - MODF (Mode Fault) interrupt pending bit is cleared by software sequence:
* a read/write operation to SPI_SR register (SPI_I2S_GetITStatus())
* followed by a write operation to SPI_CR1 register (SPI_Cmd() to enable
* the SPI).
* @retval None
*/
void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT)
{
uint16_t itpos = 0;
/* Check the parameters */
assert_param(IS_SPI_ALL_PERIPH(SPIx));
assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT));
/* Get the SPI IT index */
itpos = 0x01 << (SPI_I2S_IT & 0x0F);
/* Clear the selected SPI CRC Error (CRCERR) interrupt pending bit */
SPIx->SR = (uint16_t)~itpos;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

Plik diff jest za duży Load Diff

Plik diff jest za duży Load Diff

297
src/hal/system.c 100644
Wyświetl plik

@ -0,0 +1,297 @@
#include <stdint.h>
#include <system_stm32f10x.h>
#include <stm32f10x_rcc.h>
#include <stm32f10x_flash.h>
#include <stm32f10x_gpio.h>
#include <stm32f10x_dma.h>
#include <stm32f10x_adc.h>
#include <stm32f10x_tim.h>
#include <misc.h>
#include "system.h"
#include "delay.h"
#include "log.h"
#define BUTTON_PRESS_LONG_COUNT SYSTEM_SCHEDULER_TIMER_TICKS_PER_SECOND
#define ADC1_DR_Address ((uint32_t) 0x4001244C)
__IO uint16_t dma_buffer_adc[2];
volatile uint32_t button_pressed = 0;
void (*system_handle_timer_tick)() = NULL;
static volatile uint32_t systick_counter = 0;
static void nvic_init()
{
#ifdef VECT_TAB_RAM
NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
#else // VECT_TAB_FLASH
NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
#endif
}
// TODO: Find out how to configure watchdog!
static void rcc_init()
{
RCC_DeInit();
RCC_HSEConfig(RCC_HSE_ON);
ErrorStatus hse_status = RCC_WaitForHSEStartUp();
if (hse_status != SUCCESS) {
// If HSE fails to start up, the application will have incorrect clock configuration.
while (true) {}
}
//SystemInit();
FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
FLASH_SetLatency(FLASH_Latency_0);
RCC_HCLKConfig(RCC_SYSCLK_Div1); // Was: RCC_SYSCLK_Div4
RCC_PCLK2Config(RCC_HCLK_Div1); // Was: 4
RCC_PCLK1Config(RCC_HCLK_Div1); // Was: 2
RCC_SYSCLKConfig(RCC_SYSCLKSource_HSE);
while (RCC_GetSYSCLKSource() != 0x04);
}
static void gpio_init()
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, DISABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
GPIO_InitTypeDef gpio_init;
// Shutdown request
gpio_init.GPIO_Pin = GPIO_Pin_12;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOA, &gpio_init);
// Battery voltage (analog)
gpio_init.GPIO_Mode = GPIO_Mode_AIN;
gpio_init.GPIO_Pin = GPIO_Pin_5;
GPIO_Init(GPIOA, &gpio_init);
// Button state (analog)
gpio_init.GPIO_Mode = GPIO_Mode_AIN;
gpio_init.GPIO_Pin = GPIO_Pin_6;
GPIO_Init(GPIOA, &gpio_init);
// LEDs
gpio_init.GPIO_Pin = GPIO_PIN_LED_GREEN | GPIO_PIN_LED_RED;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOB, &gpio_init);
}
/**
* Configure continuous DMA transfer for ADC from pins PA5 and PA6
* to have battery voltage and button state available at all times.
*/
static void dma_adc_init()
{
DMA_DeInit(DMA1_Channel1);
DMA_InitTypeDef dma_init;
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
dma_init.DMA_BufferSize = 2;
dma_init.DMA_DIR = DMA_DIR_PeripheralSRC;
dma_init.DMA_M2M = DMA_M2M_Disable;
dma_init.DMA_MemoryBaseAddr = (uint32_t) &dma_buffer_adc;
dma_init.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable;
dma_init.DMA_Mode = DMA_Mode_Circular;
dma_init.DMA_PeripheralBaseAddr = ADC1_DR_Address;
dma_init.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
dma_init.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
dma_init.DMA_Priority = DMA_Priority_High;
DMA_Init(DMA1_Channel1, &dma_init);
DMA_Cmd(DMA1_Channel1, ENABLE);
RCC_ADCCLKConfig(RCC_PCLK2_Div2);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
ADC_InitTypeDef adc_init;
adc_init.ADC_Mode = ADC_Mode_Independent;
adc_init.ADC_ScanConvMode = ENABLE;
adc_init.ADC_ContinuousConvMode = ENABLE;
adc_init.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
adc_init.ADC_DataAlign = ADC_DataAlign_Right;
adc_init.ADC_NbrOfChannel = 2;
ADC_Init(ADC1, &adc_init);
ADC_RegularChannelConfig(ADC1, ADC_Channel_5, 1, ADC_SampleTime_28Cycles5);
ADC_RegularChannelConfig(ADC1, ADC_Channel_6, 2, ADC_SampleTime_28Cycles5);
// ADC1 DMA requests are routed to DMA1 Channel1
ADC_DMACmd(ADC1, ENABLE);
ADC_Cmd(ADC1, ENABLE);
ADC_ResetCalibration(ADC1);
while (ADC_GetResetCalibrationStatus(ADC1));
// Start new calibration (ADC must be off at that time)
ADC_StartCalibration(ADC1);
while (ADC_GetCalibrationStatus(ADC1));
// Start conversion (will be endless as we are in continuous mode)
ADC_SoftwareStartConvCmd(ADC1, ENABLE);
}
uint16_t system_get_battery_voltage_millivolts()
{
return (uint16_t) (((float) dma_buffer_adc[0]) * 10.0f * 600.0f / 4096.0f);
}
void system_shutdown()
{
GPIO_SetBits(GPIOA, GPIO_Pin_12);
}
void system_handle_button()
{
static uint16_t button_pressed_threshold = 0;
static bool shutdown = false;
uint16_t current_value = dma_buffer_adc[1];
if (current_value > button_pressed_threshold) {
button_pressed++;
if (button_pressed >= BUTTON_PRESS_LONG_COUNT) {
shutdown = true;
}
} else {
if (shutdown) {
system_shutdown();
}
button_pressed = 0;
}
if (button_pressed == 0) {
button_pressed_threshold = current_value * 1.1;
}
}
bool system_is_button_pressed()
{
return button_pressed > 0;
}
void system_scheduler_timer_init()
{
// Timer frequency = TIM_CLK/(TIM_PSC+1)/(TIM_ARR + 1)
// TIM_CLK =
// TIM_PSC = Prescaler
// TIM_ARR = Period
TIM_DeInit(TIM4);
TIM_TimeBaseInitTypeDef tim_init;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE);
tim_init.TIM_Prescaler = 24 - 1; // tick every 1/1000000 s
tim_init.TIM_CounterMode = TIM_CounterMode_Up;
tim_init.TIM_Period = 100 - 1; // update every 1/10000 s
tim_init.TIM_ClockDivision = TIM_CKD_DIV1;
tim_init.TIM_RepetitionCounter = 0;
TIM_TimeBaseInit(TIM4, &tim_init);
TIM_ClearITPendingBit(TIM4, TIM_IT_Update);
TIM_ITConfig(TIM4, TIM_IT_Update, ENABLE);
NVIC_InitTypeDef nvic_init;
nvic_init.NVIC_IRQChannel = TIM4_IRQn;
nvic_init.NVIC_IRQChannelPreemptionPriority = 3;
nvic_init.NVIC_IRQChannelSubPriority = 1;
nvic_init.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic_init);
TIM_Cmd(TIM4, ENABLE);
}
void system_set_green_led(bool enabled)
{
if (enabled) {
GPIO_ResetBits(GPIOB, GPIO_PIN_LED_GREEN);
} else {
GPIO_SetBits(GPIOB, GPIO_PIN_LED_GREEN);
}
}
void system_set_red_led(bool enabled)
{
if (enabled) {
GPIO_ResetBits(GPIOB, GPIO_PIN_LED_RED);
} else {
GPIO_SetBits(GPIOB, GPIO_PIN_LED_RED);
}
}
void system_disable_irq()
{
__disable_irq();
}
void system_enable_irq()
{
__enable_irq();
}
void system_init()
{
rcc_init();
nvic_init();
gpio_init();
dma_adc_init();
delay_init();
system_scheduler_timer_init();
RCC_ClocksTypeDef RCC_Clocks;
RCC_GetClocksFreq(&RCC_Clocks);
log_info("HCLK: %ld\n", RCC_Clocks.HCLK_Frequency);
log_info("SYSCLK: %ld\n", RCC_Clocks.SYSCLK_Frequency);
log_info("SystemCoreClock: %ld\n", SystemCoreClock);
delay_ms(100);
SysTick_Config(SystemCoreClock / 10000);
}
uint32_t system_get_tick()
{
return systick_counter;
}
// TODO: create RTTY / FSK encoder for Si5351
// TODO: create RTTY / FSK encoder for Si4032
// TODO: create CW / OOK encoder -- the same one should work for both Si5351 and Si4032
void SysTick_Handler()
{
systick_counter++;
}
void TIM4_IRQHandler(void)
{
if (TIM_GetITStatus(TIM4, TIM_IT_Update) != RESET) {
TIM_ClearITPendingBit(TIM4, TIM_IT_Update);
system_handle_timer_tick();
// TODO: system_handle_button();
}
}

21
src/hal/system.h 100644
Wyświetl plik

@ -0,0 +1,21 @@
#ifndef __HAL_SYSTEM_H
#define __HAL_SYSTEM_H
#include "hal.h"
#define GPIO_PIN_LED_GREEN GPIO_Pin_7
#define GPIO_PIN_LED_RED GPIO_Pin_8
#define SYSTEM_SCHEDULER_TIMER_TICKS_PER_SECOND 10000
void system_init();
uint32_t system_get_tick();
void system_disable_irq();
void system_enable_irq();
void system_set_green_led(bool enabled);
void system_set_red_led(bool enabled);
uint16_t system_get_battery_voltage_millivolts();
extern void (*system_handle_timer_tick)();
#endif

Wyświetl plik

@ -0,0 +1,42 @@
#include <stm32f10x_rcc.h>
#include <stm32f10x_gpio.h>
#include <stm32f10x_usart.h>
void usart_ext_init()
{
GPIO_InitTypeDef gpio_init;
// USART3 TX
gpio_init.GPIO_Pin = GPIO_Pin_10;
gpio_init.GPIO_Mode = GPIO_Mode_AF_PP;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOB, &gpio_init);
// USART3 RX
gpio_init.GPIO_Pin = GPIO_Pin_11;
gpio_init.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOB, &gpio_init);
NVIC_DisableIRQ(USART3_IRQn);
USART_Cmd(USART3, DISABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
USART_InitTypeDef usart_init;
usart_init.USART_BaudRate = 19200; //0x9c4;
usart_init.USART_WordLength = USART_WordLength_8b;
usart_init.USART_StopBits = USART_StopBits_1;
usart_init.USART_Parity = USART_Parity_No;
usart_init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
usart_init.USART_Mode = USART_Mode_Tx | USART_Mode_Rx;
USART_Init(USART3, &usart_init);
USART_Cmd(USART3, ENABLE);
}
void usart_ext_uninit()
{
USART_Cmd(USART3, DISABLE);
USART_DeInit(USART3);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, DISABLE);
}

104
src/hal/usart_gps.c 100644
Wyświetl plik

@ -0,0 +1,104 @@
#include <stddef.h>
#include <stm32f10x_rcc.h>
#include <stm32f10x_gpio.h>
#include <stm32f10x_usart.h>
#include <misc.h>
#include "usart_gps.h"
void (*usart_gps_handle_incoming_byte)(uint8_t data) = NULL;
void usart_gps_init(uint32_t baud_rate, bool enable_irq)
{
GPIO_InitTypeDef gpio_init;
// USART1 TX
gpio_init.GPIO_Pin = GPIO_Pin_9;
gpio_init.GPIO_Mode = GPIO_Mode_AF_PP;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOA, &gpio_init);
// USART1 RX
gpio_init.GPIO_Pin = GPIO_Pin_10;
gpio_init.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOA, &gpio_init);
NVIC_DisableIRQ(USART1_IRQn);
USART_ITConfig(USART1, USART_IT_RXNE, DISABLE);
USART_ClearITPendingBit(USART1, USART_IT_RXNE);
USART_ClearITPendingBit(USART1, USART_IT_ORE);
USART_Cmd(USART1, DISABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
USART_InitTypeDef usart_init;
usart_init.USART_BaudRate = baud_rate;
usart_init.USART_WordLength = USART_WordLength_8b;
usart_init.USART_StopBits = USART_StopBits_1;
usart_init.USART_Parity = USART_Parity_No;
usart_init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
usart_init.USART_Mode = USART_Mode_Tx | USART_Mode_Rx;
USART_Init(USART1, &usart_init);
NVIC_InitTypeDef nvic_init;
nvic_init.NVIC_IRQChannel = USART1_IRQn;
nvic_init.NVIC_IRQChannelPreemptionPriority = 15;
nvic_init.NVIC_IRQChannelSubPriority = 2;
nvic_init.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic_init);
USART_Cmd(USART1, ENABLE);
if (enable_irq) {
USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);
NVIC_EnableIRQ(USART1_IRQn);
}
}
static void usart_gps_enable_irq(bool enabled) {
if (enabled) {
USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);
NVIC_EnableIRQ(USART1_IRQn);
} else {
NVIC_DisableIRQ(USART1_IRQn);
USART_ITConfig(USART1, USART_IT_RXNE, DISABLE);
}
USART_ClearITPendingBit(USART1, USART_IT_RXNE);
USART_ClearITPendingBit(USART1, USART_IT_ORE);
}
void usart_gps_uninit()
{
usart_gps_enable_irq(false);
USART_Cmd(USART1, DISABLE);
USART_DeInit(USART1);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, DISABLE);
}
void usart_gps_enable(bool enabled)
{
usart_gps_enable_irq(enabled);
USART_Cmd(USART1, enabled ? ENABLE : DISABLE);
}
void usart_gps_send_byte(uint8_t data)
{
while (USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET) {}
USART_SendData(USART1, data);
while (USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET) {}
}
void USART1_IRQHandler(void)
{
if (USART_GetITStatus(USART1, USART_IT_RXNE) != RESET) {
USART_ClearITPendingBit(USART1, USART_IT_RXNE);
uint8_t data = (uint8_t) USART_ReceiveData(USART1);
usart_gps_handle_incoming_byte(data);
} else if (USART_GetITStatus(USART1, USART_IT_ORE) != RESET) {
USART_ClearITPendingBit(USART1, USART_IT_ORE);
USART_ReceiveData(USART1);
} else {
USART_ReceiveData(USART1);
}
}

Wyświetl plik

@ -0,0 +1,14 @@
#ifndef __USART_GPS_H
#define __USART_GPS_H
#include <stdint.h>
#include <stdbool.h>
void usart_gps_init(uint32_t baud_rate, bool enable_irq);
void usart_gps_uninit();
void usart_gps_enable(bool enabled);
void usart_gps_send_byte(uint8_t data);
extern void (*usart_gps_handle_incoming_byte)(uint8_t data);
#endif

32
src/locator.c 100644
Wyświetl plik

@ -0,0 +1,32 @@
// Based on HamLib's locator routines
// OK1TE 2018-10
#include "locator.h"
#include "config.h"
const static uint8_t loc_char_range[] = { 18, 10, 24, 10, 24, 10 };
const float precision = 1E+7;
uint8_t longlat2locator(int32_t longitude, int32_t latitude, char locator[]) {
if (!locator)
return 0;
for (uint8_t x_or_y = 0; x_or_y < 2; ++x_or_y) {
float ordinate = ((x_or_y == 0) ? (longitude / 2) / precision : latitude / precision) + 90;
uint32_t divisions = 1;
for (uint8_t pair = 0; pair < PAIR_COUNT; ++pair) {
divisions *= loc_char_range[pair];
const float square_size = 180.0 / divisions;
uint8_t locvalue = (uint8_t) (ordinate / square_size);
ordinate -= square_size * locvalue;
locvalue += (loc_char_range[pair] == 10) ? '0':'A';
locator[pair * 2 + x_or_y] = locvalue;
}
}
locator[PAIR_COUNT * 2] = 0;
return 1;
}

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