spinnaker_tools (BMP) 3.4.0
SpiNNaker BMP firmware
Loading...
Searching...
No Matches
Data Structures | Macros | Typedefs | Enumerations | Variables
bmp.h File Reference

Header file for Spin4/Spin5 Board Management Processor (BMP, LPC1768) More...

#include <stdint.h>
#include <stdbool.h>

Go to the source code of this file.

Data Structures

struct  iptag_t
 IPTag entry (24 bytes) More...
 
struct  sdp_msg_t
 SDP message type definition. More...
 
struct  fl_dir_t
 Flash directory entry. More...
 
struct  ee_data_t
 Data read from EEPROM. More...
 
struct  board_stat_t
 Board status. More...
 
struct  ip_data_t
 Information about an IP address. More...
 
struct  cortex_vec_t
 Cortex master vector. More...
 
struct  boot_vec_t
 Boot vector. More...
 
struct  event_t
 Record of how to handle an event. More...
 

Macros

#define BMP_VER_STR   "2.1.2"
 SpiNNaker BMP Version: string.
 
#define BMP_VER_NUM   0x020102
 SpiNNaker BMP Version: BCD.
 
#define BMP_ID_STR   "BC&MP/Spin5-BMP"
 SpiNNaker BMP software identifier.
 
#define CCLK   100000000
 CPU clock - 100 MHz.
 
#define NULL   0
 Null pointer.
 
#define LED_MASK    (LED_0 + LED_1 + LED_2 + LED_3 + LED_4 + LED_5 + LED_6 + LED_7)
 Mask for LED control bits.
 
#define NUM_FPGAS   3
 Number of FPGAs available (on SpiNN-5 board)
 
#define IO_STD   ((char *) 0)
 IO stream that goes immediately to host (tubotron)
 
#define IO_DBG   ((char *) 1)
 IO stream for debugging.
 
#define IO_LCD   ((char *) 2)
 IO stream that goes to the LCD panel.
 
#define IO_NULL   ((char *) 3)
 IO stream that gets dumped.
 
#define LCD_POS(x, y)   (0x80 + (y) * 64 + (x))
 LCD cursor position to motion control byte encoder.
 
#define FL_DIR_SIZE   16
 Number of fl_dir entries.
 
#define UNI_VEC_SIZE   8
 Size of uni_vec, in words.
 
#define DBG_VEC_SIZE   16
 Size of dbg_vec, in words.
 
#define CAN_SIZE   24
 Number of boards that can be managed over the CAN bus.
 

Typedefs

typedef void(* LPC_IAP) (uint32_t *cmd, uint32_t *res)
 LPC17xx In-Application Programming entry point.
 

Enumerations

enum  bmp_led_code {
  LED_0 = (1 << 4) , LED_1 = (1 << 5) , LED_2 = (1 << 19) , LED_3 = (1 << 20) ,
  LED_4 = (1 << 21) , LED_5 = (1 << 22) , LED_6 = (1 << 29) , LED_7 = (1 << 30)
}
 Encoding of LED control bits. More...
 
enum  bmp_gpio_bits { SF_NCS = (1 << 16) , XFSEL_0 = (1 << 25) , XFSEL_1 = (1 << 26) , XFSEL_2 = (1 << 29) }
 Miscellaneous GPIO bits. More...
 
enum  bmp_fpga_command { FPGA_READ = 0 , FPGA_WRITE = 1 }
 Directions for fpga_word() More...
 
enum  bmp_fl_dir_type { FL_BMP_IP = 1 , FL_SPIN_IP = 2 , FL_FPGA = 3 , FL_XREG = 4 }
 Values in fl_dir->type.
 
enum  bmp_proc_opcodes { PROC_RESET = 0 , PROC_POWER = 1 , PROC_LED = 2 }
 Commands that can be invoked over CAN. More...
 
enum  bmp_power_status_commands { POWER_ON = 2 , POWER_OFF = 0 , POWER_SHUT = 1 }
 

Functions

bmp_i2c.c
void configure_i2c (void)
 Set up I2C0 and I2C2 - 25MHz PCLK.
 
uint32_t i2c_poll (LPC_I2C_TypeDef *restrict i2c, uint32_t ctrl)
 Poll an I2C port.
 
uint32_t i2c_receive (LPC_I2C_TypeDef *restrict i2c, uint32_t ctrl, uint32_t addr, uint32_t length, void *buf)
 Receive a buffer over I2C.
 
uint32_t i2c_send (LPC_I2C_TypeDef *restrict i2c, uint32_t ctrl, uint32_t addr, uint32_t length, const void *buf)
 Send a buffer over I2C.
 
int16_t read_ts (LPC_I2C_TypeDef *restrict i2c, uint32_t addr)
 Read temperature sensor.
 
uint32_t read_ee (uint32_t addr, uint32_t count, void *buf)
 Read from EEPROM.
 
uint32_t write_ee (uint32_t addr, uint32_t count, const void *buf)
 Write to EEPROM.
 
void configure_lcd (void)
 Configure the LCD.
 
void lcd_ctrl (uint32_t c)
 Write a control byte to the LCD.
 
void lcd_putc (uint32_t c)
 Write a character to the LCD. Buffers.
 
bmp_hw.c
void clock_div (uint32_t bit_pos, uint32_t value)
 Configure clock division.
 
void delay_us (uint32_t n)
 Delay using a busy loop.
 
void delay_ms (uint32_t n)
 Delay using a busy loop.
 
void configure_hw (void)
 Configure the BMP hardware.
 
void read_adc (void)
 Read voltage from an ADC (directly into board_stat_t::adc) and start the read of the next ADC.
 
void read_temp (void)
 Read I2C temperature sensors and also compute the fan speed.
 
void read_fans (void)
 Count transitions on the fan sensor inputs.
 
