summaryrefslogtreecommitdiff
path: root/board/zinger
diff options
context:
space:
mode:
Diffstat (limited to 'board/zinger')
-rw-r--r--board/zinger/board.c13
-rw-r--r--board/zinger/board.h11
-rw-r--r--board/zinger/build.mk2
-rw-r--r--board/zinger/ec.irqlist2
-rw-r--r--board/zinger/ec.tasklist2
-rw-r--r--board/zinger/gpio.inc2
-rw-r--r--board/zinger/hardware.c56
-rw-r--r--board/zinger/runtime.c28
-rw-r--r--board/zinger/usb_pd_config.h14
-rw-r--r--board/zinger/usb_pd_pdo.c4
-rw-r--r--board/zinger/usb_pd_pdo.h2
-rw-r--r--board/zinger/usb_pd_policy.c107
12 files changed, 118 insertions, 125 deletions
diff --git a/board/zinger/board.c b/board/zinger/board.c
index f1249d6917..41d91ab438 100644
--- a/board/zinger/board.c
+++ b/board/zinger/board.c
@@ -1,4 +1,4 @@
-/* Copyright 2014 The Chromium OS Authors. All rights reserved.
+/* Copyright 2014 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
@@ -21,8 +21,8 @@
static uint32_t rsa_workbuf[3 * RSANUMWORDS];
/* RW firmware reset vector */
-static uint32_t * const rw_rst =
- (uint32_t *)(CONFIG_PROGRAM_MEMORY_BASE+CONFIG_RW_MEM_OFF+4);
+static uint32_t *const rw_rst =
+ (uint32_t *)(CONFIG_PROGRAM_MEMORY_BASE + CONFIG_RW_MEM_OFF + 4);
/* External interrupt EXTINT7 for external comparator on PA7 */
static void pd_rx_interrupt(void)
@@ -57,8 +57,8 @@ static int check_rw_valid(void *rw_hash)
return 0;
good = rsa_verify((const struct rsa_public_key *)CONFIG_RO_PUBKEY_ADDR,
- (const uint8_t *)CONFIG_RW_SIG_ADDR,
- rw_hash, rsa_workbuf);
+ (const uint8_t *)CONFIG_RW_SIG_ADDR, rw_hash,
+ rsa_workbuf);
if (!good) {
debug_printf("RSA FAILED\n");
pd_log_event(PD_EVENT_ACC_RW_FAIL, 0, 0, NULL);
@@ -75,8 +75,7 @@ int main(void)
void *rw_hash;
hardware_init();
- debug_printf("%s started\n",
- is_ro_mode() ? "RO" : "RW");
+ debug_printf("%s started\n", is_ro_mode() ? "RO" : "RW");
/* the RO partition protection is not enabled : do it */
if (!flash_physical_is_permanently_protected())
diff --git a/board/zinger/board.h b/board/zinger/board.h
index 0be755eb5c..1ca83354bc 100644
--- a/board/zinger/board.h
+++ b/board/zinger/board.h
@@ -1,4 +1,4 @@
-/* Copyright 2014 The Chromium OS Authors. All rights reserved.
+/* Copyright 2014 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
@@ -41,7 +41,7 @@
#undef CONFIG_FLASH_PHYSICAL
#undef CONFIG_FMAP
/* Not using pstate but keep some space for the public key */
-#undef CONFIG_FW_PSTATE_SIZE
+#undef CONFIG_FW_PSTATE_SIZE
#define CONFIG_FW_PSTATE_SIZE 544
#define CONFIG_HIBERNATE
#define CONFIG_HIBERNATE_WAKEUP_PINS STM32_PWR_CSR_EWUP1
@@ -59,7 +59,7 @@
#undef CONFIG_USB_PD_DUAL_ROLE
#undef CONFIG_USB_PD_INTERNAL_COMP
#define CONFIG_USB_PD_LOGGING
-#undef CONFIG_EVENT_LOG_SIZE
+#undef CONFIG_EVENT_LOG_SIZE
#define CONFIG_EVENT_LOG_SIZE 256
#define CONFIG_USB_PD_LOW_POWER_IDLE_WHEN_CONNECTED
#define CONFIG_USB_PD_PORT_MAX_COUNT 1
@@ -105,10 +105,11 @@ enum adc_channel {
#define ADC_CH_CC2_PD ADC_CH_CC1_PD
/* 3.0A Rp */
-#define PD_SRC_VNC (PD_SRC_3_0_VNC_MV * 4096 / 3300/* 12-bit ADC, 3.3V range */)
+#define PD_SRC_VNC \
+ (PD_SRC_3_0_VNC_MV * 4096 / 3300 /* 12-bit ADC, 3.3V range */)
/* delay necessary for the voltage transition on the power supply */
-#define PD_POWER_SUPPLY_TURN_ON_DELAY 50000 /* us */
+#define PD_POWER_SUPPLY_TURN_ON_DELAY 50000 /* us */
#define PD_POWER_SUPPLY_TURN_OFF_DELAY 50000 /* us */
/* Initialize all useful registers */
diff --git a/board/zinger/build.mk b/board/zinger/build.mk
index c85eb9df4b..da1878efe9 100644
--- a/board/zinger/build.mk
+++ b/board/zinger/build.mk
@@ -1,5 +1,5 @@
# -*- makefile -*-
-# Copyright 2014 The Chromium OS Authors. All rights reserved.
+# Copyright 2014 The ChromiumOS Authors
# Use of this source code is governed by a BSD-style license that can be
# found in the LICENSE file.
#
diff --git a/board/zinger/ec.irqlist b/board/zinger/ec.irqlist
index 690fa950fc..186c0f6338 100644
--- a/board/zinger/ec.irqlist
+++ b/board/zinger/ec.irqlist
@@ -1,4 +1,4 @@
-/* Copyright 2014 The Chromium OS Authors. All rights reserved.
+/* Copyright 2014 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
diff --git a/board/zinger/ec.tasklist b/board/zinger/ec.tasklist
index 091eb90a22..89d9ffab76 100644
--- a/board/zinger/ec.tasklist
+++ b/board/zinger/ec.tasklist
@@ -1,4 +1,4 @@
-/* Copyright 2014 The Chromium OS Authors. All rights reserved.
+/* Copyright 2014 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
diff --git a/board/zinger/gpio.inc b/board/zinger/gpio.inc
index 6b96e08645..65e3066695 100644
--- a/board/zinger/gpio.inc
+++ b/board/zinger/gpio.inc
@@ -1,6 +1,6 @@
/* -*- mode:c -*-
*
- * Copyright 2022 The Chromium OS Authors. All rights reserved.
+ * Copyright 2022 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
diff --git a/board/zinger/hardware.c b/board/zinger/hardware.c
index 7e6e1f8f4c..0ad5b7ff94 100644
--- a/board/zinger/hardware.c
+++ b/board/zinger/hardware.c
@@ -1,4 +1,4 @@
-/* Copyright 2014 The Chromium OS Authors. All rights reserved.
+/* Copyright 2014 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
@@ -39,16 +39,16 @@ static void power_init(void)
/* enable TIM2, TIM3, TIM14, PWR */
STM32_RCC_APB1ENR = 0x10000103;
/* enable DMA, SRAM, CRC, GPA, GPB, GPF */
- STM32_RCC_AHBENR = 0x460045;
+ STM32_RCC_AHBENR = 0x460045;
}
/* GPIO setting helpers */
-#define OUT(n) (1 << ((n) * 2))
-#define AF(n) (2 << ((n) * 2))
-#define ANALOG(n) (3 << ((n) * 2))
+#define OUT(n) (1 << ((n)*2))
+#define AF(n) (2 << ((n)*2))
+#define ANALOG(n) (3 << ((n)*2))
#define HIGH(n) (1 << (n))
#define ODR(n) (1 << (n))
-#define HISPEED(n) (3 << ((n) * 2))
+#define HISPEED(n) (3 << ((n)*2))
#define AFx(n, x) (x << (((n) % 8) * 4))
static void pins_init(void)
@@ -83,9 +83,9 @@ static void pins_init(void)
STM32_GPIO_AFRH(GPIO_A) = AFx(9, 1) | AFx(10, 1);
STM32_GPIO_OTYPER(GPIO_A) = ODR(4);
STM32_GPIO_OSPEEDR(GPIO_A) = HISPEED(5) | HISPEED(6) | HISPEED(7);
- STM32_GPIO_MODER(GPIO_A) = OUT(0) | ANALOG(1) | ANALOG(2) | ANALOG(3)
- | OUT(4) | AF(5) /*| AF(6)*/ | AF(7) | AF(9)
- | AF(10) | OUT(13) | OUT(14);
+ STM32_GPIO_MODER(GPIO_A) = OUT(0) | ANALOG(1) | ANALOG(2) | ANALOG(3) |
+ OUT(4) | AF(5) /*| AF(6)*/ | AF(7) | AF(9) |
+ AF(10) | OUT(13) | OUT(14);
/* set PF0 / PF1 as output */
STM32_GPIO_ODR(GPIO_F) = 0;
STM32_GPIO_MODER(GPIO_F) = OUT(0) | OUT(1);
@@ -107,7 +107,8 @@ static void adc_init(void)
;
}
/* Single conversion, right aligned, 12-bit */
- STM32_ADC_CFGR1 = BIT(12); /* BIT(15) => AUTOOFF */;
+ STM32_ADC_CFGR1 = BIT(12); /* BIT(15) => AUTOOFF */
+ ;
/* clock is ADCCLK (ADEN must be off when writing this reg) */
STM32_ADC_CFGR2 = 0;
/* Sampling time : 71.5 ADC clock cycles, about 5us */
@@ -132,8 +133,8 @@ static void uart_init(void)
STM32_USART_BRR(UARTN_BASE) =
DIV_ROUND_NEAREST(CPU_CLOCK, CONFIG_UART_BAUD_RATE);
/* UART enabled, 8 Data bits, oversampling x16, no parity */
- STM32_USART_CR1(UARTN_BASE) =
- STM32_USART_CR1_UE | STM32_USART_CR1_TE | STM32_USART_CR1_RE;
+ STM32_USART_CR1(UARTN_BASE) = STM32_USART_CR1_UE | STM32_USART_CR1_TE |
+ STM32_USART_CR1_RE;
/* 1 stop bit, no fancy stuff */
STM32_USART_CR2(UARTN_BASE) = 0x0000;
/* DMA disabled, special modes disabled, error interrupt disabled */
@@ -200,7 +201,7 @@ static int watchdog_ain_id, watchdog_ain_high, watchdog_ain_low;
static int adc_enable_last_watchdog(void)
{
return adc_enable_watchdog(watchdog_ain_id, watchdog_ain_high,
- watchdog_ain_low);
+ watchdog_ain_low);
}
static inline int adc_watchdog_enabled(void)
@@ -248,8 +249,7 @@ int adc_enable_watchdog(int ch, int high, int low)
/* Clear flags */
STM32_ADC_ISR = 0x8e;
/* Set Watchdog enable bit on a single channel / continuous mode */
- STM32_ADC_CFGR1 = (ch << 26) | BIT(23) | BIT(22)
- | BIT(13) | BIT(12);
+ STM32_ADC_CFGR1 = (ch << 26) | BIT(23) | BIT(22) | BIT(13) | BIT(12);
/* Enable watchdog interrupt */
STM32_ADC_IER = BIT(7);
/* Start continuous conversion */
@@ -289,17 +289,17 @@ int adc_disable_watchdog(void)
(FLASH_TIMEOUT_US * (CPU_CLOCK / SECOND) / CYCLE_PER_FLASH_LOOP)
/* Flash unlocking keys */
-#define KEY1 0x45670123
-#define KEY2 0xCDEF89AB
+#define KEY1 0x45670123
+#define KEY2 0xCDEF89AB
/* Lock bits for FLASH_CR register */
-#define PG BIT(0)
-#define PER BIT(1)
-#define OPTPG BIT(4)
-#define OPTER BIT(5)
-#define STRT BIT(6)
-#define CR_LOCK BIT(7)
-#define OPTWRE BIT(9)
+#define PG BIT(0)
+#define PER BIT(1)
+#define OPTPG BIT(4)
+#define OPTER BIT(5)
+#define STRT BIT(6)
+#define CR_LOCK BIT(7)
+#define OPTWRE BIT(9)
int crec_flash_physical_write(int offset, int size, const char *data)
{
@@ -369,14 +369,13 @@ int crec_flash_physical_erase(int offset, int size)
STM32_FLASH_CR |= PER;
for (; size > 0; size -= CONFIG_FLASH_ERASE_SIZE,
- offset += CONFIG_FLASH_ERASE_SIZE) {
+ offset += CONFIG_FLASH_ERASE_SIZE) {
int i;
/* select page to erase */
STM32_FLASH_AR = CONFIG_PROGRAM_MEMORY_BASE + offset;
/* set STRT bit : start erase */
STM32_FLASH_CR |= STRT;
-
/* Wait for erase to complete */
for (i = 0; (STM32_FLASH_SR & 1) && (i < FLASH_TIMEOUT_LOOP);
i++)
@@ -434,7 +433,6 @@ static void unlock_erase_optb(void)
STM32_FLASH_CR = OPTWRE;
}
-
static void write_optb(int byte, uint8_t value)
{
volatile int16_t *hword = (uint16_t *)(STM32_OPTB_BASE + byte);
@@ -475,6 +473,6 @@ int flash_physical_is_permanently_protected(void)
{
/* if RDP is still at level 0, the flash protection is not in place */
return (STM32_FLASH_OBR & STM32_FLASH_OBR_RDP_MASK) &&
- /* the low 16KB (RO partition) are write-protected */
- !(STM32_FLASH_WRPR & 0xF);
+ /* the low 16KB (RO partition) are write-protected */
+ !(STM32_FLASH_WRPR & 0xF);
}
diff --git a/board/zinger/runtime.c b/board/zinger/runtime.c
index 900c7b8c2f..19c33c7f0f 100644
--- a/board/zinger/runtime.c
+++ b/board/zinger/runtime.c
@@ -1,4 +1,4 @@
-/* Copyright 2014 The Chromium OS Authors. All rights reserved.
+/* Copyright 2014 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
@@ -106,7 +106,7 @@ static void zinger_config_hispeed_clock(void)
STM32_RCC_CR |= BIT(24);
/* Wait for PLL to be ready */
while (!(STM32_RCC_CR & BIT(25)))
- ;
+ ;
/* switch SYSCLK to PLL */
STM32_RCC_CFGR = 0x00288002;
@@ -135,7 +135,7 @@ void runtime_init(void)
* SET_RTC_MATCH_DELAY: max time to set RTC match alarm. if we set the alarm
* in the past, it will never wake up and cause a watchdog.
*/
-#define STOP_MODE_LATENCY 300 /* us */
+#define STOP_MODE_LATENCY 300 /* us */
#define SET_RTC_MATCH_DELAY 200 /* us */
#define MAX_LATENCY (STOP_MODE_LATENCY + SET_RTC_MATCH_DELAY)
@@ -161,10 +161,10 @@ uint32_t task_wait_event(int timeout_us)
while (1) {
/* set timeout on timer */
if (timeout_us < 0) {
- asm volatile ("wfi");
+ asm volatile("wfi");
} else if (timeout_us <= MAX_LATENCY ||
- t1.le.lo - timeout_us > t1.le.lo + MAX_LATENCY ||
- !DEEP_SLEEP_ALLOWED) {
+ t1.le.lo - timeout_us > t1.le.lo + MAX_LATENCY ||
+ !DEEP_SLEEP_ALLOWED) {
STM32_TIM32_CCR1(2) = STM32_TIM32_CNT(2) + timeout_us;
STM32_TIM_DIER(2) = 3; /* match interrupt and UIE */
@@ -177,8 +177,8 @@ uint32_t task_wait_event(int timeout_us)
/* set deep sleep bit */
CPU_SCB_SYSCTRL |= 0x4;
- set_rtc_alarm(0, timeout_us - STOP_MODE_LATENCY,
- &rtc0, 0);
+ set_rtc_alarm(0, timeout_us - STOP_MODE_LATENCY, &rtc0,
+ 0);
asm volatile("wfi");
@@ -233,8 +233,7 @@ uint32_t task_wait_event_mask(uint32_t event_mask, int timeout_us)
return evt & event_mask;
}
-noreturn
-void __keep cpu_reset(void)
+noreturn void __keep cpu_reset(void)
{
/* Disable interrupts */
interrupt_disable();
@@ -267,7 +266,8 @@ void exception_panic(void)
"bl debug_printf\n"
#endif
"bl cpu_reset\n"
- : : "r"("PANIC PC=%08x LR=%08x\n\n"));
+ :
+ : "r"("PANIC PC=%08x LR=%08x\n\n"));
}
void panic_reboot(void)
@@ -286,7 +286,9 @@ enum ec_image system_get_image_copy(void)
/* --- stubs --- */
void __hw_timer_enable_clock(int n, int enable)
-{ /* Done in hardware init */ }
+{ /* Done in hardware init */
+}
void usleep(unsigned us)
-{ /* Used only as a workaround */ }
+{ /* Used only as a workaround */
+}
diff --git a/board/zinger/usb_pd_config.h b/board/zinger/usb_pd_config.h
index d0797b3d80..c3d86e2c2b 100644
--- a/board/zinger/usb_pd_config.h
+++ b/board/zinger/usb_pd_config.h
@@ -1,4 +1,4 @@
-/* Copyright 2014 The Chromium OS Authors. All rights reserved.
+/* Copyright 2014 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
@@ -10,7 +10,7 @@
/* Timer selection for baseband PD communication */
#define TIM_CLOCK_PD_TX_C0 14
-#define TIM_CLOCK_PD_RX_C0 3
+#define TIM_CLOCK_PD_RX_C0 3
#define TIM_CLOCK_PD_TX(p) TIM_CLOCK_PD_TX_C0
#define TIM_CLOCK_PD_RX(p) TIM_CLOCK_PD_RX_C0
@@ -46,7 +46,7 @@ static inline void spi_enable_clock(int port)
#define TIM_TX_CCR_IDX(p) TIM_TX_CCR_C0
#define TIM_RX_CCR_IDX(p) TIM_RX_CCR_C0
/* connect TIM3 CH1 to TIM3_CH2 input */
-#define TIM_CCR_CS 2
+#define TIM_CCR_CS 2
#define EXTI_COMP_MASK(p) BIT(7)
#define IRQ_COMP STM32_IRQ_EXTI4_15
/* the RX is inverted, triggers on rising edge */
@@ -72,7 +72,7 @@ static inline void pd_tx_spi_reset(int port)
static inline void pd_tx_enable(int port, int polarity)
{
/* Drive SPI MISO on PA6 by putting it in AF mode */
- STM32_GPIO_MODER(GPIO_A) |= 0x2 << (2*6);
+ STM32_GPIO_MODER(GPIO_A) |= 0x2 << (2 * 6);
/* Drive TX GND on PA4 */
STM32_GPIO_BSRR(GPIO_A) = 1 << (4 + 16 /* Reset */);
}
@@ -83,7 +83,7 @@ static inline void pd_tx_disable(int port, int polarity)
/* Put TX GND (PA4) in Hi-Z state */
STM32_GPIO_BSRR(GPIO_A) = BIT(4) /* Set */;
/* Put SPI MISO (PA6) in Hi-Z by putting it in input mode */
- STM32_GPIO_MODER(GPIO_A) &= ~(0x3 << (2*6));
+ STM32_GPIO_MODER(GPIO_A) &= ~(0x3 << (2 * 6));
}
/* we know the plug polarity, do the right configuration */
@@ -98,7 +98,9 @@ static inline void pd_tx_init(void)
/* Already done in hardware_init() */
}
-static inline void pd_config_init(int port, uint8_t power_role) {}
+static inline void pd_config_init(int port, uint8_t power_role)
+{
+}
static inline int pd_adc_read(int port, int cc)
{
diff --git a/board/zinger/usb_pd_pdo.c b/board/zinger/usb_pd_pdo.c
index 13f8407d6d..36be87bd78 100644
--- a/board/zinger/usb_pd_pdo.c
+++ b/board/zinger/usb_pd_pdo.c
@@ -1,4 +1,4 @@
-/* Copyright 2021 The Chromium OS Authors. All rights reserved.
+/* Copyright 2021 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
@@ -9,7 +9,7 @@
/* Power Delivery Objects */
const uint32_t pd_src_pdo[] = {
- [PDO_IDX_5V] = PDO_FIXED(5000, RATED_CURRENT, PDO_FIXED_FLAGS),
+ [PDO_IDX_5V] = PDO_FIXED(5000, RATED_CURRENT, PDO_FIXED_FLAGS),
[PDO_IDX_12V] = PDO_FIXED(12000, RATED_CURRENT, PDO_FIXED_FLAGS),
[PDO_IDX_20V] = PDO_FIXED(20000, RATED_CURRENT, PDO_FIXED_FLAGS),
};
diff --git a/board/zinger/usb_pd_pdo.h b/board/zinger/usb_pd_pdo.h
index 07b7129202..45f6668077 100644
--- a/board/zinger/usb_pd_pdo.h
+++ b/board/zinger/usb_pd_pdo.h
@@ -1,4 +1,4 @@
-/* Copyright 2021 The Chromium OS Authors. All rights reserved.
+/* Copyright 2021 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
diff --git a/board/zinger/usb_pd_policy.c b/board/zinger/usb_pd_policy.c
index 08314e7aa6..7f60ce8772 100644
--- a/board/zinger/usb_pd_policy.c
+++ b/board/zinger/usb_pd_policy.c
@@ -1,4 +1,4 @@
-/* Copyright 2014 The Chromium OS Authors. All rights reserved.
+/* Copyright 2014 The ChromiumOS Authors
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
@@ -9,6 +9,7 @@
#include "debug_printf.h"
#include "ec_commands.h"
#include "hooks.h"
+#include "printf.h"
#include "registers.h"
#include "system.h"
#include "task.h"
@@ -20,15 +21,15 @@
/* ------------------------- Power supply control ------------------------ */
/* GPIO level setting helpers through BSRR register */
-#define GPIO_SET(n) (1 << (n))
+#define GPIO_SET(n) (1 << (n))
#define GPIO_RESET(n) (1 << ((n) + 16))
/* Output voltage selection */
enum volt {
- VO_5V = GPIO_RESET(13) | GPIO_RESET(14),
- VO_12V = GPIO_SET(13) | GPIO_RESET(14),
+ VO_5V = GPIO_RESET(13) | GPIO_RESET(14),
+ VO_12V = GPIO_SET(13) | GPIO_RESET(14),
VO_13V = GPIO_RESET(13) | GPIO_SET(14),
- VO_20V = GPIO_SET(13) | GPIO_SET(14),
+ VO_20V = GPIO_SET(13) | GPIO_SET(14),
};
static inline void set_output_voltage(enum volt v)
@@ -73,26 +74,27 @@ static timestamp_t fault_deadline;
/* ADC in 12-bit mode */
#define ADC_SCALE BIT(12)
/* ADC power supply : VDDA = 3.3V */
-#define VDDA_MV 3300
+#define VDDA_MV 3300
/* Current sense resistor : 5 milliOhm */
-#define R_SENSE 5
+#define R_SENSE 5
/* VBUS voltage is measured through 10k / 100k voltage divider = /11 */
-#define VOLT_DIV ((10+100)/10)
+#define VOLT_DIV ((10 + 100) / 10)
/* The current sensing op-amp has a x100 gain */
#define CURR_GAIN 100
/* convert VBUS voltage in raw ADC value */
-#define VBUS_MV(mv) ((mv)*ADC_SCALE/VOLT_DIV/VDDA_MV)
+#define VBUS_MV(mv) ((mv)*ADC_SCALE / VOLT_DIV / VDDA_MV)
/* convert VBUS current in raw ADC value */
-#define VBUS_MA(ma) ((ma)*ADC_SCALE*R_SENSE/1000*CURR_GAIN/VDDA_MV)
+#define VBUS_MA(ma) ((ma)*ADC_SCALE * R_SENSE / 1000 * CURR_GAIN / VDDA_MV)
/* convert raw ADC value to mA */
-#define ADC_TO_CURR_MA(vbus) ((vbus)*1000/(ADC_SCALE*R_SENSE)*VDDA_MV/CURR_GAIN)
+#define ADC_TO_CURR_MA(vbus) \
+ ((vbus)*1000 / (ADC_SCALE * R_SENSE) * VDDA_MV / CURR_GAIN)
/* convert raw ADC value to mV */
-#define ADC_TO_VOLT_MV(vbus) ((vbus)*VOLT_DIV*VDDA_MV/ADC_SCALE)
+#define ADC_TO_VOLT_MV(vbus) ((vbus)*VOLT_DIV * VDDA_MV / ADC_SCALE)
/* Max current : 20% over rated current */
-#define MAX_CURRENT VBUS_MA(RATED_CURRENT * 6/5)
+#define MAX_CURRENT VBUS_MA(RATED_CURRENT * 6 / 5)
/* Fast short circuit protection : 50% over rated current */
-#define MAX_CURRENT_FAST VBUS_MA(RATED_CURRENT * 3/2)
+#define MAX_CURRENT_FAST VBUS_MA(RATED_CURRENT * 3 / 2)
/* reset over-current after 1 second */
#define OCP_TIMEOUT SECOND
@@ -100,19 +102,19 @@ static timestamp_t fault_deadline;
#define SINK_IDLE_CURRENT VBUS_MA(500 /* mA */)
/* Under-voltage limit is 0.8x Vnom */
-#define UVP_MV(mv) VBUS_MV((mv) * 8 / 10)
+#define UVP_MV(mv) VBUS_MV((mv)*8 / 10)
/* Over-voltage limit is 1.2x Vnom */
-#define OVP_MV(mv) VBUS_MV((mv) * 12 / 10)
+#define OVP_MV(mv) VBUS_MV((mv)*12 / 10)
/* Over-voltage recovery threshold is 1.1x Vnom */
-#define OVP_REC_MV(mv) VBUS_MV((mv) * 11 / 10)
+#define OVP_REC_MV(mv) VBUS_MV((mv)*11 / 10)
/* Maximum discharging delay */
-#define DISCHARGE_TIMEOUT (275*MSEC)
+#define DISCHARGE_TIMEOUT (275 * MSEC)
/* Voltage overshoot below the OVP threshold for discharging to avoid OVP */
#define DISCHARGE_OVERSHOOT_MV VBUS_MV(200)
/* Time to wait after last RX edge interrupt before allowing deep sleep */
-#define PD_RX_SLEEP_TIMEOUT (100*MSEC)
+#define PD_RX_SLEEP_TIMEOUT (100 * MSEC)
/* ----- output voltage discharging ----- */
@@ -151,16 +153,15 @@ static void discharge_voltage(int target_volt)
/* PDO voltages (should match the table above) */
static const struct {
enum volt select; /* GPIO configuration to select the voltage */
- int uvp; /* under-voltage limit in mV */
- int ovp; /* over-voltage limit in mV */
- int ovp_rec;/* over-voltage recovery threshold in mV */
+ int uvp; /* under-voltage limit in mV */
+ int ovp; /* over-voltage limit in mV */
+ int ovp_rec; /* over-voltage recovery threshold in mV */
} voltages[ARRAY_SIZE(pd_src_pdo)] = {
- [PDO_IDX_5V] = {VO_5V, UVP_MV(5000), OVP_MV(5000),
- OVP_REC_MV(5000)},
- [PDO_IDX_12V] = {VO_12V, UVP_MV(12000), OVP_MV(12000),
- OVP_REC_MV(12000)},
- [PDO_IDX_20V] = {VO_20V, UVP_MV(20000), OVP_MV(20000),
- OVP_REC_MV(20000)},
+ [PDO_IDX_5V] = { VO_5V, UVP_MV(5000), OVP_MV(5000), OVP_REC_MV(5000) },
+ [PDO_IDX_12V] = { VO_12V, UVP_MV(12000), OVP_MV(12000),
+ OVP_REC_MV(12000) },
+ [PDO_IDX_20V] = { VO_20V, UVP_MV(20000), OVP_MV(20000),
+ OVP_REC_MV(20000) },
};
/* current and previous selected PDO entry */
@@ -199,8 +200,8 @@ void pd_transition_voltage(int idx)
/* Make sure discharging is disabled */
discharge_disable();
/* Enable over-current monitoring */
- adc_enable_watchdog(ADC_CH_A_SENSE,
- MAX_CURRENT_FAST, 0);
+ adc_enable_watchdog(ADC_CH_A_SENSE, MAX_CURRENT_FAST,
+ 0);
}
}
set_output_voltage(voltages[volt_idx].select);
@@ -241,28 +242,22 @@ void pd_power_supply_reset(int port)
}
}
-int pd_check_data_swap(int port,
- enum pd_data_role data_role)
+int pd_check_data_swap(int port, enum pd_data_role data_role)
{
/* Allow data swap if we are a DFP, otherwise don't allow */
return (data_role == PD_ROLE_DFP) ? 1 : 0;
}
-void pd_execute_data_swap(int port,
- enum pd_data_role data_role)
+void pd_execute_data_swap(int port, enum pd_data_role data_role)
{
/* Do nothing */
}
-void pd_check_pr_role(int port,
- enum pd_power_role pr_role,
- int flags)
+void pd_check_pr_role(int port, enum pd_power_role pr_role, int flags)
{
}
-void pd_check_dr_role(int port,
- enum pd_data_role dr_role,
- int flags)
+void pd_check_dr_role(int port, enum pd_data_role dr_role, int flags)
{
/* If DFP, try to switch to UFP */
if ((flags & PD_FLAGS_PARTNER_DR_DATA) && dr_role == PD_ROLE_DFP)
@@ -289,7 +284,7 @@ int pd_board_checks(void)
__enter_hibernate(0, 0);
}
} else {
- hib_to.val = get_time().val + 60*SECOND;
+ hib_to.val = get_time().val + 60 * SECOND;
hib_to_ready = 1;
}
#endif
@@ -319,8 +314,8 @@ int pd_board_checks(void)
/* trigger the slow OCP iff all 4 samples are above the max */
if (count == 3) {
debug_printf("OCP %d mA\n",
- vbus_amp * VDDA_MV / CURR_GAIN * 1000
- / R_SENSE / ADC_SCALE);
+ vbus_amp * VDDA_MV / CURR_GAIN * 1000 /
+ R_SENSE / ADC_SCALE);
pd_log_event(PD_EVENT_PS_FAULT, 0, PS_FAULT_OCP, NULL);
fault = FAULT_OCP;
/* reset over-current after 1 second */
@@ -349,8 +344,7 @@ int pd_board_checks(void)
if ((output_is_enabled() && (vbus_volt > voltages[ovp_idx].ovp)) ||
(fault && (vbus_volt > voltages[ovp_idx].ovp_rec))) {
if (!fault) {
- debug_printf("OVP %d mV\n",
- ADC_TO_VOLT_MV(vbus_volt));
+ debug_printf("OVP %d mV\n", ADC_TO_VOLT_MV(vbus_volt));
pd_log_event(PD_EVENT_PS_FAULT, 0, PS_FAULT_OVP, NULL);
}
fault = FAULT_OVP;
@@ -361,7 +355,7 @@ int pd_board_checks(void)
/* the discharge did not work properly */
if (discharge_is_enabled() &&
- (get_time().val > discharge_deadline.val)) {
+ (get_time().val > discharge_deadline.val)) {
/* ensure we always finish a 2-step discharge */
volt_idx = discharge_volt_idx;
set_output_voltage(voltages[volt_idx].select);
@@ -369,8 +363,7 @@ int pd_board_checks(void)
discharge_disable();
/* enable over-current monitoring */
adc_enable_watchdog(ADC_CH_A_SENSE, MAX_CURRENT_FAST, 0);
- debug_printf("Disch FAIL %d mV\n",
- ADC_TO_VOLT_MV(vbus_volt));
+ debug_printf("Disch FAIL %d mV\n", ADC_TO_VOLT_MV(vbus_volt));
pd_log_event(PD_EVENT_PS_FAULT, 0, PS_FAULT_DISCH, NULL);
fault = FAULT_DISCHARGE;
/* reset it after 1 second */
@@ -390,7 +383,6 @@ int pd_board_checks(void)
}
return EC_SUCCESS;
-
}
static void pd_adc_interrupt(void)
@@ -407,10 +399,10 @@ static void pd_adc_interrupt(void)
} else { /* discharge complete */
discharge_disable();
/* enable over-current monitoring */
- adc_enable_watchdog(ADC_CH_A_SENSE,
- MAX_CURRENT_FAST, 0);
+ adc_enable_watchdog(ADC_CH_A_SENSE, MAX_CURRENT_FAST,
+ 0);
}
- } else {/* Over-current detection */
+ } else { /* Over-current detection */
/* cut the power output */
pd_power_supply_reset(0);
/* record a special fault */
@@ -453,9 +445,7 @@ static int svdm_response_svids(int port, uint32_t *payload)
#define MODE_CNT 1
#define OPOS 1
-const uint32_t vdo_dp_mode[MODE_CNT] = {
- VDO_MODE_GOOGLE(MODE_GOOGLE_FU)
-};
+const uint32_t vdo_dp_mode[MODE_CNT] = { VDO_MODE_GOOGLE(MODE_GOOGLE_FU) };
static int svdm_response_modes(int port, uint32_t *payload)
{
@@ -499,16 +489,17 @@ const struct svdm_response svdm_rsp = {
};
__override int pd_custom_vdm(int port, int cnt, uint32_t *payload,
- uint32_t **rpayload)
+ uint32_t **rpayload)
{
int cmd = PD_VDO_CMD(payload[0]);
int rsize;
+ char ts_str[PRINTF_TIMESTAMP_BUF_SIZE];
if (PD_VDO_VID(payload[0]) != USB_VID_GOOGLE || !gfu_mode)
return 0;
- debug_printf("%pT] VDM/%d [%d] %08x\n",
- PRINTF_TIMESTAMP_NOW, cnt, cmd, payload[0]);
+ snprintf_timestamp_now(ts_str, sizeof(ts_str));
+ debug_printf("%s] VDM/%d [%d] %08x\n", ts_str, cnt, cmd, payload[0]);
*rpayload = payload;
rsize = pd_custom_flash_vdm(port, cnt, payload);