Skip to content

Commit

Permalink
Merge "Clean up more warnings in lk code"
Browse files Browse the repository at this point in the history
  • Loading branch information
Linux Build Service Account authored and QuIC Gerrit Code Review committed Jul 27, 2011
2 parents 23b9de5 + d2471ef commit 0a81a32
Show file tree
Hide file tree
Showing 21 changed files with 101 additions and 27 deletions.
6 changes: 5 additions & 1 deletion app/aboot/aboot.c
Expand Up @@ -95,6 +95,10 @@ struct atag_ptbl_entry

char sn_buf[13];

extern int emmc_recovery_init(void);



static void ptentry_to_tag(unsigned **ptr, struct ptentry *ptn)
{
struct atag_ptbl_entry atag_ptn;
Expand Down Expand Up @@ -354,7 +358,7 @@ int boot_linux_from_mmc(void)
dprintf(INFO, "cmdline = '%s'\n", cmdline);

dprintf(INFO, "\nBooting Linux\n");
boot_linux((void *)hdr->kernel_addr, hdr->tags_addr,
boot_linux((void *)hdr->kernel_addr, (unsigned *) hdr->tags_addr,
(const char *)cmdline, board_machtype(),
(void *)hdr->ramdisk_addr, hdr->ramdisk_size);

Expand Down
10 changes: 5 additions & 5 deletions app/aboot/recovery.c
Expand Up @@ -37,6 +37,7 @@
#include <lib/ptable.h>
#include <dev/keys.h>
#include <platform.h>
#include <mmc.h>

#include "recovery.h"
#include "bootimg.h"
Expand Down Expand Up @@ -284,7 +285,6 @@ int get_boot_info_apps (char type, unsigned int *status)
int recovery_init (void)
{
struct recovery_message msg;
struct update_header header;
char partition_name[32];
unsigned valid_command = 0;
int update_status = 0;
Expand All @@ -302,7 +302,7 @@ int recovery_init (void)
if(!strcmp("RADIO",msg.status))
{
/* We're now here due to radio update, so check for update status */
int ret = get_boot_info_apps(UPDATE_STATUS, &update_status);
int ret = get_boot_info_apps(UPDATE_STATUS, (unsigned int *) &update_status);

if(!ret && (update_status & 0x01))
{
Expand Down Expand Up @@ -381,7 +381,7 @@ static int emmc_set_recovery_msg(struct recovery_message *out)
unsigned int size = ROUND_TO_PAGE(sizeof(*out),511);
unsigned char data[size];

ptn = mmc_ptn_offset(ptn_name);
ptn = mmc_ptn_offset((unsigned char *) ptn_name);
if(ptn == 0) {
dprintf(CRITICAL,"partition %s doesn't exist\n",ptn_name);
return -1;
Expand All @@ -401,7 +401,7 @@ static int emmc_get_recovery_msg(struct recovery_message *in)
unsigned int size = ROUND_TO_PAGE(sizeof(*in),511);
unsigned char data[size];

ptn = mmc_ptn_offset(ptn_name);
ptn = mmc_ptn_offset((unsigned char *) ptn_name);
if(ptn == 0) {
dprintf(CRITICAL,"partition %s doesn't exist\n",ptn_name);
return -1;
Expand Down Expand Up @@ -430,7 +430,7 @@ int _emmc_recovery_init(void)
if (!strcmp("update-radio",msg.command))
{
/* We're now here due to radio update, so check for update status */
int ret = get_boot_info_apps(UPDATE_STATUS, &update_status);
int ret = get_boot_info_apps(UPDATE_STATUS, (unsigned int *) &update_status);

if(!ret && (update_status & 0x01))
{
Expand Down
7 changes: 5 additions & 2 deletions dev/pmic/pm8921/include/dev/pm8921.h
Expand Up @@ -72,12 +72,15 @@ enum
LDO_VOLTAGE_ENTRIES
};

typedef int (*pm8921_read_func)(uint8_t *data, uint32_t length, uint32_t addr);
typedef int (*pm8921_write_func)(uint8_t *data, uint32_t length, uint32_t addr);

typedef struct
{
uint32_t initialized;

int (*read)(uint8_t *data, uint32_t length, uint32_t addr);
int (*write)(uint8_t *data, uint32_t length, uint32_t addr);
pm8921_read_func read;
pm8921_write_func write;

} pm8921_dev_t;

Expand Down
4 changes: 4 additions & 0 deletions include/dev/gpio.h
Expand Up @@ -29,8 +29,12 @@
#ifndef __DEV_GPIO_H
#define __DEV_GPIO_H

#ifndef GPIO_INPUT
#define GPIO_INPUT 0x0000
#endif
#ifndef GPIO_OUTPUT
#define GPIO_OUTPUT 0x0001
#endif

#define GPIO_LEVEL 0x0000
#define GPIO_EDGE 0x0010
Expand Down
1 change: 0 additions & 1 deletion include/target.h
Expand Up @@ -41,7 +41,6 @@ int target_is_emmc_boot(void);
unsigned* target_atag_mem(unsigned* ptr);
void *target_get_scratch_address(void);
unsigned target_get_max_flash_size(void);
int target_is_emmc_boot(void);
void target_battery_charging_enable(unsigned enable, unsigned disconnect);
unsigned target_pause_for_battery_charge(void);
unsigned target_baseband(void);
Expand Down
4 changes: 4 additions & 0 deletions platform/msm8x60/include/platform/gpio.h
Expand Up @@ -30,8 +30,12 @@
#define __PLATFORM_MSM8X60_GPIO_H

/* GPIO TLMM: Direction */
#ifndef GPIO_INPUT
#define GPIO_INPUT 0
#endif
#ifndef GPIO_OUTPUT
#define GPIO_OUTPUT 1
#endif

/* GPIO TLMM: Pullup/Pulldown */
#define GPIO_NO_PULL 0
Expand Down
4 changes: 4 additions & 0 deletions platform/msm8x60/panel.c
Expand Up @@ -36,10 +36,14 @@
#include <platform/pmic.h>
#include <platform/pmic_pwm.h>
#include <gsbi.h>
#include <dev/gpio.h>

#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))

static struct qup_i2c_dev *dev = NULL;
void gpio_tlmm_config(uint32_t gpio, uint8_t func,
uint8_t dir, uint8_t pull,
uint8_t drvstr, uint32_t enable);

uint8_t expander_read(uint8_t addr)
{
Expand Down
12 changes: 7 additions & 5 deletions platform/msm8x60/scm-io.c
@@ -1,4 +1,4 @@
/* Copyright (c) 2010, Code Aurora Forum. All rights reserved.
/* Copyright (c) 2011, Code Aurora Forum. All rights reserved.
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are
Expand Down Expand Up @@ -39,10 +39,12 @@
#define BETWEEN(p, st, sz) ((p) >= (void *)(st) && \
(p) < ((void *)(st) + (sz)))

extern void dmb(void);

uint32_t secure_readl(uint32_t c)
{
if ((BETWEEN(c, MSM_MMSS_CLK_CTL_BASE, MSM_MMSS_CLK_CTL_SIZE)) ||
(BETWEEN(c, MSM_TCSR_BASE, MSM_TCSR_SIZE)))
if ((BETWEEN((void *) c, MSM_MMSS_CLK_CTL_BASE, MSM_MMSS_CLK_CTL_SIZE)) ||
(BETWEEN((void *) c, MSM_TCSR_BASE, MSM_TCSR_SIZE)))
{
uint32_t context_id;
register uint32_t r0 __asm__("r0") = SCM_IO_READ;
Expand All @@ -62,8 +64,8 @@ uint32_t secure_readl(uint32_t c)

void secure_writel(uint32_t v, uint32_t c)
{
if ((BETWEEN(c, MSM_MMSS_CLK_CTL_BASE, MSM_MMSS_CLK_CTL_SIZE)) ||
(BETWEEN(c, MSM_TCSR_BASE, MSM_TCSR_SIZE))) {
if ((BETWEEN((void *) c, MSM_MMSS_CLK_CTL_BASE, MSM_MMSS_CLK_CTL_SIZE)) ||
(BETWEEN((void *) c, MSM_TCSR_BASE, MSM_TCSR_SIZE))) {
uint32_t context_id;
register uint32_t r0 __asm__("r0") = SCM_IO_WRITE;
register uint32_t r1 __asm__("r1") = (uint32_t)&context_id;
Expand Down
3 changes: 3 additions & 0 deletions platform/msm_shared/hsusb.c
Expand Up @@ -34,6 +34,7 @@
#include <platform/iomap.h>
#include <platform/irqs.h>
#include <platform/interrupts.h>
#include <platform/timer.h>
#include <kernel/thread.h>
#include <reg.h>

Expand Down Expand Up @@ -795,7 +796,9 @@ int udc_start(void)

int udc_stop(void)
{
#ifdef PLATFORM_MSM8X60
int val;
#endif
writel(0, USB_USBINTR);
mask_interrupt(INT_USB_HS);

Expand Down
8 changes: 7 additions & 1 deletion platform/msm_shared/i2c_qup.c
Expand Up @@ -35,13 +35,19 @@
#include <arch/arm.h>
#include <reg.h>
#include <kernel/thread.h>
#include <dev/gpio.h>
#include <stdlib.h>
#include <string.h>

#include <gsbi.h>
#include <i2c_qup.h>
#include <platform/irqs.h>
#include <platform/iomap.h>
#include <platform/gpio.h>
#include <platform/clock.h>
#include <platform/timer.h>
#include <platform/interrupts.h>


static struct qup_i2c_dev *dev_addr = NULL;

Expand Down Expand Up @@ -681,7 +687,7 @@ struct qup_i2c_dev *qup_i2c_init(uint8_t gsbi_id,
dev->clk_ctl = 0;

/* Register the GSBIn QUP IRQ */
register_int_handler(dev->qup_irq, qup_i2c_interrupt, 0);
register_int_handler(dev->qup_irq, (int_handler) qup_i2c_interrupt, 0);

/* Then disable it */
mask_interrupt(dev->qup_irq);
Expand Down
1 change: 1 addition & 0 deletions platform/msm_shared/include/mmc.h
Expand Up @@ -630,6 +630,7 @@ unsigned long long mmc_ptn_size (unsigned char * name);

unsigned int mmc_read (unsigned long long data_addr, unsigned int* out,
unsigned int data_len);
unsigned mmc_get_psn(void);

unsigned int mmc_boot_write_to_card (struct mmc_boot_host* host,
struct mmc_boot_card* card,
Expand Down
2 changes: 1 addition & 1 deletion platform/msm_shared/lcdc.c
Expand Up @@ -172,7 +172,7 @@ struct fbcon_config *lcdc_init_set( struct lcdc_timing_parameters *custom_timing
writel(0x100, MSM_MDP_BASE1 + 0x10100);
writel(mdp_rgb_size, MSM_MDP_BASE1 + 0x40000);
writel(mdp_rgb_size, MSM_MDP_BASE1 + 0x40008);
writel(fb_cfg.base, MSM_MDP_BASE1 + 0x40010);
writel((int) fb_cfg.base, MSM_MDP_BASE1 + 0x40010);
writel(fb_cfg.width * fb_cfg.bpp / 8, MSM_MDP_BASE1 + 0x40040);
writel(0x00, MSM_MDP_BASE1 + 0x41008);
writel(MDP_RGB_565_FORMAT, MSM_MDP_BASE1 + 0x40050);
Expand Down
1 change: 1 addition & 0 deletions platform/msm_shared/mddi.c
Expand Up @@ -34,6 +34,7 @@
#include <kernel/thread.h>
#include <mddi.h>
#include <target/display.h>
#include <platform/timer.h>

#include "mddi_hw.h"

Expand Down
2 changes: 2 additions & 0 deletions platform/msm_shared/nand.c
Expand Up @@ -2281,7 +2281,9 @@ static int _flash_onenand_read_page(dmov_s *cmdlist, unsigned *ptrlist,
struct data_onenand_read *data = (void*) (ptrlist + 4);
unsigned addr = (unsigned) _addr;
unsigned curr_addr = (unsigned) _addr;
#if VERBOSE
unsigned spareaddr = (unsigned) _spareaddr;
#endif
unsigned i;
unsigned erasesize = (flash_pagesize * num_pages_per_blk);
unsigned writesize = flash_pagesize;
Expand Down
1 change: 1 addition & 0 deletions platform/msm_shared/proc_comm.c
Expand Up @@ -30,6 +30,7 @@

#include <debug.h>
#include <reg.h>
#include <dev/gpio.h>

#include <platform/iomap.h>
#define ACPU_CLK 0 /* Applications processor clock */
Expand Down
4 changes: 4 additions & 0 deletions platform/msm_shared/smem.h
Expand Up @@ -299,4 +299,8 @@ struct smem_ram_ptable {
#define PWR_ON_EVENT_USB_CHG 0x20
#define PWR_ON_EVENT_RTC_ALARM 0x2


unsigned smem_read_alloc_entry_offset(smem_mem_type_t type, void *buf, int len, int offset);
int smem_ram_ptable_init(struct smem_ram_ptable *smem_ram_ptable);

#endif /* __PLATFORM_MSM_SHARED_SMEM_H */
34 changes: 34 additions & 0 deletions platform/msm_shared/timer.c
Expand Up @@ -41,13 +41,47 @@
#include <platform/interrupts.h>
#include <kernel/thread.h>

#if PLATFORM_MSM7X30 || PLATFORM_MSM8X60 || PLATFORM_MSM8960

#define MSM_DGT_BASE (MSM_TMR_BASE + 0x24)
#define GPT_REG(off) (MSM_GPT_BASE + (off))
#define DGT_REG(off) (MSM_DGT_BASE + (off))
#define SPSS_TIMER_STATUS (MSM_TMR_BASE + 0x88)
#define SPSS_TIMER_STATUS_DGT_EN (1 << 0)

#define GPT_MATCH_VAL GPT_REG(0x0000)
#define GPT_COUNT_VAL GPT_REG(0x0004)
#define GPT_ENABLE GPT_REG(0x0008)
#define GPT_ENABLE_CLR_ON_MATCH_EN 2
#define GPT_ENABLE_EN 1
#define GPT_CLEAR GPT_REG(0x000C)

#define DGT_MATCH_VAL DGT_REG(0x0000)
#define DGT_COUNT_VAL DGT_REG(0x0004)
#define DGT_ENABLE DGT_REG(0x0008)
#define DGT_ENABLE_CLR_ON_MATCH_EN 2
#define DGT_ENABLE_EN 1
#define DGT_CLEAR DGT_REG(0x000C)
#define DGT_CLK_CTL DGT_REG(0x0010)

#define HW_REVISION_NUMBER 0xABC00270


#else
#define GPT_REG(off) (MSM_GPT_BASE + (off))

#define GPT_MATCH_VAL GPT_REG(0x0000)
#define GPT_COUNT_VAL GPT_REG(0x0004)
#define GPT_ENABLE GPT_REG(0x0008)
#define GPT_ENABLE_CLR_ON_MATCH_EN 2
#define GPT_ENABLE_EN 1
#define DGT_ENABLE_CLR_ON_MATCH_EN 2
#define DGT_ENABLE_EN 1

#define SPSS_TIMER_STATUS_DGT_EN (1 << 0)

#endif

static platform_timer_callback timer_callback;
static void *timer_arg;
static time_t timer_interval;
Expand Down
4 changes: 1 addition & 3 deletions platform/msm_shared/uart_dm.c
Expand Up @@ -39,6 +39,7 @@
#include <uart_dm.h>
#include <gsbi.h>


#ifndef NULL
#define NULL 0
#endif
Expand Down Expand Up @@ -81,9 +82,6 @@ static unsigned int msm_boot_uart_dm_write(uint8_t id, char* data,
static unsigned int msm_boot_uart_dm_init_rx_transfer(uint8_t id);
static unsigned int msm_boot_uart_dm_reset(uint8_t id);

/* TODO: Detele the patch that adds this to sys/types.h gets merged */
#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))

/* Keep track of gsbi vs port mapping.
*/
static uint8_t gsbi_lookup[4];
Expand Down
1 change: 0 additions & 1 deletion target/msm7630_surf/atags.c
Expand Up @@ -35,7 +35,6 @@


static int scratch_addr = -1;
int smem_ram_ptable_init(struct smem_ram_ptable *);

unsigned* target_atag_mem(unsigned* ptr)
{
Expand Down
12 changes: 7 additions & 5 deletions target/msm8660_surf/init.c
Expand Up @@ -33,6 +33,7 @@
#include <debug.h>
#include <dev/keys.h>
#include <dev/gpio_keypad.h>
#include <dev/gpio.h>
#include <lib/ptable.h>
#include <dev/flash.h>
#include <smem.h>
Expand All @@ -44,6 +45,7 @@
#include <reg.h>
#include <platform.h>
#include <gsbi.h>
#include <platform/scm-io.h>

#define LINUX_MACHTYPE_8660_SURF 2755
#define LINUX_MACHTYPE_8660_FFA 3017
Expand All @@ -56,8 +58,8 @@
static const uint8_t uart_gsbi_id = GSBI_ID_12;

void keypad_init(void);
extern void dmb(void);

static int emmc_boot = -1; /* set to uninitialized */
int target_is_emmc_boot(void);
void debug_led_write(char);
char debug_led_read();
Expand Down Expand Up @@ -106,9 +108,9 @@ unsigned board_machtype(void)
unsigned hw_platform = 0;
unsigned fused_chip = 0;
unsigned platform_subtype = 0;
static unsigned mach_id = -1;
static unsigned mach_id = 0xFFFFFFFF;

if(mach_id != -1)
if(mach_id != 0xFFFFFFFF)
return mach_id;
/* Detect external msm if this is a "fusion" */
smem_status = smem_read_alloc_entry_offset(SMEM_BOARD_INFO_LOCATION,
Expand Down Expand Up @@ -264,7 +266,7 @@ void reboot_device(unsigned reboot_reason)
unsigned check_reboot_mode(void)
{
unsigned restart_reason = 0;
void *restart_reason_addr = 0x2A05F65C;
void *restart_reason_addr = (void *) 0x2A05F65C;

/* Read reboot reason and scrub it */
restart_reason = readl(restart_reason_addr);
Expand Down Expand Up @@ -415,7 +417,7 @@ void target_serialno(unsigned char *buf)
if(target_is_emmc_boot())
{
serialno = mmc_get_psn();
sprintf(buf,"%x",serialno);
sprintf((char *) buf, "%x", serialno);
}
}

Expand Down

0 comments on commit 0a81a32

Please sign in to comment.