galileo: Add support for Gen. 1 pinmux and GPIO
This patch adds support for IO pinmuxing and GPIO on first generation Intel Galileo boards.
This commit is contained in:
parent
b17a936bf7
commit
4181179985
|
@ -5,7 +5,17 @@ LIBGCC_PATH = /usr/lib/gcc/$(shell gcc -dumpmachine)/$(shell gcc -dumpversion)
|
|||
|
||||
CONTIKI_TARGET_DIRS = . core/sys/ drivers/ net/
|
||||
CONTIKI_TARGET_MAIN = ${addprefix $(OBJECTDIR)/,contiki-main.o}
|
||||
CONTIKI_SOURCEFILES += contiki-main.c clock.c rtimer-arch.c gpio-pcal9535a.c pwm-pca9685.c galileo-pinmux.c eth-proc.c eth-conf.c galileo-gpio.c
|
||||
CONTIKI_SOURCEFILES += contiki-main.c clock.c rtimer-arch.c eth-proc.c eth-conf.c galileo-gpio.c
|
||||
|
||||
GALILEO_GEN ?= 2
|
||||
CFLAGS += -DGALILEO_GEN=$(GALILEO_GEN)
|
||||
CONTIKI_SOURCEFILES += galileo-gen$(GALILEO_GEN)-pinmux.c
|
||||
|
||||
ifeq ($(GALILEO_GEN),2)
|
||||
CONTIKI_SOURCEFILES += gpio-pcal9535a.c pwm-pca9685.c
|
||||
else
|
||||
CONTIKI_SOURCEFILES += cy8c9540a.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONTIKI_WITH_IPV6),1)
|
||||
CONTIKI_SOURCEFILES += nbr-table.c packetbuf.c linkaddr.c link-stats.c
|
||||
|
|
|
@ -141,6 +141,9 @@ specify X86_CONF_RESTRICT_DMA=1 as a command-line argument to the make
|
|||
command that is used to build the image. This will configure and lock
|
||||
the IMRs.
|
||||
|
||||
Galileo Gen. 2 is targeted by default. Specify GALILEO_GEN=1 on the build
|
||||
command line to target first generation boards.
|
||||
|
||||
Running
|
||||
-------
|
||||
|
||||
|
@ -193,7 +196,8 @@ $ cp examples/hello-world/hello-world.galileo.efi /mnt/sdcard/efi/boot/bootia32.
|
|||
|
||||
### Connect to the console output
|
||||
|
||||
Connect the serial cable to your computer as shown in [2].
|
||||
Connect the serial cable to your computer as shown in [8] for first generation
|
||||
boards and [2] for second generation boards.
|
||||
|
||||
Choose a terminal emulator such as PuTTY. Make sure you use the SCO keyboard
|
||||
mode (on PuTTY that option is at Terminal -> Keyboard, on the left menu).
|
||||
|
@ -277,3 +281,5 @@ References
|
|||
[6] https://docs.docker.com/docker-for-windows/#/shared-drives
|
||||
|
||||
[7] https://docs.docker.com/engine/understanding-docker/
|
||||
|
||||
[8] https://software.intel.com/en-us/articles/intel-galileo-gen-1-board-assembly-using-eclipse-and-intel-xdk-iot-edition
|
||||
|
|
131
platform/galileo/drivers/cy8c9540a.c
Normal file
131
platform/galileo/drivers/cy8c9540a.c
Normal file
|
@ -0,0 +1,131 @@
|
|||
/*
|
||||
* Copyright (C) 2016, Intel Corporation. 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. Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
|
||||
* OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#include "cy8c9540a.h"
|
||||
|
||||
#include <assert.h>
|
||||
#include "i2c.h"
|
||||
#include <stdio.h>
|
||||
|
||||
/* Change this to 0x21 if J2 is set to 1-2
|
||||
* (covering the pin marked with the white triangle). */
|
||||
#define I2C_ADDR 0x20
|
||||
|
||||
#define REG_PORT_SEL 0x18
|
||||
#define REG_PORT_DIR 0x1C
|
||||
|
||||
#define PORT_CNT 6
|
||||
|
||||
/* Cache the current state of each port to obviate the need for reading before
|
||||
* writing to output ports when simply updating a single pin.
|
||||
*/
|
||||
static uint8_t out_cache[PORT_CNT];
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static void
|
||||
write_reg(uint8_t reg, uint8_t data)
|
||||
{
|
||||
uint8_t pkt[] = { reg, data };
|
||||
assert(quarkX1000_i2c_polling_write(pkt, sizeof(pkt), I2C_ADDR) == 0);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static uint8_t
|
||||
read_reg(uint8_t reg)
|
||||
{
|
||||
uint8_t data;
|
||||
assert(quarkX1000_i2c_polling_write(®, 1, I2C_ADDR) == 0);
|
||||
assert(quarkX1000_i2c_polling_read(&data, 1, I2C_ADDR) == 0);
|
||||
return data;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
cy8c9540a_init(void)
|
||||
{
|
||||
uint8_t status;
|
||||
|
||||
/* has to init after I2C master */
|
||||
assert(quarkX1000_i2c_is_available());
|
||||
|
||||
status = read_reg(0x2E);
|
||||
if((status >> 4) != 4) {
|
||||
fprintf(stderr, "Failed to communicate with CY8C9540A. Perhaps jumper J2 "
|
||||
"is not set to 2-3? Halting.\n");
|
||||
halt();
|
||||
}
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
* \brief Set the direction (in or out) for the indicated GPIO pin.
|
||||
*/
|
||||
void
|
||||
cy8c9540a_set_port_dir(cy8c9540a_bit_addr_t addr, cy8c9540a_port_dir_t dir)
|
||||
{
|
||||
uint8_t mask;
|
||||
|
||||
assert(addr.port < PORT_CNT);
|
||||
|
||||
write_reg(REG_PORT_SEL, addr.port);
|
||||
mask = read_reg(REG_PORT_DIR);
|
||||
mask &= ~(1 << addr.pin);
|
||||
mask |= ((uint8_t)dir) << addr.pin;
|
||||
write_reg(REG_PORT_DIR, mask);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
* \brief Set the drive mode for the indicated GPIO pin.
|
||||
*/
|
||||
void
|
||||
cy8c9540a_set_drive_mode(cy8c9540a_bit_addr_t addr,
|
||||
cy8c9540a_drive_mode_t drv_mode)
|
||||
{
|
||||
assert(addr.port < PORT_CNT);
|
||||
|
||||
write_reg(REG_PORT_SEL, addr.port);
|
||||
write_reg((uint8_t)drv_mode, 1 << addr.pin);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
bool
|
||||
cy8c9540a_read(cy8c9540a_bit_addr_t addr)
|
||||
{
|
||||
assert(addr.port < PORT_CNT);
|
||||
|
||||
return ((read_reg(addr.port) >> addr.pin) & 1) == 1;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
cy8c9540a_write(cy8c9540a_bit_addr_t addr, bool val)
|
||||
{
|
||||
assert(addr.port < PORT_CNT);
|
||||
|
||||
out_cache[addr.port] &= ~(1 << addr.pin);
|
||||
out_cache[addr.port] |= ((uint8_t)val) << addr.pin;
|
||||
write_reg(8 + addr.port, out_cache[addr.port]);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
72
platform/galileo/drivers/cy8c9540a.h
Normal file
72
platform/galileo/drivers/cy8c9540a.h
Normal file
|
@ -0,0 +1,72 @@
|
|||
/*
|
||||
* Copyright (C) 2016, Intel Corporation. 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. Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
|
||||
* OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifndef PLATFORM_GALILEO_DRIVERS_CY8C9540A_H_
|
||||
#define PLATFORM_GALILEO_DRIVERS_CY8C9540A_H_
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
/* Driver for Cypress Semiconductors CY8C9540A device used for GPIO, PWM, and
|
||||
* pinmuxing on the first generation Intel Galileo.
|
||||
*/
|
||||
|
||||
/* The numeric value of each drive mode corresponds to the device register
|
||||
* address for selecting that mode. Only a subset of the available modes are
|
||||
* listed here.
|
||||
*/
|
||||
typedef enum cy8c9540a_drive_mode {
|
||||
CY8C9540A_DRIVE_PULL_UP = 0x1D,
|
||||
CY8C9540A_DRIVE_PULL_DOWN = 0x1E,
|
||||
CY8C9540A_DRIVE_STRONG = 0x21,
|
||||
CY8C9540A_DRIVE_HI_Z = 0x23
|
||||
} cy8c9540a_drive_mode_t;
|
||||
|
||||
typedef enum cy8c9540a_port_dir {
|
||||
CY8C9540A_PORT_DIR_OUT = 0,
|
||||
CY8C9540A_PORT_DIR_IN = 1
|
||||
} cy8c9540a_port_dir_t;
|
||||
|
||||
typedef struct cy8c9540a_bit_addr {
|
||||
uint8_t port;
|
||||
int pin;
|
||||
} cy8c9540a_bit_addr_t;
|
||||
|
||||
#define CY8C9540A_BIT_ADDR_INVALID_PORT 0xFF
|
||||
|
||||
void cy8c9540a_init(void);
|
||||
void cy8c9540a_set_port_dir(cy8c9540a_bit_addr_t addr,
|
||||
cy8c9540a_port_dir_t dir);
|
||||
void cy8c9540a_set_drive_mode(cy8c9540a_bit_addr_t addr,
|
||||
cy8c9540a_drive_mode_t drv_mode);
|
||||
bool cy8c9540a_read(cy8c9540a_bit_addr_t addr);
|
||||
void cy8c9540a_write(cy8c9540a_bit_addr_t addr, bool val);
|
||||
|
||||
#endif /* PLATFORM_GALILEO_DRIVERS_CY8C9540A_H_ */
|
282
platform/galileo/drivers/galileo-gen1-pinmux.c
Normal file
282
platform/galileo/drivers/galileo-gen1-pinmux.c
Normal file
|
@ -0,0 +1,282 @@
|
|||
/*
|
||||
* Copyright (C) 2016, Intel Corporation. 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. Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
|
||||
* OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#include "galileo-pinmux.h"
|
||||
|
||||
#include <assert.h>
|
||||
#include "cy8c9540a.h"
|
||||
#include "gpio.h"
|
||||
#include <stdio.h>
|
||||
|
||||
static cy8c9540a_bit_addr_t mux_bit_addrs[] = {
|
||||
{ 3, 4 }, /* IO0 */
|
||||
{ 3, 5 }, /* IO1 */
|
||||
{ 1, 7 }, /* IO2 */
|
||||
{ 1, 6 }, /* IO3 */
|
||||
{ CY8C9540A_BIT_ADDR_INVALID_PORT, 0 }, /* IO4 */
|
||||
{ CY8C9540A_BIT_ADDR_INVALID_PORT, 0 }, /* IO5 */
|
||||
{ CY8C9540A_BIT_ADDR_INVALID_PORT, 0 }, /* IO6 */
|
||||
{ CY8C9540A_BIT_ADDR_INVALID_PORT, 0 }, /* IO7 */
|
||||
{ CY8C9540A_BIT_ADDR_INVALID_PORT, 0 }, /* IO8 */
|
||||
{ CY8C9540A_BIT_ADDR_INVALID_PORT, 0 }, /* IO9 */
|
||||
{ 3, 6 }, /* IO10 */
|
||||
{ 3, 7 }, /* IO11 */
|
||||
{ 5, 2 }, /* IO12 */
|
||||
{ 5, 3 }, /* IO13 */
|
||||
{ 3, 1 }, /* A0 */
|
||||
{ 3, 0 }, /* A1 */
|
||||
{ 0, 7 }, /* A2 */
|
||||
{ 0, 6 }, /* A3 */
|
||||
{ 0, 5 }, /* A4 (also controlled by I2C mux) */
|
||||
{ 0, 4 }, /* A5 (also controlled by I2C mux) */
|
||||
};
|
||||
|
||||
static cy8c9540a_bit_addr_t i2c_mux_bit_addr = { 1, 5 };
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static void
|
||||
flatten_pin_num(galileo_pin_group_t grp, unsigned *pin)
|
||||
{
|
||||
if(grp == GALILEO_PIN_GRP_ANALOG) {
|
||||
*pin += GALILEO_NUM_DIGITAL_PINS;
|
||||
}
|
||||
|
||||
assert(*pin < GALILEO_NUM_PINS);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* See galileo-gpio.c for the declaration of this function. */
|
||||
int
|
||||
galileo_brd_to_cpu_gpio_pin(unsigned pin, bool *sus)
|
||||
{
|
||||
assert(pin < GALILEO_NUM_PINS);
|
||||
*sus = false;
|
||||
switch(pin) {
|
||||
case 2:
|
||||
return 6;
|
||||
case 3:
|
||||
return 7;
|
||||
case 10:
|
||||
return 2;
|
||||
default:
|
||||
return -1; /* GPIO pin may be connected to the CY8C9540A chip, but not the
|
||||
CPU. */
|
||||
}
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static cy8c9540a_bit_addr_t cy8c9540a_gpio_mapping[] = {
|
||||
{ 4, 6 },
|
||||
{ 4, 7 },
|
||||
{ CY8C9540A_BIT_ADDR_INVALID_PORT, 0 },
|
||||
{ CY8C9540A_BIT_ADDR_INVALID_PORT, 0 },
|
||||
{ 1, 4 },
|
||||
{ 0, 1 },
|
||||
{ 1, 0 },
|
||||
{ 1, 3 },
|
||||
{ 1, 2 },
|
||||
{ 0, 3 },
|
||||
{ 0, 0 }, /* This driver configures IO10 to connect to CPU GPIO when setting
|
||||
IO10 to a digital mode, but hardware exists to alternately
|
||||
connect it to this pin of the CY8C9540A chip. */
|
||||
{ 1, 1 },
|
||||
{ 3, 2 },
|
||||
{ 3, 3 },
|
||||
{ 4, 0 },
|
||||
{ 4, 1 },
|
||||
{ 4, 2 },
|
||||
{ 4, 3 },
|
||||
{ 4, 4 },
|
||||
{ 4, 5 }
|
||||
};
|
||||
/* Map a board-level GPIO pin number to the address of the CY8C9540A pin that
|
||||
* implements it.
|
||||
*/
|
||||
cy8c9540a_bit_addr_t
|
||||
galileo_brd_to_cy8c9540a_gpio_pin(unsigned pin)
|
||||
{
|
||||
assert(pin < GALILEO_NUM_PINS);
|
||||
return cy8c9540a_gpio_mapping[pin];
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* The I2C mux control must be set high to be able to access A4 and A5.
|
||||
*/
|
||||
static void
|
||||
set_i2c_mux(bool val)
|
||||
{
|
||||
cy8c9540a_write(i2c_mux_bit_addr, val);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static void
|
||||
select_gpio_pwm(unsigned flat_pin, bool pwm)
|
||||
{
|
||||
bool mux_val;
|
||||
cy8c9540a_bit_addr_t mux_bit_addr;
|
||||
mux_bit_addr = mux_bit_addrs[flat_pin];
|
||||
if(mux_bit_addr.port != CY8C9540A_BIT_ADDR_INVALID_PORT) {
|
||||
mux_val = pwm || !(flat_pin == 2 || flat_pin == 3 || flat_pin == 10);
|
||||
cy8c9540a_write(mux_bit_addr, mux_val);
|
||||
}
|
||||
if((GALILEO_NUM_DIGITAL_PINS + 4) <= flat_pin) {
|
||||
/* This single control switches away from both I2C pins. */
|
||||
set_i2c_mux(true);
|
||||
}
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static void
|
||||
select_gpio(galileo_pin_group_t grp, unsigned pin, bool out)
|
||||
{
|
||||
bool sus;
|
||||
int cpu_pin;
|
||||
cy8c9540a_bit_addr_t gpio_bit_addr;
|
||||
|
||||
flatten_pin_num(grp, &pin);
|
||||
select_gpio_pwm(pin, false);
|
||||
|
||||
cpu_pin = galileo_brd_to_cpu_gpio_pin(pin, &sus);
|
||||
if(cpu_pin == -1) {
|
||||
gpio_bit_addr = galileo_brd_to_cy8c9540a_gpio_pin(pin);
|
||||
cy8c9540a_set_port_dir(gpio_bit_addr,
|
||||
out?
|
||||
CY8C9540A_PORT_DIR_OUT :
|
||||
CY8C9540A_PORT_DIR_IN);
|
||||
cy8c9540a_set_drive_mode(gpio_bit_addr,
|
||||
out?
|
||||
CY8C9540A_DRIVE_STRONG :
|
||||
CY8C9540A_DRIVE_HI_Z);
|
||||
} else {
|
||||
quarkX1000_gpio_config(cpu_pin,
|
||||
out? QUARKX1000_GPIO_OUT : QUARKX1000_GPIO_IN);
|
||||
}
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
galileo_pinmux_select_din(galileo_pin_group_t grp, unsigned pin)
|
||||
{
|
||||
select_gpio(grp, pin, false);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void galileo_pinmux_select_dout(galileo_pin_group_t grp, unsigned pin)
|
||||
{
|
||||
select_gpio(grp, pin, true);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void galileo_pinmux_select_pwm(unsigned pin)
|
||||
{
|
||||
switch(pin) {
|
||||
case 3:
|
||||
case 5:
|
||||
case 6:
|
||||
case 9:
|
||||
case 10:
|
||||
case 11:
|
||||
break;
|
||||
default:
|
||||
fprintf(stderr, "%s: invalid pin: %d.\n", __FUNCTION__, pin);
|
||||
halt();
|
||||
}
|
||||
|
||||
select_gpio_pwm(pin, true);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void galileo_pinmux_select_serial(unsigned pin)
|
||||
{
|
||||
assert(pin == 0 || pin == 1);
|
||||
|
||||
cy8c9540a_write(mux_bit_addrs[pin], false);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void galileo_pinmux_select_i2c(void)
|
||||
{
|
||||
set_i2c_mux(false);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void galileo_pinmux_select_spi(void)
|
||||
{
|
||||
unsigned pin;
|
||||
for(pin = 11; pin <= 13; pin++) {
|
||||
cy8c9540a_write(mux_bit_addrs[pin], false);
|
||||
}
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void galileo_pinmux_select_analog(unsigned pin)
|
||||
{
|
||||
assert(pin < GALILEO_NUM_ANALOG_PINS);
|
||||
pin += GALILEO_NUM_DIGITAL_PINS;
|
||||
|
||||
cy8c9540a_write(mux_bit_addrs[pin], false);
|
||||
|
||||
if(4 <= pin) {
|
||||
/* This single control switches away from both I2C pins. */
|
||||
set_i2c_mux(true);
|
||||
}
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
int
|
||||
galileo_pinmux_initialize(void)
|
||||
{
|
||||
int i;
|
||||
|
||||
cy8c9540a_init();
|
||||
|
||||
/* Configure all mux control pins as outputs. */
|
||||
for(i = 0; i < GALILEO_NUM_PINS; i++) {
|
||||
if(mux_bit_addrs[i].port == CY8C9540A_BIT_ADDR_INVALID_PORT) {
|
||||
continue;
|
||||
}
|
||||
|
||||
cy8c9540a_set_port_dir(mux_bit_addrs[i], CY8C9540A_PORT_DIR_OUT);
|
||||
cy8c9540a_set_drive_mode(mux_bit_addrs[i], CY8C9540A_DRIVE_STRONG);
|
||||
}
|
||||
cy8c9540a_set_port_dir(i2c_mux_bit_addr, CY8C9540A_PORT_DIR_OUT);
|
||||
cy8c9540a_set_drive_mode(i2c_mux_bit_addr, CY8C9540A_DRIVE_STRONG);
|
||||
|
||||
/* Activate default pinmux configuration. */
|
||||
galileo_pinmux_select_serial(0);
|
||||
galileo_pinmux_select_serial(1);
|
||||
galileo_pinmux_select_dout(GALILEO_PIN_GRP_DIGITAL, 2);
|
||||
galileo_pinmux_select_din(GALILEO_PIN_GRP_DIGITAL, 3);
|
||||
galileo_pinmux_select_din(GALILEO_PIN_GRP_DIGITAL, 4);
|
||||
galileo_pinmux_select_din(GALILEO_PIN_GRP_DIGITAL, 5);
|
||||
galileo_pinmux_select_din(GALILEO_PIN_GRP_DIGITAL, 6);
|
||||
galileo_pinmux_select_din(GALILEO_PIN_GRP_DIGITAL, 7);
|
||||
galileo_pinmux_select_din(GALILEO_PIN_GRP_DIGITAL, 8);
|
||||
galileo_pinmux_select_din(GALILEO_PIN_GRP_DIGITAL, 9);
|
||||
galileo_pinmux_select_dout(GALILEO_PIN_GRP_DIGITAL, 10);
|
||||
galileo_pinmux_select_din(GALILEO_PIN_GRP_DIGITAL, 11);
|
||||
galileo_pinmux_select_dout(GALILEO_PIN_GRP_DIGITAL, 12);
|
||||
galileo_pinmux_select_din(GALILEO_PIN_GRP_DIGITAL, 13);
|
||||
galileo_pinmux_select_analog(0);
|
||||
galileo_pinmux_select_analog(1);
|
||||
galileo_pinmux_select_analog(2);
|
||||
galileo_pinmux_select_analog(3);
|
||||
galileo_pinmux_select_i2c();
|
||||
|
||||
return 0;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
|
@ -31,14 +31,22 @@
|
|||
#include "galileo-gpio.h"
|
||||
#include <assert.h>
|
||||
#include "gpio.h"
|
||||
#if GALILEO_GEN == 1
|
||||
#include "cy8c9540a.h"
|
||||
#endif
|
||||
|
||||
/* Must be implemented in board-specific pinmux file to map a board-level GPIO
|
||||
* pin number to the corresponding CPU GPIO pin number.
|
||||
*
|
||||
* The return value should always be a positive number. An assertion within the
|
||||
* For gen. 1 boards, the value -1 may be returned to indicate that the
|
||||
* specified GPIO pin is not connected to any CPU pin. For gen. 2 boards, the
|
||||
* return value should always be a positive number. An assertion within the
|
||||
* function should check the validity of the pin number.
|
||||
*/
|
||||
int galileo_brd_to_cpu_gpio_pin(unsigned pin, bool *sus);
|
||||
#if GALILEO_GEN == 1
|
||||
cy8c9540a_bit_addr_t galileo_brd_to_cy8c9540a_gpio_pin(unsigned pin);
|
||||
#endif
|
||||
|
||||
static int
|
||||
brd_to_cpu_pin(unsigned pin)
|
||||
|
@ -63,10 +71,32 @@ void galileo_gpio_config(uint8_t pin, int flags)
|
|||
*/
|
||||
void galileo_gpio_read(uint8_t pin, uint8_t *value)
|
||||
{
|
||||
assert(quarkX1000_gpio_read(brd_to_cpu_pin(pin), value) == 0);
|
||||
#if GALILEO_GEN == 1
|
||||
cy8c9540a_bit_addr_t bit_addr;
|
||||
#endif
|
||||
int cpu_pin = brd_to_cpu_pin(pin);
|
||||
#if GALILEO_GEN == 1
|
||||
if(cpu_pin == -1) {
|
||||
bit_addr = galileo_brd_to_cy8c9540a_gpio_pin(pin);
|
||||
*value = cy8c9540a_read(bit_addr);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
assert(quarkX1000_gpio_read(cpu_pin, value) == 0);
|
||||
}
|
||||
|
||||
void galileo_gpio_write(uint8_t pin, uint8_t value)
|
||||
{
|
||||
assert(quarkX1000_gpio_write(brd_to_cpu_pin(pin), value) == 0);
|
||||
#if GALILEO_GEN == 1
|
||||
cy8c9540a_bit_addr_t bit_addr;
|
||||
#endif
|
||||
int cpu_pin = brd_to_cpu_pin(pin);
|
||||
#if GALILEO_GEN == 1
|
||||
if(cpu_pin == -1) {
|
||||
bit_addr = galileo_brd_to_cy8c9540a_gpio_pin(pin);
|
||||
cy8c9540a_write(bit_addr, value);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
assert(quarkX1000_gpio_write(cpu_pin, value) == 0);
|
||||
}
|
||||
|
|
Loading…
Reference in a new issue