void set_power (uint32_t state)
 Turn board off or on.
 
void reset_spin (uint32_t code)
 Resets SpiNNaker by raising/lowering POR and switching the Serial Flash multiplexer as needed when POR falls.
 
void fpga_reset (uint32_t code)
 Reset the FPGAs.
 
uint32_t fpga_init (uint32_t mask)
 Initialise FPGAs.
 
void refresh_wdt (void)
 Refresh the watchdog timer so that the watchdog doesn't bark.
 
void led_set (uint32_t leds)
 Control the LEDs.
 
void ssp0_pins (uint32_t on)
 Set up GPIO pins that talk to Flash.
 
uint32_t cpu_int_off (void)
 Disable interrupts.
 
void cpu_int_restore (uint32_t cpsr)
 Restore interrupts.
 
bmp_flash.c
uint32_t is_blank (const void *buf, uint32_t len)
 Check if an area of memory is blank (filled with 0xFF)
 
uint32_t flash_sector (uint32_t addr)
 Convert flash address to sector number (LPC17xx specific)
 
uint32_t flash_write (uint32_t addr, uint32_t length, const uint32_t *buffer)
 Write to flash from supplied buffer. Only writes one sector.
 
uint32_t flash_erase (uint32_t start, uint32_t end)
 Erase sectors given start and end (byte) addresses.
 
bmp_clock.c
void configure_clocks (void)
 Configure the clocks.
 
bmp_cmd.c
void flash_buf_init (void)
 Initialise flash_buf.
 
void proc_power (uint32_t arg1, uint32_t arg2)
 Control power for this board; calls set_power() (and sf_scan() and reset_spin() if powering on)
 
void proc_reset (uint32_t arg1, uint32_t arg2)
 Board reset handler; calls reset_spin()
 
void proc_led (uint32_t arg1, uint32_t arg2)
 Control the LEDs on this board; call led_set()
 
uint32_t debug (sdp_msg_t *)
 SDP message dispatcher.
 
bmp_net.c
void eth_receive (void)
 Receive a packet off the ethernet hardware.
 
void copy_ip_data (void)
 Copy IP address data from Flash (bmp_flash_ip and spin_flash_ip)
 
void iptag_timer (void)
 IPTag timeout tick. Called from proc_100hz() every 10ms.
 
void copy_ip (const uint8_t *restrict f, uint8_t *restrict t)
 Copy IP address.
 
void arp_lookup (iptag_t *iptag)
 Request an ARP lookup.
 
uint32_t iptag_new (void)
 Allocate a transient IPTag.
 
void msg_init (void)
 Initialise the message queue.
 
sdp_msg_tmsg_get (void)
 "Allocate" a message from the free message pool
 
uint32_t msg_queue_size (void)
 How big is the message queue?
 
uint32_t msg_queue_insert (sdp_msg_t *msg)
 Insert a message in the message queue.
 
sdp_msg_tmsg_queue_remove (void)
 Get a message from the head of the message queue and remove it from the queue.
 
void route_msg (sdp_msg_t *msg)
 Route a message to its destination.
 
bmp_eth.c
uint32_t eth_rx_rdy (void)
 Is the ethernet hardware ready to receive?
 
uint32_t eth_tx_rdy (void)
 Is the ethernet hardware ready to transmit?
 
uint32_t eth_rx_size (void)
 Get size of received data.
 
void eth_update_tx (void)
 Select the next transmission buffer.
 
void eth_rx_discard (void)
 Discard received packet, releasing buffer for reuse.
 
void eth_copy_txbuf (uint32_t *buffer, uint32_t length)
 Copy supplied buffer into transmit hardware.
 
void eth_copy_rxbuf (uint32_t *buffer, uint32_t length)
 Copy received message into supplied buffer.
 
void configure_eth (const uint8_t *mac_addr)
 Configure the ethernet hardware.
 
bmp_can.c
void configure_can (uint32_t id)
 Initialises the CAN controller.
 
uint32_t can_send_msg (uint32_t dest, sdp_msg_t *msg)
 Send an SDP message over the CAN.
 
void can_timer (void)
 This is called every 10ms on all boards.
 
void can_proc_cmd (uint32_t dest, uint32_t op, uint32_t arg1, uint32_t arg2)
 Asks another BMP to run a proc from proc_list.
 
bmp_crc.c
uint32_t crc32 (void *buf, uint32_t len, uint32_t crc)
 Compute CRC32 for a buffer of given length.
 
uint32_t crc32_chk (void *buf, uint32_t len)
 Compute the CRC of a buffer.
 
void crc32_buf (void *buf, uint32_t len)
 Compute and insert CRC32 of a buffer where the CRC is placed in the last 4 bytes.
 
bmp_io.c
void io_printf (char *stream, char *f,...)
 Print to an output stream.
 
bmp_ssp.c
void configure_ssp (void)
 Configure SSP (serial flash, FPGAs)
 
void ssp1_fast (void)
 Configure SSP1 to be fast.
 
void ssp1_slow (void)
 Configure SSP1 to be slow.
 
void ssp0_read (uint32_t cmd, uint32_t addr, uint32_t len, uint8_t *buf)
 Read buffer from Serial Flash.
 
void ssp0_write (uint32_t cmd, uint32_t addr, uint32_t len, const uint8_t *buf)
 Write buffer to Serial Flash.
 
void ssp0_copy (uint32_t addr, uint32_t len)
 Copy from Serial Flash on SSP0 to FPGA(s) on SSP1.
 
void ssp1_copy (uint32_t count, const uint8_t *buf)
 Copy buffer to FPGAs.
 
void sf_read (uint32_t addr, uint32_t len, uint8_t *buf)
 Read from flash.
 
void sf_write (uint32_t addr, uint32_t len, const uint8_t *buf)
 Write to flash.
 
