Merge pull request #1697 from locicontrols/cc2538
Add support for the Texas Instruments CC2538 ARM Cortex-M3 MCU and developer kit.dev/timer
commit
ecae75a1ab
@ -0,0 +1,4 @@
|
||||
# Tell the Makefile.base which module to build:
|
||||
MODULE = $(BOARD)_base
|
||||
|
||||
include $(RIOTBASE)/Makefile.base
|
@ -0,0 +1 @@
|
||||
FEATURES_PROVIDED = periph_gpio
|
@ -0,0 +1,41 @@
|
||||
# Define the cpu used by the CC2538DK board:
|
||||
export CPU = cc2538
|
||||
|
||||
export CPU_MODEL ?= cc2538nf53
|
||||
|
||||
# Define tools used for building the project:
|
||||
export PREFIX ?= arm-none-eabi-
|
||||
|
||||
export CC = $(PREFIX)gcc
|
||||
export AR = $(PREFIX)ar
|
||||
export AS = $(PREFIX)as
|
||||
export LINK = $(PREFIX)gcc
|
||||
export SIZE = $(PREFIX)size
|
||||
export OBJCOPY = $(PREFIX)objcopy
|
||||
export OBJDUMP = $(PREFIX)objdump
|
||||
|
||||
export TERMPROG ?= $(RIOTBASE)/dist/tools/pyterm/pyterm
|
||||
|
||||
# Define the flash-tool and default port:
|
||||
export FLASHER ?= python $(RIOTBOARD)/$(BOARD)/dist/cc2538-bsl.py
|
||||
export PORT ?= /dev/ttyUSB1
|
||||
|
||||
# Define build specific options:
|
||||
export CPU_USAGE = -mcpu=cortex-m3
|
||||
|
||||
export ASFLAGS += -ggdb -g3 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian
|
||||
export CFLAGS += $(ASFLAGS) -std=gnu99 -mthumb -mthumb-interwork -nostartfiles -Os -Wall -Wstrict-prototypes -ffunction-sections -fdata-sections -fno-builtin
|
||||
export LINKFLAGS += $(CFLAGS) -static -lgcc -T$(LINKERSCRIPT) -L$(RIOTCPU)/$(CPU)
|
||||
export OFLAGS += -O binary --gap-fill 0xff
|
||||
export FFLAGS += -p "$(PORT)" -e -w -v bin/$(BOARD)/$(APPLICATION).hex
|
||||
export TERMFLAGS += -p "$(PORT)"
|
||||
|
||||
export OBJDUMPFLAGS += --disassemble --source --disassembler-options=force-thumb
|
||||
|
||||
# Use the nano-specs of the NewLib when available:
|
||||
ifeq ($(shell $(LINK) -specs=nano.specs -E - 2>/dev/null >/dev/null </dev/null ; echo $$?),0)
|
||||
export LINKFLAGS += -specs=nano.specs -lc -lnosys
|
||||
endif
|
||||
|
||||
# Export board specific includes to the global includes-listing:
|
||||
export INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include
|
@ -0,0 +1,59 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Loci Controls Inc.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup board_cc2538dk
|
||||
* @{
|
||||
*
|
||||
* @file board.c
|
||||
* @brief Board specific implementations for the CC2538DK board
|
||||
*
|
||||
* @author Ian Martin <ian@locicontrols.com>
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include "board.h"
|
||||
#include "cpu.h"
|
||||
|
||||
#include "ioc.h"
|
||||
#include "lpm.h"
|
||||
#include "cc2538-gpio.h"
|
||||
|
||||
static void led_init_helper(int gpio_num) {
|
||||
gpio_software_control(gpio_num);
|
||||
gpio_dir_output(gpio_num);
|
||||
|
||||
/* Enable output without any internal pull resistors: */
|
||||
IOC_PXX_OVER[gpio_num] = IOC_OVERRIDE_OE;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initialize the SmartRF06's on-board LEDs
|
||||
*/
|
||||
void led_init(void)
|
||||
{
|
||||
led_init_helper(LED_RED_GPIO);
|
||||
led_init_helper(LED_GREEN_GPIO);
|
||||
led_init_helper(LED_YELLOW_GPIO);
|
||||
led_init_helper(LED_ORANGE_GPIO);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initialize the SmartRF06 board
|
||||
*/
|
||||
void board_init(void)
|
||||
{
|
||||
/* initialize the CPU */
|
||||
cpu_init();
|
||||
|
||||
/* initialize the boards LEDs */
|
||||
led_init();
|
||||
}
|
||||
|
||||
/** @} */
|
@ -0,0 +1,761 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (c) 2014, Jelmer Tiete <jelmer@tiete.be>.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in the
|
||||
# documentation and/or other materials provided with the distribution.
|
||||
# 3. The name of the author may not be used to endorse or promote
|
||||
# products derived from this software without specific prior
|
||||
# written permission.
|
||||
|
||||
# THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS
|
||||
# OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
# WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
# ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY
|
||||
# DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE
|
||||
# GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||
# WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
|
||||
# NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
# SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
# Implementation based on stm32loader by Ivan A-R <ivan@tuxotronic.org>
|
||||
|
||||
# Serial boot loader over UART for CC2538
|
||||
# Based on the info found in TI's swru333a.pdf (spma029.pdf)
|
||||
#
|
||||
# Bootloader only starts if no valid image is found or if boot loader
|
||||
# backdoor is enabled.
|
||||
# Make sure you don't lock yourself out!! (enable backdoor in your firmware)
|
||||
# More info at https://github.com/JelmerT/cc2538-bsl
|
||||
|
||||
from __future__ import print_function
|
||||
from subprocess import Popen, PIPE
|
||||
|
||||
import sys, getopt
|
||||
import glob
|
||||
import time
|
||||
import tempfile
|
||||
import os
|
||||
import subprocess
|
||||
import struct
|
||||
import binascii
|
||||
|
||||
#version
|
||||
VERSION_STRING = "1.0"
|
||||
|
||||
# Verbose level
|
||||
QUIET = 5
|
||||
|
||||
# Check which version of Python is running
|
||||
PY3 = sys.version_info >= (3,0)
|
||||
|
||||
try:
|
||||
import serial
|
||||
except ImportError:
|
||||
print('{} requires the Python serial library'.format(sys.argv[0]))
|
||||
print('Please install it with one of the following:')
|
||||
print('')
|
||||
if PY3:
|
||||
print(' Ubuntu: sudo apt-get install python3-serial')
|
||||
print(' Mac: sudo port install py34-serial')
|
||||
else:
|
||||
print(' Ubuntu: sudo apt-get install python-serial')
|
||||
print(' Mac: sudo port install py-serial')
|
||||
sys.exit(1)
|
||||
|
||||
|
||||
def mdebug(level, message, attr='\n'):
|
||||
if QUIET >= level:
|
||||
print(message, end=attr, file=sys.stderr)
|
||||
|
||||
# Takes chip IDs (obtained via Get ID command) to human-readable names
|
||||
CHIP_ID_STRS = {0xb964: 'CC2538'}
|
||||
|
||||
RETURN_CMD_STRS = {0x40: 'Success',
|
||||
0x41: 'Unknown command',
|
||||
0x42: 'Invalid command',
|
||||
0x43: 'Invalid address',
|
||||
0x44: 'Flash fail'
|
||||
}
|
||||
|
||||
COMMAND_RET_SUCCESS = 0x40
|
||||
COMMAND_RET_UNKNOWN_CMD = 0x41
|
||||
COMMAND_RET_INVALID_CMD = 0x42
|
||||
COMMAND_RET_INVALID_ADR = 0x43
|
||||
COMMAND_RET_FLASH_FAIL = 0x44
|
||||
|
||||
ADDR_IEEE_ADDRESS_SECONDARY = 0x0027ffcc
|
||||
|
||||
class CmdException(Exception):
|
||||
pass
|
||||
|
||||
class CommandInterface(object):
|
||||
def open(self, aport='/dev/tty.usbserial-000013FAB', abaudrate=500000):
|
||||
self.sp = serial.Serial(
|
||||
port=aport,
|
||||
baudrate=abaudrate, # baudrate
|
||||
bytesize=8, # number of databits
|
||||
parity=serial.PARITY_NONE,
|
||||
stopbits=1,
|
||||
xonxoff=0, # enable software flow control
|
||||
rtscts=0, # disable RTS/CTS flow control
|
||||
timeout=0.5 # set a timeout value, None for waiting forever
|
||||
)
|
||||
|
||||
# Use the DTR and RTS lines to control !RESET and the bootloader pin.
|
||||
# This can automatically invoke the bootloader without the user
|
||||
# having to toggle any pins.
|
||||
# DTR: connected to the bootloader pin
|
||||
# RTS: connected to !RESET
|
||||
self.sp.setDTR(1)
|
||||
self.sp.setRTS(0)
|
||||
self.sp.setRTS(1)
|
||||
self.sp.setRTS(0)
|
||||
self.sp.setDTR(0)
|
||||
|
||||
def close(self):
|
||||
self.sp.close()
|
||||
|
||||
|
||||
def _wait_for_ack(self, info="", timeout=0):
|
||||
stop = time.time() + timeout
|
||||
got = None
|
||||
while not got:
|
||||
got = self._read(2)
|
||||
if time.time() > stop:
|
||||
break
|
||||
|
||||
if not got:
|
||||
mdebug(10, "No response to %s" % info)
|
||||
return 0
|
||||
|
||||
# wait for ask
|
||||
ask = got[1]
|
||||
|
||||
if ask == 0xCC:
|
||||
# ACK
|
||||
return 1
|
||||
elif ask == 0x33:
|
||||
# NACK
|
||||
mdebug(10, "Target replied with a NACK during %s" % info)
|
||||
return 0
|
||||
|
||||
# Unknown response
|
||||
mdebug(10, "Unrecognised response 0x%x to %s" % (ask, info))
|
||||
return 0
|
||||
|
||||
def _encode_addr(self, addr):
|
||||
byte3 = (addr >> 0) & 0xFF
|
||||
byte2 = (addr >> 8) & 0xFF
|
||||
byte1 = (addr >> 16) & 0xFF
|
||||
byte0 = (addr >> 24) & 0xFF
|
||||
if PY3:
|
||||
return bytes([byte0, byte1, byte2, byte3])
|
||||
else:
|
||||
return (chr(byte0) + chr(byte1) + chr(byte2) + chr(byte3))
|
||||
|
||||
def _decode_addr(self, byte0, byte1, byte2, byte3):
|
||||
return ((byte3 << 24) | (byte2 << 16) | (byte1 << 8) | (byte0 << 0))
|
||||
|
||||
def _calc_checks(self, cmd, addr, size):
|
||||
return ((sum(bytearray(self._encode_addr(addr)))
|
||||
+sum(bytearray(self._encode_addr(size)))
|
||||
+cmd)
|
||||
&0xFF)
|
||||
|
||||
def _write(self, data):
|
||||
if PY3:
|
||||
if type(data) == int:
|
||||
self.sp.write(bytes([data]))
|
||||
elif type(data) == bytes or type(data) == bytearray:
|
||||
self.sp.write(data)
|
||||
else:
|
||||
if type(data) == int:
|
||||
self.sp.write(chr(data))
|
||||
else:
|
||||
self.sp.write(data)
|
||||
|
||||
def _read(self, length):
|
||||
got = self.sp.read(length)
|
||||
if PY3:
|
||||
return got
|
||||
else:
|
||||
return [ord(x) for x in got]
|
||||
|
||||
def sendAck(self):
|
||||
self._write(chr(0x00))
|
||||
self._write(0xCC)
|
||||
return
|
||||
|
||||
def sendNAck(self):
|
||||
self._write(chr(0x00))
|
||||
self._write(chr(0x33))
|
||||
return
|
||||
|
||||
|
||||
def receivePacket(self):
|
||||
# stop = time.time() + 5
|
||||
# got = None
|
||||
# while not got:
|
||||
got = self._read(2)
|
||||
# if time.time() > stop:
|
||||
# break
|
||||
|
||||
# if not got:
|
||||
# raise CmdException("No response to %s" % info)
|
||||
|
||||
size = got[0] #rcv size
|
||||
chks = got[1] #rcv checksum
|
||||
data = self._read(size-2) # rcv data
|
||||
|
||||
mdebug(10, "*** received %x bytes" % size)
|
||||
if chks == sum(data)&0xFF:
|
||||
self.sendAck()
|
||||
return data
|
||||
else:
|
||||
self.sendNAck()
|
||||
#TODO: retry receiving!
|
||||
raise CmdException("Received packet checksum error")
|
||||
return 0
|
||||
|
||||
def sendSynch(self):
|
||||
cmd = 0x55
|
||||
|
||||
self.sp.flushInput() #flush serial input buffer for first ACK reception
|
||||
|
||||
mdebug(10, "*** sending synch sequence")
|
||||
self._write(cmd) # send U
|
||||
self._write(cmd) # send U
|
||||
return self._wait_for_ack("Synch (0x55 0x55)")
|
||||
|
||||
def checkLastCmd(self):
|
||||
stat = self.cmdGetStatus()
|
||||
if not (stat):
|
||||
raise CmdException("No response from target on status request. (Did you disable the bootloader?)")
|
||||
|
||||
if stat[0] == COMMAND_RET_SUCCESS:
|
||||
mdebug(10, "Command Successful")
|
||||
return 1
|
||||
else:
|
||||
stat_str = RETURN_CMD_STRS.get(stat, None)
|
||||
if stat_str is None:
|
||||
mdebug(0, 'Warning: unrecognized status returned 0x%x' % stat)
|
||||
else:
|
||||
mdebug(0, "Target returned: 0x%x, %s" % (stat, stat_str))
|
||||
return 0
|
||||
|
||||
|
||||
def cmdPing(self):
|
||||
cmd = 0x20
|
||||
lng = 3
|
||||
|
||||
self._write(lng) # send size
|
||||
self._write(cmd) # send checksum
|
||||
self._write(cmd) # send data
|
||||
|
||||
mdebug(10, "*** Ping command (0x20)")
|
||||
if self._wait_for_ack("Ping (0x20)"):
|
||||
return self.checkLastCmd()
|
||||
|
||||
def cmdReset(self):
|
||||
cmd = 0x25
|
||||
lng = 3
|
||||
|
||||
self._write(lng) # send size
|
||||
self._write(cmd) # send checksum
|
||||
self._write(cmd) # send data
|
||||
|
||||
mdebug(10, "*** Reset command (0x25)")
|
||||
if self._wait_for_ack("Reset (0x25)"):
|
||||
return 1
|
||||
|
||||
def cmdGetChipId(self):
|
||||
cmd = 0x28
|
||||
lng = 3
|
||||
|
||||
self._write(lng) # send size
|
||||
self._write(cmd) # send checksum
|
||||
self._write(cmd) # send data
|
||||
|
||||
mdebug(10, "*** GetChipId command (0x28)")
|
||||
if self._wait_for_ack("Get ChipID (0x28)"):
|
||||
version = self.receivePacket() # 4 byte answ, the 2 LSB hold chip ID
|
||||
if self.checkLastCmd():
|
||||
assert len(version) == 4, "Unreasonable chip id: %s" % repr(version)
|
||||
chip_id = (version[2] << 8) | version[3]
|
||||
return chip_id
|
||||
else:
|
||||
raise CmdException("GetChipID (0x28) failed")
|
||||
|
||||
def cmdGetStatus(self):
|
||||
cmd = 0x23
|
||||
lng = 3
|
||||
|
||||
self._write(lng) # send size
|
||||
self._write(cmd) # send checksum
|
||||
self._write(cmd) # send data
|
||||
|
||||
mdebug(10, "*** GetStatus command (0x23)")
|
||||
if self._wait_for_ack("Get Status (0x23)"):
|
||||
stat = self.receivePacket()
|
||||
return stat
|
||||
|
||||
def cmdSetXOsc(self):
|
||||
cmd = 0x29
|
||||
lng = 3
|
||||
|
||||
self._write(lng) # send size
|
||||
self._write(cmd) # send checksum
|
||||
self._write(cmd) # send data
|
||||
|
||||
mdebug(10, "*** SetXOsc command (0x29)")
|
||||
if self._wait_for_ack("SetXOsc (0x29)"):
|
||||
return 1
|
||||
# UART speed (needs) to be changed!
|
||||
|
||||
def cmdRun(self, addr):
|
||||
cmd=0x22
|
||||
lng=7
|
||||
|
||||
self._write(lng) # send length
|
||||
self._write(self._calc_checks(cmd,addr,0)) # send checksum
|
||||
self._write(cmd) # send cmd
|
||||
self._write(self._encode_addr(addr)) # send addr
|
||||
|
||||
mdebug(10, "*** Run command(0x22)")
|
||||
return 1
|
||||
|
||||
def cmdEraseMemory(self, addr, size):
|
||||
cmd=0x26
|
||||
lng=11
|
||||
|
||||
self._write(lng) # send length
|
||||
self._write(self._calc_checks(cmd,addr,size)) # send checksum
|
||||
self._write(cmd) # send cmd
|
||||
self._write(self._encode_addr(addr)) # send addr
|
||||
self._write(self._encode_addr(size)) # send size
|
||||
|
||||
mdebug(10, "*** Erase command(0x26)")
|
||||
if self._wait_for_ack("Erase memory (0x26)",10):
|
||||
return self.checkLastCmd()
|
||||
|
||||
def cmdCRC32(self, addr, size):
|
||||
cmd=0x27
|
||||
lng=11
|
||||
|
||||
self._write(lng) # send length
|
||||
self._write(self._calc_checks(cmd,addr,size)) # send checksum
|
||||
self._write(cmd) # send cmd
|
||||
self._write(self._encode_addr(addr)) # send addr
|
||||
self._write(self._encode_addr(size)) # send size
|
||||
|
||||
mdebug(10, "*** CRC32 command(0x27)")
|
||||
if self._wait_for_ack("Get CRC32 (0x27)",1):
|
||||
crc=self.receivePacket()
|
||||
if self.checkLastCmd():
|
||||
return self._decode_addr(crc[3],crc[2],crc[1],crc[0])
|
||||
|
||||
def cmdDownload(self, addr, size):
|
||||
cmd=0x21
|
||||
lng=11
|
||||
|
||||
if (size % 4) != 0: # check for invalid data lengths
|
||||
raise Exception('Invalid data size: %i. Size must be a multiple of 4.' % size)
|
||||
|
||||
self._write(lng) # send length
|
||||
self._write(self._calc_checks(cmd,addr,size)) # send checksum
|
||||
self._write(cmd) # send cmd
|
||||
self._write(self._encode_addr(addr)) # send addr
|
||||
self._write(self._encode_addr(size)) # send size
|
||||
|
||||
mdebug(10, "*** Download command (0x21)")
|
||||
if self._wait_for_ack("Download (0x21)",2):
|
||||
return self.checkLastCmd()
|
||||
|
||||
def cmdSendData(self, data):
|
||||
cmd=0x24
|
||||
lng=len(data)+3
|
||||
# TODO: check total size of data!! max 252 bytes!
|
||||
|
||||
self._write(lng) # send size
|
||||
self._write((sum(bytearray(data))+cmd)&0xFF) # send checksum
|
||||
self._write(cmd) # send cmd
|
||||
self._write(bytearray(data)) # send data
|
||||
|
||||
mdebug(10, "*** Send Data (0x24)")
|
||||
if self._wait_for_ack("Send data (0x24)",10):
|
||||
return self.checkLastCmd()
|
||||
|
||||
def cmdMemRead(self, addr): # untested
|
||||
cmd=0x2A
|
||||
lng=8
|
||||
|
||||
self._write(lng) # send length
|
||||
self._write(self._calc_checks(cmd,addr,4)) # send checksum
|
||||
self._write(cmd) # send cmd
|
||||
self._write(self._encode_addr(addr)) # send addr
|
||||
self._write(4) # send width, 4 bytes
|
||||
|
||||
mdebug(10, "*** Mem Read (0x2A)")
|
||||
if self._wait_for_ack("Mem Read (0x2A)",1):
|
||||
data = self.receivePacket()
|
||||
if self.checkLastCmd():
|
||||
return data # self._decode_addr(ord(data[3]),ord(data[2]),ord(data[1]),ord(data[0]))
|
||||
|
||||
def cmdMemWrite(self, addr, data, width): # untested
|
||||
# TODO: check width for 1 or 4 and data size
|
||||
cmd=0x2B
|
||||
lng=10
|
||||
|
||||
self._write(lng) # send length
|
||||
self._write(self._calc_checks(cmd,addr,0)) # send checksum
|
||||
self._write(cmd) # send cmd
|
||||
self._write(self._encode_addr(addr)) # send addr
|
||||
self._write(bytearray(data)) # send data
|
||||
self._write(width) # send width, 4 bytes
|
||||
|
||||
mdebug(10, "*** Mem write (0x2B)")
|
||||
if self._wait_for_ack("Mem Write (0x2B)",2):
|
||||
return checkLastCmd()
|
||||
|
||||
|
||||
# Complex commands section
|
||||
|
||||
def writeMemory(self, addr, data):
|
||||
lng = len(data)
|
||||
trsf_size = 248 # amount of data bytes transferred per packet (theory: max 252 + 3)
|
||||
if PY3:
|
||||
empty_packet = b'\xff'*trsf_size # empty packet (filled with 0xFF)
|
||||
else:
|
||||
empty_packet = [255]*trsf_size # empty packet (filled with 0xFF)
|
||||
|
||||
# Boot loader enable check
|
||||
# TODO: implement check for all chip sizes & take into account partial firmware uploads
|
||||
if (lng == 524288): #check if file is for 512K model
|
||||
if not ((data[524247] & (1 << 4)) >> 4): #check the boot loader enable bit (only for 512K model)
|
||||
if not query_yes_no("The boot loader backdoor is not enabled "\
|
||||
"in the firmware you are about to write to the target. "\
|
||||
"You will NOT be able to reprogram the target using this tool if you continue! "\
|
||||
"Do you want to continue?","no"):
|
||||
raise Exception('Aborted by user.')
|
||||
|
||||
mdebug(5, "Writing %(lng)d bytes starting at address 0x%(addr)X" %
|
||||
{ 'lng': lng, 'addr': addr})
|
||||
|
||||
offs = 0
|
||||
addr_set = 0
|
||||
|
||||
while lng > trsf_size: #check if amount of remaining data is less then packet size
|
||||
if data[offs:offs+trsf_size] != empty_packet: #skip packets filled with 0xFF
|
||||
if addr_set != 1:
|
||||
self.cmdDownload(addr,lng) #set starting address if not set
|
||||
addr_set = 1
|
||||
|
||||
mdebug(5, " Write %(len)d bytes at 0x%(addr)X" % {'addr': addr, 'len': trsf_size}, '\r')
|
||||
sys.stdout.flush()
|
||||
|
||||
self.cmdSendData(data[offs:offs+trsf_size]) # send next data packet
|
||||
else: # skipped packet, address needs to be set
|
||||
addr_set = 0
|
||||
|
||||
offs = offs + trsf_size
|
||||
addr = addr + trsf_size
|
||||
lng = lng - trsf_size
|
||||
|
||||
mdebug(5, "Write %(len)d bytes at 0x%(addr)X" % {'addr': addr, 'len': lng}, '\r')
|
||||
self.cmdDownload(addr,lng)
|
||||
return self.cmdSendData(data[offs:offs+lng]) # send last data packet
|
||||
|
||||
def query_yes_no(question, default="yes"):
|
||||
valid = {"yes":True, "y":True, "ye":True,
|
||||
"no":False, "n":False}
|
||||
if default == None:
|
||||
prompt = " [y/n] "
|
||||
elif default == "yes":
|
||||
prompt = " [Y/n] "
|
||||
elif default == "no":
|
||||
prompt = " [y/N] "
|
||||
else:
|
||||
raise ValueError("invalid default answer: '%s'" % default)
|
||||
|
||||
while True:
|
||||
sys.stdout.write(question + prompt)
|
||||
if PY3:
|
||||
choice = input().lower()
|
||||
else:
|
||||
choice = raw_input().lower()
|
||||
if default is not None and choice == '':
|
||||
return valid[default]
|
||||
elif choice in valid:
|
||||
return valid[choice]
|
||||
else:
|
||||
sys.stdout.write("Please respond with 'yes' or 'no' "\
|
||||
"(or 'y' or 'n').\n")
|
||||
|
||||
# Convert the entered IEEE address into an integer
|
||||
def parse_ieee_address (inaddr):
|
||||
try:
|
||||
return int(inaddr, 16)
|
||||
except ValueError:
|
||||
# inaddr is not a hex string, look for other formats
|
||||
if ':' in inaddr:
|
||||
bytes = inaddr.split(':')
|
||||
elif '-' in inaddr:
|
||||
bytes = inaddr.split('-')
|
||||
if len(bytes) != 8:
|
||||
raise ValueError("Supplied IEEE address does not contain 8 bytes")
|
||||
addr = 0
|
||||
for i,b in zip(range(8), bytes):
|
||||
try:
|
||||
addr += int(b, 16) << (56-(i*8))
|
||||
except ValueError:
|
||||
raise ValueError("IEEE address contains invalid bytes")
|
||||
return addr
|
||||
|
||||
def print_version():
|
||||
# Get the version using "git describe".
|
||||
try:
|
||||
p = Popen(['git', 'describe', '--tags', '--match', '[0-9]*'],
|
||||
stdout=PIPE, stderr=PIPE)
|
||||
p.stderr.close()
|
||||
line = p.stdout.readlines()[0]
|
||||
version = line.strip()
|
||||
except:
|
||||
# We're not in a git repo, or git failed, use fixed version string.
|
||||
version = VERSION_STRING
|
||||
print('%s %s' % (sys.argv[0], version))
|
||||
|
||||
def usage():
|
||||
print("""Usage: %s [-hqVewvr] [-l length] [-p port] [-b baud] [-a addr] [-i addr] [file.bin]
|
||||
-h This help
|
||||
-q Quiet
|
||||
-V Verbose
|
||||
-e Erase (full)
|
||||
-w Write
|
||||
-v Verify (CRC32 check)
|
||||
-r Read
|
||||
-l length Length of read
|
||||
-p port Serial port (default: first USB-like port in /dev)
|
||||
-b baud Baud speed (default: 500000)
|
||||
-a addr Target address
|
||||
-i, --ieee-address addr Set the secondary 64 bit IEEE address
|
||||
--version Print script version
|
||||
|
||||
Examples:
|
||||
./%s -e -w -v example/main.bin
|
||||
./%s -e -w -v --ieee-address 00:12:4b:aa:bb:cc:dd:ee example/main.bin
|
||||
|
||||
""" % (sys.argv[0],sys.argv[0],sys.argv[0]))
|
||||
|
||||
def read(filename):
|
||||
"""Read the file to be programmed and turn it into a binary"""
|
||||
with open(filename, 'rb') as f:
|
||||
bytes = f.read()
|
||||
if PY3:
|
||||
return bytes
|
||||
else:
|
||||
return [ord(x) for x in bytes]
|
||||
|
||||
if __name__ == "__main__":
|
||||
|
||||
conf = {
|
||||
'port': 'auto',
|
||||
'baud': 500000,
|
||||
'force_speed' : 0,
|
||||
'address': 0x00200000,
|
||||
'erase': 0,
|
||||
'write': 0,
|
||||
'verify': 0,
|
||||
'read': 0,
|
||||
'len': 0x80000,
|
||||
'fname':'',
|
||||
'ieee_address': 0,
|
||||
}
|
||||
|
||||
# http://www.python.org/doc/2.5.2/lib/module-getopt.html
|
||||
|
||||
try:
|
||||
opts, args = getopt.getopt(sys.argv[1:], "hqVewvrp:b:a:l:i:", ['ieee-address=', 'version'])
|
||||
except getopt.GetoptError as err:
|
||||
# print help information and exit:
|
||||
print(str(err)) # will print something like "option -a not recognized"
|
||||
usage()
|
||||
sys.exit(2)
|
||||
|
||||
for o, a in opts:
|
||||
if o == '-V':
|
||||
QUIET = 10
|
||||
elif o == '-q':
|
||||
QUIET = 0
|
||||
elif o == '-h':
|
||||
usage()
|
||||
sys.exit(0)
|
||||
elif o == '-e':
|
||||
conf['erase'] = 1
|
||||
elif o == '-w':
|
||||
conf['write'] = 1
|
||||
elif o == '-v':
|
||||
conf['verify'] = 1
|
||||
elif o == '-r':
|
||||
conf['read'] = 1
|
||||
elif o == '-p':
|
||||
conf['port'] = a
|
||||
elif o == '-b':
|
||||
conf['baud'] = eval(a)
|
||||
conf['force_speed'] = 1
|
||||
elif o == '-a':
|
||||
conf['address'] = eval(a)
|
||||
elif o == '-l':
|
||||
conf['len'] = eval(a)
|
||||
elif o == '-i' or o == '--ieee-address':
|
||||
conf['ieee_address'] = str(a)
|
||||
elif o == '--version':
|
||||
print_version()
|
||||
sys.exit(0)
|
||||
else:
|
||||
assert False, "Unhandled option"
|
||||
|
||||
try:
|
||||
# Sanity checks
|
||||
if conf['write'] or conf['read'] or conf['verify']: # check for input/output file
|
||||
try:
|
||||
args[0]
|
||||
except:
|
||||
raise Exception('No file path given.')
|
||||
|
||||
if conf['write'] and conf['read']:
|
||||
if not query_yes_no("You are reading and writing to the same file. This will overwrite your input file. "\
|
||||
"Do you want to continue?","no"):
|
||||
raise Exception('Aborted by user.')
|
||||
if conf['erase'] and conf['read'] and not conf['write']:
|
||||
if not query_yes_no("You are about to erase your target before reading. "\
|
||||
"Do you want to continue?","no"):
|
||||
raise Exception('Aborted by user.')
|
||||
|
||||
if conf['read'] and not conf['write'] and conf['verify']:
|
||||
raise Exception('Verify after read not implemented.')
|
||||
|
||||
# Try and find the port automatically
|
||||
if conf['port'] == 'auto':
|
||||
ports = []
|
||||
|
||||
# Get a list of all USB-like names in /dev
|
||||
for name in ['tty.usbserial', 'ttyUSB', 'tty.usbmodem']:
|
||||
ports.extend(glob.glob('/dev/%s*' % name))
|
||||
|
||||
ports = sorted(ports)
|
||||
|
||||
if ports:
|
||||
# Found something - take it
|
||||
conf['port'] = ports[0]
|
||||
else:
|
||||
raise Exception('No serial port found.')
|
||||
|
||||
cmd = CommandInterface()
|
||||
cmd.open(conf['port'], conf['baud'])
|
||||
mdebug(5, "Opening port %(port)s, baud %(baud)d" % {'port':conf['port'],
|
||||
'baud':conf['baud']})
|
||||
if conf['write'] or conf['verify']:
|
||||
mdebug(5, "Reading data from %s" % args[0])
|
||||
data = read(args[0])
|
||||
|
||||
mdebug(5, "Connecting to target...")
|
||||
|
||||
if not cmd.sendSynch():
|
||||
raise CmdException("Can't connect to target. Ensure boot loader is started. (no answer on synch sequence)")
|
||||
|
||||
if conf['force_speed'] != 1:
|
||||
if cmd.cmdSetXOsc(): #switch to external clock source
|
||||
cmd.close()
|
||||
conf['baud']=1000000
|
||||
cmd.open(conf['port'], conf['baud'])
|
||||
mdebug(6, "Opening port %(port)s, baud %(baud)d" % {'port':conf['port'],'baud':conf['baud']})
|
||||
mdebug(6, "Reconnecting to target at higher speed...")
|
||||
if (cmd.sendSynch()!=1):
|
||||
raise CmdException("Can't connect to target after clock source switch. (Check external crystal)")
|
||||
else:
|
||||
raise CmdException("Can't switch target to external clock source. (Try forcing speed)")
|
||||
|
||||
# if (cmd.cmdPing() != 1):
|
||||
# raise CmdException("Can't connect to target. Ensure boot loader is started. (no answer on ping command)")
|
||||
|
||||
chip_id = cmd.cmdGetChipId()
|
||||
chip_id_str = CHIP_ID_STRS.get(chip_id, None)
|
||||
|
||||
if chip_id_str is None:
|
||||
mdebug(0, 'Warning: unrecognized chip ID 0x%x' % chip_id)
|
||||
else:
|
||||
mdebug(5, " Target id 0x%x, %s" % (chip_id, chip_id_str))
|
||||
|
||||
if conf['erase']:
|
||||
# we only do full erase for now (CC2538)
|
||||
address = 0x00200000 #flash start addr for cc2538
|
||||
size = 0x80000 #total flash size cc2538
|
||||
mdebug(5, "Erasing %s bytes starting at address 0x%x" % (size, address))
|
||||
|
||||
if cmd.cmdEraseMemory(address, size):
|
||||
mdebug(5, " Erase done")
|
||||
else:
|
||||
raise CmdException("Erase failed")
|
||||
|
||||
if conf['write']:
|
||||
# TODO: check if boot loader back-door is open, need to read flash size first to get address
|
||||
if cmd.writeMemory(conf['address'], data):
|
||||
mdebug(5, " Write done ")
|
||||
else:
|
||||
raise CmdException("Write failed ")
|
||||
|
||||
if conf['verify']:
|
||||
mdebug(5,"Verifying by comparing CRC32 calculations.")
|
||||
|
||||
crc_local = (binascii.crc32(bytearray(data))& 0xffffffff)
|
||||
crc_target = cmd.cmdCRC32(conf['address'],len(data)) #CRC of target will change according to length input file
|
||||
|
||||
if crc_local == crc_target:
|
||||
mdebug(5, " Verified (match: 0x%08x)" % crc_local)
|
||||
else:
|
||||
cmd.cmdReset()
|
||||
raise Exception("NO CRC32 match: Local = 0x%x, Target = 0x%x" % (crc_local,crc_target))
|
||||
|
||||
if conf['ieee_address'] != 0:
|
||||
ieee_addr = parse_ieee_address(conf['ieee_address'])
|
||||
if PY3:
|
||||
mdebug(5, "Setting IEEE address to %s" % (':'.join(['%02x' % b for b in struct.pack('>Q', ieee_addr)])))
|
||||
ieee_addr_bytes = struct.pack('<Q', ieee_addr)
|
||||
else:
|
||||
mdebug(5, "Setting IEEE address to %s" % (':'.join(['%02x' % ord(b) for b in struct.pack('>Q', ieee_addr)])))
|
||||
ieee_addr_bytes = [ord(b) for b in struct.pack('<Q', ieee_addr)]
|
||||
|
||||
if cmd.writeMemory(ADDR_IEEE_ADDRESS_SECONDARY, ieee_addr_bytes):
|
||||
mdebug(5, " Set address done ")
|
||||
else:
|
||||
raise CmdException("Set address failed ")
|
||||
|
||||
if conf['read']:
|
||||
length = conf['len']
|
||||
if length < 4: # reading 4 bytes at a time
|
||||
length = 4
|
||||
else:
|
||||
length = length + (length % 4)
|
||||
|
||||
mdebug(5, "Reading %s bytes starting at address 0x%x" % (length, conf['address']))
|
||||
f = file(args[0], 'w').close() #delete previous file
|
||||
for i in range(0,(length/4)):
|
||||
rdata = cmd.cmdMemRead(conf['address']+(i*4)) #reading 4 bytes at a time
|
||||
mdebug(5, " 0x%x: 0x%02x%02x%02x%02x" % (conf['address']+(i*4), ord(rdata[3]), ord(rdata[2]), ord(rdata[1]), ord(rdata[0])), '\r')
|
||||
file(args[0], 'ab').write(''.join(reversed(rdata)))
|
||||
mdebug(5, " Read done ")
|
||||
|
||||
cmd.cmdReset()
|
||||
|
||||
except Exception as err:
|
||||
exit('ERROR: %s' % str(err))
|
@ -0,0 +1,100 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Loci Controls Inc.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @defgroup board_cc2538dk CC2538DK
|
||||
* @ingroup boards
|
||||
* @brief Support for the Texas Instruments CC2538DK board.
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
*
|
||||
* @author Ian Martin <ian@locicontrols.com>
|
||||
*/
|
||||
|
||||
#ifndef __BOARD_H
|
||||
#define __BOARD_H
|
||||
|
||||
#include "cpu.h"
|
||||
#include "periph/gpio.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Define the nominal CPU core clock in this board
|
||||
*/
|
||||
#define F_CPU XOSC32M_FREQ
|
||||
|
||||
/**
|
||||
* Assign the hardware timer
|
||||
*/
|
||||
#define HW_TIMER TIMER_0
|
||||
|
||||
/**
|
||||
* @name Define UART device and baudrate for stdio
|
||||
* @{
|
||||
*/
|
||||
#define STDIO UART_0
|
||||
#define STDIO_BAUDRATE 115200
|
||||
#define STDIO_RX_BUFSIZE (64U)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name Macros for controlling the on-board LEDs.
|
||||
* @{
|
||||
*/
|
||||
#define LED_RED_GPIO GPIO_PC0 /**< Red LED GPIO pin */
|
||||
#define LED_YELLOW_GPIO GPIO_PC1 /**< Yellow LED GPIO pin */
|
||||
#define LED_GREEN_GPIO GPIO_PC2 /**< Green LED GPIO pin */
|
||||
#define LED_ORANGE_GPIO GPIO_PC3 /**< Orange LED GPIO pin */
|
||||
|
||||
#define LED_RED_ON cc2538_gpio_set(LED_GREEN_GPIO)
|
||||
#define LED_RED_OFF cc2538_gpio_clear(LED_GREEN_GPIO)
|
||||
#define LED_RED_TOGGLE cc2538_gpio_toggle(LED_GREEN_GPIO)
|
||||
|
||||
#define LED_YELLOW_ON cc2538_gpio_set(LED_YELLOW_GPIO)
|
||||
#define LED_YELLOW_OFF cc2538_gpio_clear(LED_YELLOW_GPIO)
|
||||
#define LED_YELLOW_TOGGLE cc2538_gpio_toggle(LED_YELLOW_GPIO)
|
||||
|
||||
#define LED_GREEN_ON cc2538_gpio_set(LED_GREEN_GPIO)
|
||||
#define LED_GREEN_OFF cc2538_gpio_clear(LED_GREEN_GPIO)
|
||||
#define LED_GREEN_TOGGLE cc2538_gpio_toggle(LED_GREEN_GPIO)
|
||||
|
||||
#define LED_ORANGE_ON cc2538_gpio_set(LED_ORANGE_GPIO)
|
||||
#define LED_ORANGE_OFF cc2538_gpio_clear(LED_ORANGE_GPIO)
|
||||
#define LED_ORANGE_TOGGLE cc2538_gpio_toggle(LED_ORANGE_GPIO)
|
||||
|
||||
/* Default to red if the color is not specified: */
|
||||
#define LED_ON LED_RED_ON
|
||||
#define LED_OFF LED_RED_OFF
|
||||
#define LED_TOGGLE LED_RED_TOGGLE
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name Flash Customer Configuration Area (CCA) parameters
|
||||
* @{
|
||||
*/
|
||||
#define UPDATE_CCA 1
|
||||
#define CCA_BACKDOOR_ENABLE 1
|
||||
#define CCA_BACKDOOR_PORT_A_PIN 3 /**< Select button */
|
||||
#define CCA_BACKDOOR_ACTIVE_LEVEL 0 /**< Active low */
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @brief Initialize board specific hardware, including clock, LEDs and std-IO
|
||||
*/
|
||||
void board_init(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
} /* end extern "C" */
|
||||
#endif
|
||||
|
||||
#endif /** __BOARD_H */
|
||||
/** @} */
|
@ -0,0 +1,186 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Loci Controls Inc.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup board_cc2538dk
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Peripheral MCU configuration for the CC2538DK board
|
||||
*
|
||||
* @author Ian Martin <ian@locicontrols.com>
|
||||
*/
|
||||
|
||||
#ifndef __PERIPH_CONF_H
|
||||
#define __PERIPH_CONF_H
|
||||
|
||||
#include "gptimer.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @name Timer peripheral configuration
|
||||
* @{
|
||||
*/
|
||||
#define TIMER_NUMOF GPTIMER_NUMOF
|
||||
#define TIMER_0_EN 1
|
||||
#define TIMER_1_EN 1
|
||||
#define TIMER_2_EN 1
|
||||
#define TIMER_3_EN 1
|
||||
|
||||
#define TIMER_IRQ_PRIO 1
|
||||
|
||||
/* Timer 0 configuration */
|
||||
#define TIMER_0_DEV GPTIMER0
|
||||
#define TIMER_0_CHANNELS NUM_CHANNELS_PER_GPTIMER
|
||||
#define TIMER_0_MAX_VALUE 0xffffffff
|
||||
#define TIMER_0_IRQn_1 GPTIMER_0A_IRQn
|
||||
#define TIMER_0_IRQn_2 GPTIMER_0B_IRQn
|
||||
|
||||
/* Timer 1 configuration */
|
||||
#define TIMER_1_DEV GPTIMER1
|
||||
#define TIMER_1_CHANNELS NUM_CHANNELS_PER_GPTIMER
|
||||
#define TIMER_1_MAX_VALUE 0xffffffff
|
||||
#define TIMER_1_IRQn_1 GPTIMER_1A_IRQn
|
||||
#define TIMER_1_IRQn_2 GPTIMER_1B_IRQn
|
||||
|
||||
/* Timer 2 configuration */
|
||||
#define TIMER_2_DEV GPTIMER2
|
||||
#define TIMER_2_CHANNELS NUM_CHANNELS_PER_GPTIMER
|
||||
#define TIMER_2_MAX_VALUE 0xffffffff
|
||||
#define TIMER_2_IRQn_1 GPTIMER_2A_IRQn
|
||||
#define TIMER_2_IRQn_2 GPTIMER_2B_IRQn
|
||||
|
||||
/* Timer 3 configuration */
|
||||
#define TIMER_3_DEV GPTIMER3
|
||||
#define TIMER_3_CHANNELS NUM_CHANNELS_PER_GPTIMER
|
||||
#define TIMER_3_MAX_VALUE 0xffffffff
|
||||
#define TIMER_3_IRQn_1 GPTIMER_3A_IRQn
|
||||
#define TIMER_3_IRQn_2 GPTIMER_3B_IRQn
|
||||
/** @} */
|
||||
|
||||
|
||||
/**
|
||||
* @name UART configuration
|
||||
* @{
|
||||
*/
|
||||
#define UART_NUMOF 1
|
||||
|
||||
#define UART_0_EN 1
|
||||
#define UART_1_EN 0
|
||||
#define UART_2_EN 0
|
||||
#define UART_3_EN 0
|
||||
|
||||
#define UART_IRQ_PRIO 1
|
||||
|
||||
/* UART 0 device configuration */
|
||||
#define UART_0_DEV UART0
|
||||
#define UART_0_IRQ UART0_IRQn
|
||||
/* UART 0 pin configuration */
|
||||
#define UART_0_TX_PIN GPIO_PA1
|
||||
#define UART_0_RX_PIN GPIO_PA0
|
||||
|
||||
/* UART 1 device configuration */
|
||||
#define UART_1_DEV UART1
|
||||
#define UART_1_IRQ UART1_IRQn
|
||||
/* UART 1 pin configuration */
|
||||
#define UART_1_RTS_PIN GPIO_PD3
|
||||
#define UART_1_CTS_PIN GPIO_PB0
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name Random Number Generator configuration
|
||||
* @{
|
||||
*/
|
||||
#define RANDOM_NUMOF 1
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name GPIO configuration
|
||||
* @{
|
||||
*/
|
||||
#define GPIO_NUMOF 32
|
||||
|
||||
#define GPIO_IRQ_PRIO 1
|
||||
|
||||
#define GPIO_0_EN 1
|
||||
#define GPIO_1_EN 1
|
||||
#define GPIO_2_EN 1
|
||||
#define GPIO_3_EN 1
|
||||
#define GPIO_4_EN 1
|
||||
#define GPIO_5_EN 1
|
||||
#define GPIO_6_EN 1
|
||||
#define GPIO_7_EN 1
|
||||
#define GPIO_8_EN 1
|
||||
#define GPIO_9_EN 1
|
||||
#define GPIO_10_EN 1
|
||||
#define GPIO_11_EN 1
|
||||
#define GPIO_12_EN 1
|
||||
#define GPIO_13_EN 1
|
||||
#define GPIO_14_EN 1
|
||||
#define GPIO_15_EN 1
|
||||
#define GPIO_16_EN 1
|
||||
#define GPIO_17_EN 1
|
||||
#define GPIO_18_EN 1
|
||||
#define GPIO_19_EN 1
|
||||
#define GPIO_20_EN 1
|
||||
#define GPIO_21_EN 1
|
||||
#define GPIO_22_EN 1
|
||||
#define GPIO_23_EN 1
|
||||
#define GPIO_24_EN 1
|
||||
#define GPIO_25_EN 1
|
||||
#define GPIO_26_EN 1
|
||||
#define GPIO_27_EN 1
|
||||
#define GPIO_28_EN 1
|
||||
#define GPIO_29_EN 1
|
||||
#define GPIO_30_EN 1
|
||||
#define GPIO_31_EN 1
|
||||
|
||||
/* GPIO channel configuration */
|
||||
#define GPIO_0_PIN GPIO_PA0
|
||||
#define GPIO_1_PIN GPIO_PA1
|
||||
#define GPIO_2_PIN GPIO_PA2
|
||||
#define GPIO_3_PIN GPIO_PA3
|
||||
#define GPIO_4_PIN GPIO_PA4
|
||||
#define GPIO_5_PIN GPIO_PA5
|
||||
#define GPIO_6_PIN GPIO_PA6
|
||||
#define GPIO_7_PIN GPIO_PA7
|
||||
#define GPIO_8_PIN GPIO_PB0
|
||||
#define GPIO_9_PIN GPIO_PB1
|
||||
#define GPIO_10_PIN GPIO_PB2
|
||||
#define GPIO_11_PIN GPIO_PB3
|
||||
#define GPIO_12_PIN GPIO_PB4
|
||||
#define GPIO_13_PIN GPIO_PB5
|
||||
#define GPIO_14_PIN GPIO_PB6
|
||||
#define GPIO_15_PIN GPIO_PB7
|
||||
#define GPIO_16_PIN GPIO_PC0
|
||||
#define GPIO_17_PIN GPIO_PC1
|
||||
#define GPIO_18_PIN GPIO_PC2
|
||||
#define GPIO_19_PIN GPIO_PC3
|
||||
#define GPIO_20_PIN GPIO_PC4
|
||||
#define GPIO_21_PIN GPIO_PC5
|
||||
#define GPIO_22_PIN GPIO_PC6
|
||||
#define GPIO_23_PIN GPIO_PC7
|
||||
#define GPIO_24_PIN GPIO_PD0
|
||||
#define GPIO_25_PIN GPIO_PD1
|
||||
#define GPIO_26_PIN GPIO_PD2
|
||||
#define GPIO_27_PIN GPIO_PD3
|
||||
#define GPIO_28_PIN GPIO_PD4
|
||||
#define GPIO_29_PIN GPIO_PD5
|
||||
#define GPIO_30_PIN GPIO_PD6
|
||||
#define GPIO_31_PIN GPIO_PD7
|
||||
/** @} */
|
||||
|
||||
#ifdef __cplusplus
|
||||
} /* end extern "C" */
|
||||
#endif
|
||||
|
||||
#endif /* __PERIPH_CONF_H */
|
||||
/** @} */
|
@ -0,0 +1,7 @@
|
||||
# Define the module that is built:
|
||||
MODULE = cpu
|
||||
|
||||
# Add a list of subdirectories, that should also be built:
|
||||
DIRS = periph $(CORTEX_COMMON)
|
||||
|
||||
include $(RIOTBASE)/Makefile.base
|
@ -0,0 +1,35 @@
|
||||
# This CPU implementation is using the new core/CPU interface:
|
||||
export CFLAGS += -DCOREIF_NG=1
|
||||
|
||||
# Tell the build system that the CPU depends on the Cortex-M common files:
|
||||
export USEMODULE += cortex-m3_common
|
||||
|
||||
# Define path to cortex-m common module, which is needed for this CPU:
|
||||
export CORTEX_COMMON = $(RIOTCPU)/cortex-m3_common/
|
||||
|
||||
# Define the linker script to use for this CPU:
|
||||
export LINKERSCRIPT = $(RIOTCPU)/$(CPU)/$(CPU_MODEL)_linkerscript.ld
|
||||
|
||||
# Include CPU specific includes:
|
||||
export INCLUDES += -I$(RIOTCPU)/$(CPU)/include
|
||||
|
||||
# Explicitly tell the linker to link the syscalls and startup code.
|
||||
# Without this the interrupt vectors will not be linked correctly!
|
||||
export UNDEF += $(BINDIR)cpu/syscalls.o
|
||||
export UNDEF += $(BINDIR)cpu/startup.o
|
||||
|
||||
# Export the peripheral drivers to be linked into the final binary:
|
||||
export USEMODULE += periph
|
||||
|
||||
# this CPU implementation makes use of the ringbuffer, so include the lib module
|
||||
export USEMODULE += lib
|
||||
|
||||
# CPU depends on the cortex-m common module, so include it:
|
||||
include $(CORTEX_COMMON)Makefile.include
|
||||
|
||||
# Avoid overriding the default rule:
|
||||
all:
|
||||
|
||||
# Rule to generate assembly listings from ELF files:
|
||||
%.lst: %.elf
|
||||
$(OBJDUMP) $(OBJDUMPFLAGS) $< > $@
|
@ -0,0 +1,140 @@
|
||||
/* ----------------------------------------------------------------------------
|
||||
* SAM Software Package License
|
||||
* ----------------------------------------------------------------------------
|
||||
* Copyright (c) 2012, Atmel Corporation
|
||||
*
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following condition is met:
|
||||
*
|
||||
* - Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the disclaimer below.
|
||||
*
|
||||
* Atmel's name may not be used to endorse or promote products derived from
|
||||
* this software without specific prior written permission.
|
||||
*
|
||||
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
|
||||
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
|
||||
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
|
||||
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
|
||||
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
|
||||
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
* ----------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
|
||||
OUTPUT_ARCH(arm)
|
||||
SEARCH_DIR(.)
|
||||
|
||||
/* The stack size used by the application. NOTE: you need to adjust */
|
||||
STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 2K ;
|
||||
|
||||
/* Section Definitions */
|
||||
SECTIONS
|
||||
{
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sfixed = .;
|
||||
KEEP(*(.vectors .vectors.*))
|
||||
*(.text .text.* .gnu.linkonce.t.*)
|
||||
*(.glue_7t) *(.glue_7)
|
||||
*(.rodata .rodata* .gnu.linkonce.r.*)
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
|
||||
/* Support C constructors, and C destructors in both user code
|
||||
and the C library. This also provides support for C++ code. */
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.init))
|
||||
. = ALIGN(4);
|
||||
__preinit_array_start = .;
|
||||
KEEP (*(.preinit_array))
|
||||
__preinit_array_end = .;
|
||||
|
||||
. = ALIGN(4);
|
||||
__init_array_start = .;
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array))
|
||||
__init_array_end = .;
|
||||
|
||||
. = ALIGN(0x4);
|
||||
KEEP (*crtbegin.o(.ctors))
|
||||
KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
|
||||
KEEP (*(SORT(.ctors.*)))
|
||||
KEEP (*crtend.o(.ctors))
|
||||
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
__fini_array_start = .;
|
||||
KEEP (*(.fini_array))
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
__fini_array_end = .;
|
||||
|
||||
KEEP (*crtbegin.o(.dtors))
|
||||
KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
|
||||
KEEP (*(SORT(.dtors.*)))
|
||||
KEEP (*crtend.o(.dtors))
|
||||
|
||||
. = ALIGN(4);
|
||||
_efixed = .; /* End of text section */
|
||||
} > rom
|
||||
|
||||
/* .ARM.exidx is sorted, so has to go in its own output section. */
|
||||
PROVIDE_HIDDEN (__exidx_start = .);
|
||||
.ARM.exidx :
|
||||
{
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
} > rom
|
||||
PROVIDE_HIDDEN (__exidx_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .;
|
||||
|
||||
.relocate : AT (_etext)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_srelocate = .;
|
||||
*(.ramfunc .ramfunc.*);
|
||||
*(.data .data.*);
|
||||
. = ALIGN(4);
|
||||
_erelocate = .;
|
||||
} > ram
|
||||
|
||||
/* .bss section which is used for uninitialized data */
|
||||
.bss (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sbss = . ;
|
||||
_szero = .;
|
||||
*(.bss .bss.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = . ;
|
||||
_ezero = .;
|
||||
} > ram
|
||||
|
||||
/* stack section */
|
||||
.stack (NOLOAD):
|
||||
{
|
||||
. = ALIGN(8);
|
||||
_sstack = .;
|
||||
. = . + STACK_SIZE;
|
||||
. = ALIGN(8);
|
||||
_estack = .;
|
||||
} > ram
|
||||
|
||||
. = ALIGN(4);
|
||||
_end = . ;
|
||||
|
||||
.flashcca :
|
||||
{
|
||||
KEEP(*(.flashcca))
|
||||
} > cca
|
||||
}
|
@ -0,0 +1,30 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Loci Controls Inc.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @addtogroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file cc2538nf11_linkerscript.ld
|
||||
* @brief Linker script for the CC2538NF11 model MCU
|
||||
*
|
||||
* @author Ian Martin <ian@locicontrols.com>
|
||||
*/
|
||||
|
||||
/* Memory Space Definitions: */
|
||||
MEMORY
|
||||
{
|
||||
rom (rx ) : ORIGIN = 0x00200000, LENGTH = 128K - 44
|
||||
cca (rx ) : ORIGIN = 0x0027ffd4, LENGTH = 44
|
||||
sram1 (rwx) : ORIGIN = 0x20004000, LENGTH = 16K
|
||||
ram (rwx) : ORIGIN = 0x20004000, LENGTH = 16K
|
||||
}
|
||||
|
||||
INCLUDE cc2538_linkerscript.ld
|
||||
|
||||
/* @} */
|
@ -0,0 +1,31 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Loci Controls Inc.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @addtogroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file cc2538nf23_linkerscript.ld
|
||||
* @brief Linker script for the CC2538NF23 and CC2538SF23 model MCUs
|
||||
*
|
||||
* @author Ian Martin <ian@locicontrols.com>
|
||||
*/
|
||||
|
||||
/* Memory Space Definitions: */
|
||||
MEMORY
|
||||
{
|
||||
rom (rx ) : ORIGIN = 0x00200000, LENGTH = 256K - 44
|
||||
cca (rx ) : ORIGIN = 0x0027ffd4, LENGTH = 44
|
||||
sram0 (rwx) : ORIGIN = 0x20000000, LENGTH = 16K /* Lost in PM2 and PM3 */
|
||||
sram1 (rwx) : ORIGIN = 0x20004000, LENGTH = 16K
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 32K
|
||||
}
|
||||
|
||||
INCLUDE cc2538_linkerscript.ld
|
||||
|
||||
/* @} */
|
@ -0,0 +1,31 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Loci Controls Inc.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @addtogroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file cc2538nf53_linkerscript.ld
|
||||
* @brief Linker script for the CC2538NF53 and CC2538SF53 model MCUs
|
||||
*
|
||||
* @author Ian Martin <ian@locicontrols.com>
|
||||
*/
|
||||
|
||||
/* Memory Space Definitions: */
|
||||
MEMORY
|
||||
{
|
||||
rom (rx ) : ORIGIN = 0x00200000, LENGTH = 512K - 44
|
||||
cca (rx ) : ORIGIN = 0x0027ffd4, LENGTH = 44
|
||||
sram0 (rwx) : ORIGIN = 0x20000000, LENGTH = 16K /* Lost in PM2 and PM3 */
|
||||
sram1 (rwx) : ORIGIN = 0x20004000, LENGTH = 16K
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 32K
|
||||
}
|
||||
|
||||
INCLUDE cc2538_linkerscript.ld
|
||||
|
||||
/* @} */
|
@ -0,0 +1,90 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Loci Controls Inc.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file cpu.c
|
||||
* @brief Implementation of the CPU initialization
|
||||
*
|
||||
* @author Ian Martin <ian@locicontrols.com>
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "cpu.h"
|
||||
#include "sys-ctrl.h"
|
||||
|
||||
#define BIT(n) ( 1UL << (n) )
|
||||
|
||||
/* Select CLOCK_CTRL register bit masks: */
|
||||
#define OSC32K BIT(24) /**< 32-kHz clock oscillator selection */
|
||||
#define OSC_PD BIT(17) /**< Oscillator power-down */
|
||||
#define OSC BIT(16) /**< System clock oscillator selection */
|
||||
|
||||
/* CLOCK_CTRL register field offsets: */
|
||||
#define IO_DIV_SHIFT 8
|
||||
#define SYS_DIV_SHIFT 0
|
||||
|
||||
#define CLOCK_STA_MASK ( OSC32K | OSC )
|
||||
|
||||
static void cpu_clock_init(void);
|
||||
|
||||
/**
|
||||
* @brief Initialize the CPU, set IRQ priorities
|
||||
*/
|
||||
void cpu_init(void)
|
||||
{
|
||||
/* configure the vector table location to internal flash */
|
||||
SCB->VTOR = FLASH_BASE;
|
||||
|
||||
/* initialize the clock system */
|
||||
cpu_clock_init();
|
||||
|
||||
/* set pendSV interrupt to lowest possible priority */
|
||||
NVIC_SetPriority(PendSV_IRQn, 0xff);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configure the controllers clock system
|
||||
*/
|
||||
static void cpu_clock_init(void)
|
||||
{
|
||||
const uint32_t CLOCK_CTRL_VALUE =
|
||||
OSC_PD /**< Power down the oscillator not selected by OSC bit (hardware-controlled when selected). */
|
||||
| (1 << IO_DIV_SHIFT) /**< 16 MHz IO_DIV */
|
||||
| (1 << SYS_DIV_SHIFT) /**< 16 MHz SYS_DIV */
|
||||
#if !SYS_CTRL_OSC32K_USE_XTAL
|
||||
| OSC32K /**< Use internal RC oscillator. */
|
||||
#endif
|
||||
;
|
||||
|
||||
#if SYS_CTRL_OSC32K_USE_XTAL
|
||||
/* Set the XOSC32K_Q pads to analog for the external crystal: */
|
||||
gpio_software_control(GPIO_PD6);
|
||||
gpio_dir_input(GPIO_PD6);
|
||||
IOC_PXX_OVER[GPIO_PD6] = IOC_OVERRIDE_ANA;
|
||||
|
||||
gpio_software_control(GPIO_PD7);
|
||||
gpio_dir_input(GPIO_PD7);
|
||||
IOC_PXX_OVER[GPIO_PD7] = IOC_OVERRIDE_ANA;
|
||||
#endif
|
||||
|
||||
/* Configure the clock settings: */
|
||||
SYS_CTRL->CLOCK_CTRL = CLOCK_CTRL_VALUE;
|
||||
|
||||
/* Wait for the new clock settings to take effect: */
|
||||
while ( (SYS_CTRL->CLOCK_STA ^ CLOCK_CTRL_VALUE) & CLOCK_STA_MASK );
|
||||
|
||||
#if SYS_CTRL_OSC32K_USE_XTAL
|
||||
/* Wait for the 32-kHz crystal oscillator to stabilize: */
|
||||
while ( SYS_CTRL->CLOCK_STAbits.SYNC_32K);
|
||||
while (!SYS_CTRL->CLOCK_STAbits.SYNC_32K);
|
||||
#endif
|
||||