uint32_t sf_crc32 (uint32_t addr, uint32_t len)
 Compute CRC of data on flash.
 
void fpga_word (uint32_t addr, uint32_t fpga, uint32_t *buf, uint32_t dir)
 Read or write an FPGA.
 

Variables

static fl_dir_t *const fl_dir = (fl_dir_t *) 0x1000
 Address in Flash of Flash directory.
 
static ip_data_t *const bmp_flash_ip = (ip_data_t *) 0x1020
 Address in Flash of BMP IP address.
 
static ip_data_t *const spin_flash_ip = (ip_data_t *) 0x10a0
 Address in Flash of SpiNNaker base IP address.
 
static LPC_IAP const lpc_iap = (LPC_IAP) 0x1fff1ff1
 LPC17xx In Application Programming entry point.
 
static uint32_t *const flash_buf = (uint32_t *) 0x10000000
 4096 byte buffer used for writing to Flash and as a general purpose buffer
 
static uint32_t *const uni_vec = (uint32_t *) 0x10001000
 32 byte (8 word) uninitialised vector
 
static uint32_t *const dbg_vec = (uint32_t *) 0x10001020
 64 byte (16 word) uninitialised fault debug vector
 
uint8_t can_ID
 CAN ID (from backplane)
 
uint8_t board_ID
 Board ID (devived from can_ID)
 
bool bp_ctrl
 Backplane controller.
 
bool fan_sense
 Compute fan speed.
 
uint8_t power_state
 Power supply state.
 
ip_data_t spin_ip
 IP address of the board we manage.
 
ip_data_t bmp_ip
 Our own IP address.
 
uint8_t can_status [CAN_SIZE]
 Whether a particular board is talking to the CAN bus.
 
board_stat_t board_stat [CAN_SIZE]
 Board status.
 
ee_data_t ee_data
 Copy of EEPROM data.
 
bool lcd_active
 Whether the LCD is active; if not, nothing should be sent to the LCD.
 
uint32_t boot_sec
 Boot block number.
 
uint32_t up_time
 
const uint8_t * can2board
 Mapping from CAN ID to board number.
 
const uint8_t * board2can
 Mapping from board number to CAN ID.
 
bool data_ok
 Data sector CRC OK.
 
iptag_t tag_table []
 The table of IPTags.
 
const uint32_t hw_ver
 Hardware version.
 

SDP

#define BOARD_MASK   31
 How to mask off the board bits.
 
#define FLASH_BYTES   4096
 Size of flash buffer (bytes)
 
#define FLASH_WORDS   1024
 
#define PORT_SHIFT   5
 Where the port is in the SDP port/board word.
 
#define PORT_MASK   7
 How to mask off the port bits.
 
#define BOARD_MASK   31
 How to mask off the board bits.
 
#define PORT_ETH   (7 << PORT_SHIFT)
 SDP port for Ethernet traffic.
 
#define SDP_BUF_SIZE   256
 Size of user data area of SDP message.
 
enum  bmp_commands {
  CMD_VER = 0 , CMD_RUN = 1 , CMD_READ = 2 , CMD_WRITE = 3 ,
  CMD_FILL = 5 , CMD_FPGA_READ = 17 , CMD_FPGA_WRITE = 18 , CMD_LED = 25 ,
  CMD_IPTAG = 26 , CMD_BMP_INFO = 48 , CMD_FLASH_COPY = 49 , CMD_FLASH_ERASE = 50 ,
  CMD_FLASH_WRITE = 51 , CMD_BMP_SF = 53 , CMD_BMP_EE = 54 , CMD_RESET = 55 ,
  CMD_XILINX = 56 , CMD_POWER = 57 , CMD_BMP_I2C = 61 , CMD_BMP_PWM = 62 ,
  CMD_TUBE = 64
}
 Commands supported by the BMP. More...
 
enum  bmp_type_code { TYPE_BYTE = 0 , TYPE_HALF = 1 , TYPE_WORD = 2 }
 Data transfer unit. More...
 
enum  bmp_return_code {
  RC_OK = 0x80 , RC_LEN = 0x81 , RC_SUM = 0x82 , RC_CMD = 0x83 ,
  RC_ARG = 0x84 , RC_PORT = 0x85 , RC_TIMEOUT = 0x86 , RC_ROUTE = 0x87 ,
  RC_CPU = 0x88
}
 SDP return codes. More...
 

IPTAG definitions

#define IPTAG_MAX   4
 Max operation code in bmp_iptag_commands.
 
#define TAG_NONE   255
 Invalid tag/transient request.
 
#define TAG_HOST   0
 Reserved for host.
 
#define TAG_FIXED_SIZE   8
 Number of user-controllable IPTags.
 
#define TAG_POOL_SIZE   8
 Number of transient IPTags.
 
#define FIRST_POOL_TAG   TAG_FIXED_SIZE
 Index of first transient IPTag.
 
#define LAST_POOL_TAG   (TAG_FIXED_SIZE + TAG_POOL_SIZE - 1)
 Index of last transient IPTag.
 
#define TAG_TABLE_SIZE   (TAG_FIXED_SIZE + TAG_POOL_SIZE)
 Size of the table of IPTags.
 
#define SDPF_REPLY   0x80
 SDP flag bit: reply desired.
 
enum  bmp_iptag_commands {
  IPTAG_NEW = 0 , IPTAG_SET = 1 , IPTAG_GET = 2 , IPTAG_CLR = 3 ,
  IPTAG_TTO = 4
}
 Subcommands for manipulating IPTags. More...
 
enum  bmp_iptag_flags { IPTAG_VALID = 0x8000 , IPTAG_TRANS = 0x4000 , IPTAG_ARP = 0x2000 }
 Flags on IPTags. More...
 

Cortex boot vector formats

typedef void(* handler) (void)
 Type of an interrupt handler.
 
typedef void(* proc4) (uint32_t, uint32_t, uint32_t, uint32_t)
 Type of a function that takes four arguments.
 
typedef void(* main_proc) (void *, uint32_t, uint32_t, uint32_t)
 Type of a main entry point.
 
static boot_vec_t *const boot_vec = (boot_vec_t *) 0
 Boot vector.
 
cortex_vec_tcortex_vec
 Cortex boot vector.
 

bmp_event.c

typedef void(* event_proc) (uint32_t, uint32_t)
 The type of an event handler.
 
void event_init (uint32_t priority)
 Initialise the event processing system.
 
event_tevent_new (event_proc proc, uint32_t a1, uint32_t a2)
 Allocates a new event.
 
void event_set_byte (uint32_t addr, uint32_t data)
 Set a byte at an address.
 
void event_schedule (event_t *e, uint32_t t)
 Schedules an event to occur some time in the future.
 
void event_cancel (event_t *e, uint32_t ID)
 Cancel an event that was previously scheduled.
 
void proc_queue_add (event_t *e)
 Adds an event to a list of events which can (all) be executed at some later time.
 
void proc_queue_run (void)
 Execute a list of events (in the order in which they were added to the list).
 

Detailed Description

Header file for Spin4/Spin5 Board Management Processor (BMP, LPC1768)


Data Structure Documentation

◆ iptag_t

struct iptag_t

IPTag entry (24 bytes)

Data Fields
uint8_t ip[4] IP address of target.
uint8_t mac[6] MAC address of target.
uint16_t port UDP port of target.
uint16_t timeout Timeout (in 10ms ticks)
uint16_t flags Flags (bmp_iptag_flags)
uint32_t count Count of messages sent via IPTag.

◆ sdp_msg_t

struct sdp_msg_t

SDP message type definition.

Note that the length field is the number of bytes following the checksum. It will be a minimum of 8 as the SDP header should always be present.

Data Fields
struct sdp_msg * next Next in free list.
uint16_t length length
uint16_t checksum checksum (if used)
uint8_t flags SDP flag byte.
uint8_t tag SDP IPtag.
uint8_t dest_port SDP destination port/CPU.
uint8_t srce_port SDP source port/CPU.
uint16_t dest_addr SDP destination address.
uint16_t srce_addr SDP source address.
uint16_t cmd_rc Command/Return Code.
uint16_t seq Sequence number.
uint32_t arg1 Arg 1.
uint32_t arg2 Arg 2.
uint32_t arg3 Arg 3.
uint8_t data[SDP_BUF_SIZE] User data (256 bytes)

◆ fl_dir_t

struct fl_dir_t

Flash directory entry.

Data Fields
uint8_t type
uint8_t size
uint16_t flags
uint32_t time
uint32_t crc
uint32_t base
uint32_t length
uint32_t p0
uint32_t p1
uint32_t p2
uint8_t data[96]

◆ ee_data_t

struct ee_data_t

Data read from EEPROM.

Data Fields
uint8_t marker 0: == 0x96
uint8_t sw_ver 1: EE Data format version
uint8_t hw_ver 2: Backplane HW version (0..7)
uint8_t frame_ID 3: Frame Identifier
uint32_t mod_date 4: Date written
uint8_t gw_addr[4] 8: Gateway address (& IP base)
uint8_t flags 12: 8 flag bits
uint8_t mask_bits 13: IP mask bits (0..31)
uint8_t mac_byte 14: Byte 1 of MAC address
uint8_t LCD_time 15: Time (secs) for initial display
int8_t warn_int[4] 32: Int Temp Warning settings
int8_t shut_int[4] 36: Int Temp Shutdown settings
int8_t warn_ext[4] 40: Ext Temp Warning settings
int8_t shut_ext[4] 44: Ext Temp Shutdown settings
uint8_t warn_fan[4] 48: Fan Speed Warning settings
uint8_t shut_fan[4] 52: Fan Speed Shutdown settings
uint8_t warn_vlow[8] 56: Under-voltage Warning settings
uint8_t shut_vlow[8] 64: Under-voltage Shutdown settings
uint8_t warn_vhigh[8] 72: Over-voltage Warning settings
uint8_t shut_vhigh[8] 80: Over-voltage Shutdown settings
uint32_t CRC32 252: CRC

◆ board_stat_t

struct board_stat_t

Board status.

Data Fields
uint16_t adc[8] Voltages.
int16_t t_int[4] Internal temperatures.
int16_t t_ext[4] External temperatures.
uint16_t fan[4] Fan speeds.
uint32_t warning Warning flags.
uint32_t shutdown Shutdown flags.

◆ ip_data_t

struct ip_data_t

Information about an IP address.

Data Fields
uint16_t flags Miscellaneous flags.
uint8_t mac_addr[6] MAC address.
uint8_t ip_addr[4] IP address.
uint8_t gw_addr[4] Gateway IP address.
uint8_t net_mask[4] Net mask.
uint16_t udp_port UDP port.

◆ cortex_vec_t

struct cortex_vec_t

Cortex master vector.

Data Fields
uint32_t * stack_top
main_proc main
handler NMI
handler HardFault
handler MemManage
handler BusFault
handler UsageFault
handler Rsvd_7
handler Rsvd_8
handler Rsvd_9
handler Rsvd_10
handler SVC
handler DebugMon
handler Rsvd_13
handler PendSV
handler SysTickH
handler WDT
handler TIMER0
handler TIMER1
handler TIMER2
handler TIMER3
handler UART0
handler UART1
handler UART2
handler UART3
handler PWM1
handler I2C0
handler I2C1
handler I2C2
handler SPI
handler SSP0
handler SSP1
handler PLL0
handler RTC
handler EINT0
handler EINT1
handler EINT2
handler EINT3
handler ADC
handler BOD
handler USB
handler CAN
handler DMA
handler I2S
handler ENET
handler RIT
handler MCPWM
handler QEI
handler PLL1
handler USBActivity
handler CANActivity
handler Rsvd_51
handler Rsvd_52
uint32_t build_date
uint32_t sw_ver
uint32_t RO_length
uint32_t RW_length
uint32_t * RO_limit
uint32_t * RW_base
uint32_t * RW_limit
uint32_t * ZI_base
uint32_t * ZI_limit
uint32_t * stack_base
uint32_t * stack_limit

◆ boot_vec_t

struct boot_vec_t

Boot vector.

Data Fields
uint32_t * stack_top Stack top.
handler boot_proc Boot handler.
proc4 flash_copy Flash copy.
proc4 Rsvd_3
proc4 Rsvd_4
uint32_t build_date Build date.
uint32_t sw_ver Software version.
uint32_t checksum Checksum.

◆ event_t

struct event_t

Record of how to handle an event.

Data Fields
event_proc proc Proc to be called or NULL.
uint32_t arg1 First arg to proc.
uint32_t arg2 Second arg to proc.
uint32_t time Time (CPU ticks) until event due (0 if at head of Q)
uint32_t ID Unique ID for active event (0 if inactive)
event_t * next Next in Q or NULL.

Macro Definition Documentation

◆ FLASH_WORDS

#define FLASH_WORDS   1024

Size of flash buffer (words)

◆ LCD_POS

#define LCD_POS (   x,
 
)    (0x80 + (y) * 64 + (x))

LCD cursor position to motion control byte encoder.

Parameters
[in]xTarget X location (0..20)
[in]yTarget Y location (0..1)
Returns
control byte that will, when printed, move the LCD cursor

◆ CAN_SIZE

#define CAN_SIZE   24

Number of boards that can be managed over the CAN bus.

This is the maximum number of boards in a frame.

Typedef Documentation

◆ LPC_IAP

typedef void(* LPC_IAP) (uint32_t *cmd, uint32_t *res)

LPC17xx In-Application Programming entry point.

Parameters
[in]cmdCommand to apply
[out]resResult

Enumeration Type Documentation

◆ bmp_led_code

Encoding of LED control bits.

Enumerator
LED_0 

Green.

LED_1 

Orange.

LED_2 

Red.

LED_3 

Green.

LED_4 

Green.

LED_5 

Green.

LED_6 

Green.

LED_7 

Red.

◆ bmp_gpio_bits

Miscellaneous GPIO bits.

Enumerator
XFSEL_0 

Port 3.

XFSEL_1 

Port 3.

XFSEL_2 

Port 4.

◆ bmp_fpga_command

Directions for fpga_word()

Enumerator
FPGA_READ 

Read from FPGA.

FPGA_WRITE 

Write to FPGA.

◆ bmp_commands

Commands supported by the BMP.

Enumerator
CMD_VER 

Get BMP version.

CMD_RUN 

Run.

CMD_READ 

Read memory.

CMD_WRITE 

Write memory.

CMD_FILL 

Fill memory.

CMD_FPGA_READ 

Read FPGA memory.

CMD_FPGA_WRITE 

Write FPGA memory.

CMD_LED 

Control LEDs.

CMD_IPTAG 

Control IPTags.

CMD_BMP_INFO 

Get BMP information.

CMD_FLASH_COPY 

Copy Flash.

CMD_FLASH_ERASE 

Erase Flash.

CMD_FLASH_WRITE 

Write Flash.

CMD_BMP_SF 

Access Boot Flash.

CMD_BMP_EE 

Access EEPROM.

CMD_RESET 

Reset boards.

CMD_XILINX 

Access XILINX.

CMD_POWER 

Control board power.

CMD_BMP_I2C 

Access I2C bus.

CMD_BMP_PWM 

Configure PWM.

CMD_TUBE 

tubotron: outbound message

◆ bmp_type_code

Data transfer unit.

Enumerator
TYPE_BYTE 

Transfer by bytes.

TYPE_HALF 

Transfer by half-words.

TYPE_WORD 

Transfer by words.

◆ bmp_return_code

SDP return codes.

Enumerator
RC_OK 

Command completed OK.

RC_LEN 

Bad packet length.

RC_SUM 

Bad checksum.

RC_CMD 

Bad/invalid command.

RC_ARG 

Invalid arguments.

RC_PORT 

Bad port number.

RC_TIMEOUT 

Timeout.

RC_ROUTE 

No P2P route.

RC_CPU 

Bad CPU number.

◆ bmp_iptag_commands

Subcommands for manipulating IPTags.

Enumerator
IPTAG_NEW 

Allocate and configure IPTag.

IPTAG_SET 

Configure existing IPTag.

IPTAG_GET 

Read IPTag status.

IPTAG_CLR 

Deallocate all IPTags.

IPTAG_TTO 

Set IPTag timeout (common)

◆ bmp_iptag_flags

Flags on IPTags.

Enumerator
IPTAG_VALID 

Entry is valid.

IPTAG_TRANS 

Entry is transient.

IPTAG_ARP 

Awaiting ARP resolution.

◆ bmp_proc_opcodes

Commands that can be invoked over CAN.

Enumerator
PROC_RESET 

proc_reset()

PROC_POWER 

proc_power()

PROC_LED 

proc_led()

Function Documentation

◆ event_init()

void event_init ( uint32_t  priority)

Initialise the event processing system.

Parameters
[in]priorityPriority to use for the driving timer interrupt

◆ event_new()

event_t * event_new ( event_proc  proc,
uint32_t  arg1,
uint32_t  arg2 
)

Allocates a new event.

Allocates a new event from the free queue and intialise "proc", "arg1" and "arg2" fields. The "ID", "next" and "time" fields are also set.

Parameters
[in]procThe event handler
[in]arg1First argument to pass to proc when event fires
[in]arg2Second argument to pass to proc when event fires
Returns
The allocated event, or NULL if no event can be allocated

◆ event_set_byte()

void event_set_byte ( uint32_t  addr,
uint32_t  data 
)

Set a byte at an address.

Parameters
[in]addrThe address to write at.
[in]dataThe value to write there.

◆ event_schedule()

void event_schedule ( event_t e,
uint32_t  time 
)

Schedules an event to occur some time in the future.

Parameters
[in]eThe event to schedule
[in]timeHow many μs in the future to schedule the event firing at

◆ event_cancel()

void event_cancel ( event_t e,
uint32_t  ID 
)

Cancel an event that was previously scheduled.

The ID that was allocated when the event was created must be given in case the event has already executed and possibly been recycled.

It is potentially quite difficult to cancel an event at the head of the event queue so in this case the "proc" is made NULL and the event left to terminate on the timer interrupt.

Parameters
[in]eThe event to cancel.
[in]IDThe ID that the event is expected to have.

◆ proc_queue_add()

void proc_queue_add ( event_t e)

Adds an event to a list of events which can (all) be executed at some later time.

The order of execution is the same as that of addition to the list.

Parameters
[in]eThe event to add.

◆ proc_queue_run()

void proc_queue_run ( void  )

Execute a list of events (in the order in which they were added to the list).

Events are returned to the free queue after execution.

◆ i2c_poll()

uint32_t i2c_poll ( LPC_I2C_TypeDef *restrict  i2c,
uint32_t  ctrl 
)

Poll an I2C port.

Parameters
[in]i2cWhich I2C port to poll
[in]ctrlControl byte
Returns
True if ACK received

◆ i2c_receive()

uint32_t i2c_receive ( LPC_I2C_TypeDef *restrict  i2c,
uint32_t  ctrl,
uint32_t  addr,
uint32_t  length,
void *  buf 
)

Receive a buffer over I2C.

Parameters
[in]i2cWhich I2C port to receive via
[in]ctrlControl word
[in]addrSource address
[in]lengthNumber of bytes to receive
[in]bufBuffer of data to receive into
Returns
true if data was received

◆ i2c_send()

uint32_t i2c_send ( LPC_I2C_TypeDef *restrict  i2c,
uint32_t  ctrl,
uint32_t  addr,
uint32_t  length,
const void *  buf 
)

Send a buffer over I2C.

Parameters
[in]i2cWhich I2C port to send via
[in]ctrlControl word
[in]addrDestination address
[in]lengthNumber of bytes to write
[in]bufBuffer of data to write
Returns
true if data was written

◆ read_ts()

int16_t read_ts ( LPC_I2C_TypeDef *restrict  i2c,
uint32_t  addr 
)

Read temperature sensor.

Parameters
[in]i2cWhich I2C port to use
[in]addrWhat address to read. (Controls which sensor to read)
Returns
The temperature sensor value

◆ read_ee()

uint32_t read_ee ( uint32_t  addr,
uint32_t  count,
void *  buf 
)

Read from EEPROM.

Parameters
[in]addrAddress to read from
[in]countNumber of bytes to read
[in]bufBuffer to read into
Returns
True if the read succeeded

◆ write_ee()

uint32_t write_ee ( uint32_t  addr,
uint32_t  count,
const void *  buf 
)

Write to EEPROM.

Parameters
[in]addrAddress to write to
[in]countNumber of bytes to write
[in]bufBuffer to write from
Returns
True if the write succeeded

◆ lcd_ctrl()

void lcd_ctrl ( uint32_t  c)

Write a control byte to the LCD.

Parameters
[in]cControl byte to write

◆ lcd_putc()

void lcd_putc ( uint32_t  c)

Write a character to the LCD. Buffers.

Parameters
[in]cThe character to write

◆ clock_div()

void clock_div ( uint32_t  bit_pos,
uint32_t  value 
)

Configure clock division.

Parameters
bit_posthe bit position to configure
valuethe value of that bit

◆ delay_us()

void delay_us ( uint32_t  n)

Delay using a busy loop.

Parameters
[in]nHow many μs to delay for

◆ delay_ms()

void delay_ms ( uint32_t  n)

Delay using a busy loop.

Parameters
[in]nHow many milliseconds to delay for

◆ read_adc()

void read_adc ( void  )

Read voltage from an ADC (directly into board_stat_t::adc) and start the read of the next ADC.

This is called approx every 80ms from proc_100hz().

◆ read_temp()

void read_temp ( void  )

Read I2C temperature sensors and also compute the fan speed.

This routine is called once per second.

◆ read_fans()

void read_fans ( void  )

Count transitions on the fan sensor inputs.

This routine is called once per millisec and it's assumed that the fan speed is low enough for there to be no more than one transition per ms.

◆ set_power()

void set_power ( uint32_t  state)

Turn board off or on.

Parameters
[in]stateState to go into.

◆ reset_spin()

void reset_spin ( uint32_t  code)

Resets SpiNNaker by raising/lowering POR and switching the Serial Flash multiplexer as needed when POR falls.

Parameters
[in]codeHow to do the reset

code = 0 - lower POR (reset off) code = 1 - raise POR (reset on) code = 2 - pulse POR

If Bit 2 of code is set then the FPGAs are also reset

The Serial Flash is dual ported on Spin5 and the SpiNNaker root chip reads its IP address from it just after it is reset. The read takes about 12ms for the 'standard' IP address block of 32 bytes. If the Serial Flash is set up to contain more code, the delay of 20ms will need to be increased.

◆ fpga_reset()

void fpga_reset ( uint32_t  code)

Reset the FPGAs.

Parameters
[in]codeHow to do the reset. 0 = clear reset line, 1 = set reset line, 2 = cycle reset line

◆ fpga_init()

uint32_t fpga_init ( uint32_t  mask)

Initialise FPGAs.

Parameters
[in]maskWhich FPGAs to initialise
Returns
True if initalisation succeeded

◆ led_set()

void led_set ( uint32_t  leds)

Control the LEDs.

Parameters
[in]ledsEncoded packed LED control word. Two bits per LED: 0 = ignore, 1 = toggle, 2 = turn off, 3 = turn on.

◆ ssp0_pins()

void ssp0_pins ( uint32_t  on)

Set up GPIO pins that talk to Flash.

Parameters
[in]onTrue to enable

◆ cpu_int_off()

uint32_t cpu_int_off ( void  )

Disable interrupts.

Returns
old CPSR state

◆ cpu_int_restore()

void cpu_int_restore ( uint32_t  cpsr)

Restore interrupts.

Parameters
[in]cpsrold CPSR state to restore

◆ is_blank()

uint32_t is_blank ( const void *  buf,
uint32_t  len 
)

Check if an area of memory is blank (filled with 0xFF)

Parameters
[in]bufThe address of the area of memory
[in]lenThe size of the area of memory, in bytes
Returns
True if all bytes are 0xFF, false otherwise

◆ flash_sector()

uint32_t flash_sector ( uint32_t  addr)

Convert flash address to sector number (LPC17xx specific)

Sectors 0..15 are 4096 bytes and sectors 16..29 are 32768 bytes

Parameters
[in]addrAddress in flash
Returns
Sector number

◆ flash_write()

uint32_t flash_write ( uint32_t  addr,
uint32_t  length,
const uint32_t *  buffer 
)

Write to flash from supplied buffer. Only writes one sector.

Parameters
[in]addrbyte address in flash
[in]lengthnumber of bytes to write
[in]bufferdata to write
Returns
Result code

◆ flash_erase()

uint32_t flash_erase ( uint32_t  start,
uint32_t  end 
)

Erase sectors given start and end (byte) addresses.

Parameters
[in]startStarting address
[in]endEnding address
Returns
Result code

◆ proc_power()

void proc_power ( uint32_t  arg,
uint32_t  mask 
)

Control power for this board; calls set_power() (and sf_scan() and reset_spin() if powering on)

Parameters
[in]argtarget power state and pre-switch delay factor
[in]maskWhich boards are being controlled; this function only acts if this board is selected in the mask

◆ proc_reset()

void proc_reset ( uint32_t  arg,
uint32_t  mask 
)

Board reset handler; calls reset_spin()

Parameters
[in]argreset code and pre-reset delay factor
[in]maskWhich boards are being controlled; this function only acts if this board is selected in the mask

◆ proc_led()

void proc_led ( uint32_t  arg,
uint32_t  mask 
)

Control the LEDs on this board; call led_set()

Parameters
[in]argArgument to pass to led_set()
[in]maskWhich boards are being controlled; this function only acts if this board is selected in the mask

◆ debug()

uint32_t debug ( sdp_msg_t msg)

SDP message dispatcher.

Parameters
[in,out]msgThe SDP message. Updated to be the response
Returns
the length of the response payload

Delegates to:

◆ eth_receive()

void eth_receive ( void  )

Receive a packet off the ethernet hardware.

Delegates to:

◆ copy_ip()

void copy_ip ( const uint8_t *restrict  f,
uint8_t *restrict  t 
)

Copy IP address.

Parameters
[in]fWhere to copy from
[out]tWhere to copy to

◆ arp_lookup()

void arp_lookup ( iptag_t iptag)

Request an ARP lookup.

Parameters
[in]iptagThe IPTag to do the lookup for

◆ iptag_new()

uint32_t iptag_new ( void  )

Allocate a transient IPTag.

Returns
The IPTag ID, or TAG_NONE if allocation failed

◆ msg_get()

sdp_msg_t * msg_get ( void  )

"Allocate" a message from the free message pool

Returns
The message, or NULL if the pool is empty

◆ msg_queue_size()

uint32_t msg_queue_size ( void  )

How big is the message queue?

Returns
The number of messages in the queue

◆ msg_queue_insert()

uint32_t msg_queue_insert ( sdp_msg_t msg)

Insert a message in the message queue.

Parameters
[in]msgThe message to enqueue
Returns
True if the message was enqueued, false if the queue was full

◆ msg_queue_remove()

sdp_msg_t * msg_queue_remove ( void  )

Get a message from the head of the message queue and remove it from the queue.

Returns
the message, or NULL if the queue is empty

◆ route_msg()

void route_msg ( sdp_msg_t msg)

Route a message to its destination.

Parameters
[in]msgThe message to route. Ownership of the message is taken! Caller must not use the message after this.

◆ eth_rx_rdy()

uint32_t eth_rx_rdy ( void  )

Is the ethernet hardware ready to receive?

Returns
true if a packet has been received

◆ eth_tx_rdy()

uint32_t eth_tx_rdy ( void  )

Is the ethernet hardware ready to transmit?

Returns
true if a packet can be sent now

◆ eth_rx_size()

uint32_t eth_rx_size ( void  )

Get size of received data.

Returns
Size of message, in bytes

◆ eth_copy_txbuf()

void eth_copy_txbuf ( uint32_t *  buffer,
uint32_t  length 
)

Copy supplied buffer into transmit hardware.

Parameters
[in]bufferBuffer to copy the message from
[in]lengthLength of message

◆ eth_copy_rxbuf()

void eth_copy_rxbuf ( uint32_t *  buffer,
uint32_t  length 
)

Copy received message into supplied buffer.

Parameters
[out]bufferBuffer to copy the message into
[in]lengthLength of message. Buffer must be at least this large.

◆ configure_eth()

void configure_eth ( const uint8_t *  mac_addr)

Configure the ethernet hardware.

Parameters
[in]mac_addrThe MAC address to use

◆ configure_can()

void configure_can ( uint32_t  id)

Initialises the CAN controller.

Parameters
[in]idOur ID

◆ can_send_msg()

uint32_t can_send_msg ( uint32_t  dest,
sdp_msg_t msg 
)

Send an SDP message over the CAN.

Parameters
[in]destWhich board to send to
[in]msgThe message to send
Returns
SDP response code

◆ can_timer()

void can_timer ( void  )

This is called every 10ms on all boards.

Non-zero boards just use it to timeout the CAN LED. The zero board uses it to ping all other boards and send them "config1" and "config2"

◆ can_proc_cmd()

void can_proc_cmd ( uint32_t  dest,
uint32_t  op,
uint32_t  arg1,
uint32_t  arg2 
)

Asks another BMP to run a proc from proc_list.

Parameters
[in]destWho to ask
[in]opDescribes what operation to run
[in]arg1First payload word
[in]arg2Second payload word

◆ crc32()

uint32_t crc32 ( void *  buf,
uint32_t  len,
uint32_t  crc 
)

Compute CRC32 for a buffer of given length.

Parameters
[in]bufthe data to compute the CRC of
[in]lennumber of bytes in buf
[in]crccan be 0xffffffff to start checking, or result of a previous call.
Returns
The final result needs to be inverted to produce valid CRC32.

◆ crc32_chk()

uint32_t crc32_chk ( void *  buf,
uint32_t  len 
)

Compute the CRC of a buffer.

Parameters
[in]bufthe data to compute the CRC of
[in]lennumber of bytes in buf
Returns
The CRC of the buffer

◆ crc32_buf()

void crc32_buf ( void *  buf,
uint32_t  len 
)

Compute and insert CRC32 of a buffer where the CRC is placed in the last 4 bytes.

Parameters
[in]bufthe data to compute the CRC of
[in]lennumber of bytes in buf

◆ io_printf()

void io_printf ( char *  stream,
char *  f,
  ... 
)

Print to an output stream.

Parameters
[in]streamWhere to write to.
[in]fThe format string
[in]...Values to fill into the format string

◆ ssp0_read()

void ssp0_read ( uint32_t  cmd,
uint32_t  addr,
uint32_t  len,
uint8_t *  buf 
)

Read buffer from Serial Flash.

Parameters
[in]cmdCommand for SSP0
[in]addrWhere to read from
[in]lenHow many bytes to read
[out]bufBuffer to receive read bytes

◆ ssp0_write()

void ssp0_write ( uint32_t  cmd,
uint32_t  addr,
uint32_t  len,
const uint8_t *  buf 
)

Write buffer to Serial Flash.

Parameters
[in]cmdCommand for SSP0
[in]addrWhere to write to
[in]lenHow many bytes to write
[in]bufBuffer of bytes to write

◆ ssp0_copy()

void ssp0_copy ( uint32_t  addr,
uint32_t  len 
)

Copy from Serial Flash on SSP0 to FPGA(s) on SSP1.

Parameters
[in]addrAddress of data to move (same address used for all)
[in]lenLength of data to move

◆ ssp1_copy()

void ssp1_copy ( uint32_t  count,
const uint8_t *  buf 
)

Copy buffer to FPGAs.

Parameters
[in]countNumber of bytes in buf to copy
[in]bufBuffer containing data to copy

◆ sf_read()

void sf_read ( uint32_t  addr,
uint32_t  len,
uint8_t *  buf 
)

Read from flash.

Parameters
[in]addrWhere to read from
[in]lenHow many bytes to read
[out]bufThe buffer receiving the data

◆ sf_write()

void sf_write ( uint32_t  addr,
uint32_t  len,
const uint8_t *  buf 
)

Write to flash.

Parameters
[in]addrWhere to write to
[in]lenHow many bytes to write
[in]bufThe data to write

◆ sf_crc32()

uint32_t sf_crc32 ( uint32_t  addr,
uint32_t  len 
)

Compute CRC of data on flash.

Parameters
[in]addrWhere the data is
[in]lenThe length of the data
Returns
CRC of the data

◆ fpga_word()

void fpga_word ( uint32_t  addr,
uint32_t  fpga,
uint32_t *  buf,
uint32_t  dir 
)

Read or write an FPGA.

Parameters
[in]addrWhere on the FPGA to access
[in]fpgaWhich FPGA to access
[in,out]bufBuffer; contains word to write to FPGA, or is location to put word read from FPGA
[in]dirReading (FPGA_READ) or writing (FPGA_WRITE)

Variable Documentation

◆ lpc_iap

LPC_IAP const lpc_iap = (LPC_IAP) 0x1fff1ff1
static

LPC17xx In Application Programming entry point.

Note
This is a THUMB address in ROM

◆ uni_vec

uint32_t* const uni_vec = (uint32_t *) 0x10001000
static

32 byte (8 word) uninitialised vector

0 - copy of last RSID register
1 - count of WDT timeouts
2 - up time (seconds)
3 - time of last WDT/SYSRESET (copy of up time)
4 - count of SYSRESETs
5 - NVIC->IABR[0]: active interrupts @ call to error_han()
6 - IPSR: exception that caused call to error_han()
7 - count of calls to error_han()
void error_han(void)
Critical error handler.
Definition bmp_init.c:84

◆ dbg_vec

uint32_t* const dbg_vec = (uint32_t *) 0x10001020
static

64 byte (16 word) uninitialised fault debug vector

0 - stacked r0
1 - stacked r1
2 - stacked r2
3 - stacked r3
4 - stacked r12
5 - stacked lr
6 - stacked pc
7 - stacked psr
8 - Configurable Fault Status Register
9 - Hard Fault Status Register
10 - Debug Fault Status Register
11 - Auxiliary Fault Status Register
12 - bus fault address
13 - memory mgmt fault address
14 - exc_return