* [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-23 10:49 [Qemu-devel] [PATCH 0/3] Fix guest time drift under heavy load Gleb Natapov
@ 2008-06-23 10:49 ` Gleb Natapov
0 siblings, 0 replies; 29+ messages in thread
From: Gleb Natapov @ 2008-06-23 10:49 UTC (permalink / raw)
To: qemu-devel
The return value is less then zero if interrupt is masked, zero if it
is known that interrupt is lost (due to coalescing) or greater then zero
if interrupt is delivered or was successfully queued for delivery by
interrupt controller. Device emulation can use this info as it pleases.
Included patch adds detection of interrupt coalescing into PIC and APIC
code for edge triggered interrupts.
Signed-off-by: Gleb Natapov <gleb@qumranet.com>
---
hw/apic.c | 103 +++++++++++++++++++++++++++++++++++++--------------------
hw/esp.c | 4 ++
hw/fdc.c | 4 ++
hw/i8259.c | 19 +++++++----
hw/ide.c | 8 +++-
hw/irq.c | 10 +++---
hw/irq.h | 22 +++++++-----
hw/max7310.c | 4 ++
hw/pc.c | 6 ++-
hw/pc.h | 2 +
hw/pci.c | 8 +++-
hw/ssd0323.c | 4 ++
hw/twl92230.c | 8 +++-
13 files changed, 131 insertions(+), 71 deletions(-)
diff --git a/hw/apic.c b/hw/apic.c
index 6fd0160..9bdaed2 100644
--- a/hw/apic.c
+++ b/hw/apic.c
@@ -101,7 +101,7 @@ static APICState *local_apics[MAX_APICS + 1];
static int last_apic_id = 0;
static void apic_init_ipi(APICState *s);
-static void apic_set_irq(APICState *s, int vector_num, int trigger_mode);
+static int apic_set_irq(APICState *s, int vector_num, int trigger_mode);
static void apic_update_irq(APICState *s);
/* Find first bit starting from msb. Return 0 if value = 0 */
@@ -166,6 +166,14 @@ static inline void reset_bit(uint32_t *tab, int index)
tab[i] &= ~mask;
}
+static inline int get_bit(uint32_t *tab, int index)
+{
+ int i, mask;
+ i = index >> 5;
+ mask = 1 << (index & 0x1f);
+ return !!(tab[i] & mask);
+}
+
void apic_local_deliver(CPUState *env, int vector)
{
APICState *s = env->apic_state;
@@ -215,12 +223,13 @@ void apic_local_deliver(CPUState *env, int vector)
}\
}
-static void apic_bus_deliver(const uint32_t *deliver_bitmask,
+static int apic_bus_deliver(const uint32_t *deliver_bitmask,
uint8_t delivery_mode,
uint8_t vector_num, uint8_t polarity,
uint8_t trigger_mode)
{
APICState *apic_iter;
+ int ret = 0;
switch (delivery_mode) {
case APIC_DM_LOWPRI:
@@ -237,11 +246,12 @@ static void apic_bus_deliver(const uint32_t *deliver_bitmask,
if (d >= 0) {
apic_iter = local_apics[d];
if (apic_iter) {
- apic_set_irq(apic_iter, vector_num, trigger_mode);
+ ret = apic_set_irq(apic_iter, vector_num, trigger_mode);
}
- }
+ } else
+ ret = 1;
}
- return;
+ return ret;
case APIC_DM_FIXED:
break;
@@ -249,29 +259,33 @@ static void apic_bus_deliver(const uint32_t *deliver_bitmask,
case APIC_DM_SMI:
foreach_apic(apic_iter, deliver_bitmask,
cpu_interrupt(apic_iter->cpu_env, CPU_INTERRUPT_SMI) );
- return;
+ return 1;
case APIC_DM_NMI:
foreach_apic(apic_iter, deliver_bitmask,
cpu_interrupt(apic_iter->cpu_env, CPU_INTERRUPT_NMI) );
- return;
+ return 1;
case APIC_DM_INIT:
/* normal INIT IPI sent to processors */
foreach_apic(apic_iter, deliver_bitmask,
apic_init_ipi(apic_iter) );
- return;
+ return 1;
case APIC_DM_EXTINT:
/* handled in I/O APIC code */
break;
default:
- return;
+ return ret;
}
+ /* if interrupt should be delivered to more then one apic report it as
+ * delivered if at least one apic accepts it */
foreach_apic(apic_iter, deliver_bitmask,
- apic_set_irq(apic_iter, vector_num, trigger_mode) );
+ ret += apic_set_irq(apic_iter, vector_num, trigger_mode) );
+
+ return ret;
}
void cpu_set_apic_base(CPUState *env, uint64_t val)
@@ -361,14 +375,18 @@ static void apic_update_irq(APICState *s)
cpu_interrupt(s->cpu_env, CPU_INTERRUPT_HARD);
}
-static void apic_set_irq(APICState *s, int vector_num, int trigger_mode)
+static int apic_set_irq(APICState *s, int vector_num, int trigger_mode)
{
+ int ret = !get_bit(s->irr, vector_num);
+
set_bit(s->irr, vector_num);
if (trigger_mode)
set_bit(s->tmr, vector_num);
else
reset_bit(s->tmr, vector_num);
apic_update_irq(s);
+
+ return ret;
}
static void apic_eoi(APICState *s)
@@ -906,9 +924,8 @@ int apic_init(CPUState *env)
return 0;
}
-static void ioapic_service(IOAPICState *s)
+static int ioapic_service_one(IOAPICState *s, uint8_t pin)
{
- uint8_t i;
uint8_t trig_mode;
uint8_t vector;
uint8_t delivery_mode;
@@ -919,34 +936,44 @@ static void ioapic_service(IOAPICState *s)
uint8_t polarity;
uint32_t deliver_bitmask[MAX_APIC_WORDS];
+ mask = 1 << pin;
+ if (!(s->irr & mask))
+ return 1;
+
+ entry = s->ioredtbl[pin];
+ if ((entry & APIC_LVT_MASKED))
+ return -1;
+
+ trig_mode = ((entry >> 15) & 1);
+ dest = entry >> 56;
+ dest_mode = (entry >> 11) & 1;
+ delivery_mode = (entry >> 8) & 7;
+ polarity = (entry >> 13) & 1;
+ if (trig_mode == APIC_TRIGGER_EDGE)
+ s->irr &= ~mask;
+ if (delivery_mode == APIC_DM_EXTINT)
+ vector = pic_read_irq(isa_pic);
+ else
+ vector = entry & 0xff;
+
+ apic_get_delivery_bitmask(deliver_bitmask, dest, dest_mode);
+ return apic_bus_deliver(deliver_bitmask, delivery_mode, vector, polarity,
+ trig_mode);
+}
+
+static void ioapic_service(IOAPICState *s)
+{
+ uint8_t i;
+
for (i = 0; i < IOAPIC_NUM_PINS; i++) {
- mask = 1 << i;
- if (s->irr & mask) {
- entry = s->ioredtbl[i];
- if (!(entry & APIC_LVT_MASKED)) {
- trig_mode = ((entry >> 15) & 1);
- dest = entry >> 56;
- dest_mode = (entry >> 11) & 1;
- delivery_mode = (entry >> 8) & 7;
- polarity = (entry >> 13) & 1;
- if (trig_mode == APIC_TRIGGER_EDGE)
- s->irr &= ~mask;
- if (delivery_mode == APIC_DM_EXTINT)
- vector = pic_read_irq(isa_pic);
- else
- vector = entry & 0xff;
-
- apic_get_delivery_bitmask(deliver_bitmask, dest, dest_mode);
- apic_bus_deliver(deliver_bitmask, delivery_mode,
- vector, polarity, trig_mode);
- }
- }
+ ioapic_service_one(s, i);
}
}
-void ioapic_set_irq(void *opaque, int vector, int level)
+int ioapic_set_irq(void *opaque, int vector, int level)
{
IOAPICState *s = opaque;
+ int ret = 1;
if (vector >= 0 && vector < IOAPIC_NUM_PINS) {
uint32_t mask = 1 << vector;
@@ -956,7 +983,7 @@ void ioapic_set_irq(void *opaque, int vector, int level)
/* level triggered */
if (level) {
s->irr |= mask;
- ioapic_service(s);
+ ioapic_service_one(s, vector);
} else {
s->irr &= ~mask;
}
@@ -964,10 +991,12 @@ void ioapic_set_irq(void *opaque, int vector, int level)
/* edge triggered */
if (level) {
s->irr |= mask;
- ioapic_service(s);
+ ret = ioapic_service_one(s, vector);
}
}
}
+
+ return ret;
}
static uint32_t ioapic_mem_readl(void *opaque, target_phys_addr_t addr)
diff --git a/hw/esp.c b/hw/esp.c
index 1843fb8..aa5e546 100644
--- a/hw/esp.c
+++ b/hw/esp.c
@@ -409,10 +409,12 @@ static void esp_reset(void *opaque)
s->do_cmd = 0;
}
-static void parent_esp_reset(void *opaque, int irq, int level)
+static int parent_esp_reset(void *opaque, int irq, int level)
{
if (level)
esp_reset(opaque);
+
+ return 1;
}
static uint32_t esp_mem_readb(void *opaque, target_phys_addr_t addr)
diff --git a/hw/fdc.c b/hw/fdc.c
index cd00420..b212d89 100644
--- a/hw/fdc.c
+++ b/hw/fdc.c
@@ -713,7 +713,7 @@ static void fdctrl_external_reset(void *opaque)
fdctrl_reset(s, 0);
}
-static void fdctrl_handle_tc(void *opaque, int irq, int level)
+static int fdctrl_handle_tc(void *opaque, int irq, int level)
{
//fdctrl_t *s = opaque;
@@ -721,6 +721,8 @@ static void fdctrl_handle_tc(void *opaque, int irq, int level)
// XXX
FLOPPY_DPRINTF("TC pulsed\n");
}
+
+ return 1;
}
/* XXX: may change if moved to bdrv */
diff --git a/hw/i8259.c b/hw/i8259.c
index add6345..ab7eb2d 100644
--- a/hw/i8259.c
+++ b/hw/i8259.c
@@ -72,9 +72,9 @@ static uint64_t irq_count[16];
#endif
/* set irq level. If an edge is detected, then the IRR is set to 1 */
-static inline void pic_set_irq1(PicState *s, int irq, int level)
+static inline int pic_set_irq1(PicState *s, int irq, int level)
{
- int mask;
+ int mask, ret = 1;
mask = 1 << irq;
if (s->elcr & mask) {
/* level triggered */
@@ -88,13 +88,18 @@ static inline void pic_set_irq1(PicState *s, int irq, int level)
} else {
/* edge triggered */
if (level) {
- if ((s->last_irr & mask) == 0)
+ if ((s->last_irr & mask) == 0) {
+ if((s->irr & mask))
+ ret = 0;
s->irr |= mask;
+ }
s->last_irr |= mask;
} else {
s->last_irr &= ~mask;
}
}
+
+ return (s->imr & mask) ? -1 : ret;
}
/* return the highest priority found in mask (highest = smallest
@@ -178,9 +183,10 @@ void pic_update_irq(PicState2 *s)
int64_t irq_time[16];
#endif
-static void i8259_set_irq(void *opaque, int irq, int level)
+static int i8259_set_irq(void *opaque, int irq, int level)
{
PicState2 *s = opaque;
+ int pic_ret, ioapic_ret;
#if defined(DEBUG_PIC) || defined(DEBUG_IRQ_COUNT)
if (level != irq_level[irq]) {
@@ -199,11 +205,12 @@ static void i8259_set_irq(void *opaque, int irq, int level)
irq_time[irq] = qemu_get_clock(vm_clock);
}
#endif
- pic_set_irq1(&s->pics[irq >> 3], irq & 7, level);
+ pic_ret = pic_set_irq1(&s->pics[irq >> 3], irq & 7, level);
/* used for IOAPIC irqs */
if (s->alt_irq_func)
- s->alt_irq_func(s->alt_irq_opaque, irq, level);
+ ioapic_ret = s->alt_irq_func(s->alt_irq_opaque, irq, level);
pic_update_irq(s);
+ return MAX(pic_ret, ioapic_ret);
}
/* acknowledge interrupt 'irq' */
diff --git a/hw/ide.c b/hw/ide.c
index dc41982..d155bae 100644
--- a/hw/ide.c
+++ b/hw/ide.c
@@ -2942,7 +2942,7 @@ static void cmd646_update_irq(PCIIDEState *d)
}
/* the PCI irq level is the logical OR of the two channels */
-static void cmd646_set_irq(void *opaque, int channel, int level)
+static int cmd646_set_irq(void *opaque, int channel, int level)
{
PCIIDEState *d = opaque;
int irq_mask;
@@ -2953,6 +2953,8 @@ static void cmd646_set_irq(void *opaque, int channel, int level)
else
d->dev.config[MRDMODE] &= ~irq_mask;
cmd646_update_irq(d);
+
+ return 1;
}
/* CMD646 PCI IDE controller */
@@ -3345,7 +3347,7 @@ static inline void md_interrupt_update(struct md_s *s)
!(s->opt & OPT_SRESET));
}
-static void md_set_irq(void *opaque, int irq, int level)
+static int md_set_irq(void *opaque, int irq, int level)
{
struct md_s *s = (struct md_s *) opaque;
if (level)
@@ -3354,6 +3356,8 @@ static void md_set_irq(void *opaque, int irq, int level)
s->stat &= ~STAT_INT;
md_interrupt_update(s);
+
+ return 1;
}
static void md_reset(struct md_s *s)
diff --git a/hw/irq.c b/hw/irq.c
index eca707d..78ece4c 100644
--- a/hw/irq.c
+++ b/hw/irq.c
@@ -30,12 +30,12 @@ struct IRQState {
int n;
};
-void qemu_set_irq(qemu_irq irq, int level)
+int qemu_set_irq(qemu_irq irq, int level)
{
if (!irq)
- return;
+ return 1;
- irq->handler(irq->opaque, irq->n, level);
+ return irq->handler(irq->opaque, irq->n, level);
}
qemu_irq *qemu_allocate_irqs(qemu_irq_handler handler, void *opaque, int n)
@@ -56,11 +56,11 @@ qemu_irq *qemu_allocate_irqs(qemu_irq_handler handler, void *opaque, int n)
return s;
}
-static void qemu_notirq(void *opaque, int line, int level)
+static int qemu_notirq(void *opaque, int line, int level)
{
struct IRQState *irq = opaque;
- irq->handler(irq->opaque, irq->n, !level);
+ return irq->handler(irq->opaque, irq->n, !level);
}
qemu_irq qemu_irq_invert(qemu_irq irq)
diff --git a/hw/irq.h b/hw/irq.h
index 0880ad2..36abdae 100644
--- a/hw/irq.h
+++ b/hw/irq.h
@@ -4,25 +4,29 @@
/* Generic IRQ/GPIO pin infrastructure. */
/* FIXME: Rmove one of these. */
-typedef void (*qemu_irq_handler)(void *opaque, int n, int level);
-typedef void SetIRQFunc(void *opaque, int irq_num, int level);
+typedef int (*qemu_irq_handler)(void *opaque, int n, int level);
+typedef int SetIRQFunc(void *opaque, int irq_num, int level);
-void qemu_set_irq(qemu_irq irq, int level);
+int qemu_set_irq(qemu_irq irq, int level);
-static inline void qemu_irq_raise(qemu_irq irq)
+static inline int qemu_irq_raise(qemu_irq irq)
{
- qemu_set_irq(irq, 1);
+ return qemu_set_irq(irq, 1);
}
-static inline void qemu_irq_lower(qemu_irq irq)
+static inline int qemu_irq_lower(qemu_irq irq)
{
- qemu_set_irq(irq, 0);
+ return qemu_set_irq(irq, 0);
}
-static inline void qemu_irq_pulse(qemu_irq irq)
+static inline int qemu_irq_pulse(qemu_irq irq)
{
- qemu_set_irq(irq, 1);
+ int ret;
+
+ ret = qemu_set_irq(irq, 1);
qemu_set_irq(irq, 0);
+
+ return ret;
}
/* Returns an array of N IRQs. */
diff --git a/hw/max7310.c b/hw/max7310.c
index 397950a..6d498d5 100644
--- a/hw/max7310.c
+++ b/hw/max7310.c
@@ -179,7 +179,7 @@ static int max7310_load(QEMUFile *f, void *opaque, int version_id)
static int max7310_iid = 0;
-static void max7310_gpio_set(void *opaque, int line, int level)
+static int max7310_gpio_set(void *opaque, int line, int level)
{
struct max7310_s *s = (struct max7310_s *) opaque;
if (line >= sizeof(s->handler) / sizeof(*s->handler) || line < 0)
@@ -189,6 +189,8 @@ static void max7310_gpio_set(void *opaque, int line, int level)
s->level |= s->direction & (1 << line);
else
s->level &= ~(s->direction & (1 << line));
+
+ return 1;
}
/* MAX7310 is SMBus-compatible (can be used with only SMBus protocols),
diff --git a/hw/pc.c b/hw/pc.c
index 4c5e1c3..8e52041 100644
--- a/hw/pc.c
+++ b/hw/pc.c
@@ -114,18 +114,20 @@ int cpu_get_pic_interrupt(CPUState *env)
return intno;
}
-static void pic_irq_request(void *opaque, int irq, int level)
+static int pic_irq_request(void *opaque, int irq, int level)
{
CPUState *env = first_cpu;
if (!level)
- return;
+ return 1;
while (env) {
if (apic_accept_pic_intr(env))
apic_local_deliver(env, APIC_LINT0);
env = env->next_cpu;
}
+
+ return 1;
}
/* PC cmos mappings */
diff --git a/hw/pc.h b/hw/pc.h
index 0c98ff0..b789f98 100644
--- a/hw/pc.h
+++ b/hw/pc.h
@@ -47,7 +47,7 @@ int apic_accept_pic_intr(CPUState *env);
void apic_local_deliver(CPUState *env, int vector);
int apic_get_interrupt(CPUState *env);
IOAPICState *ioapic_init(void);
-void ioapic_set_irq(void *opaque, int vector, int level);
+int ioapic_set_irq(void *opaque, int vector, int level);
/* i8254.c */
diff --git a/hw/pci.c b/hw/pci.c
index bc55989..6d85ccb 100644
--- a/hw/pci.c
+++ b/hw/pci.c
@@ -47,7 +47,7 @@ struct PCIBus {
};
static void pci_update_mappings(PCIDevice *d);
-static void pci_set_irq(void *opaque, int irq_num, int level);
+static int pci_set_irq(void *opaque, int irq_num, int level);
target_phys_addr_t pci_mem_base;
static int pci_irq_index;
@@ -485,7 +485,7 @@ uint32_t pci_data_read(void *opaque, uint32_t addr, int len)
/* generic PCI irq support */
/* 0 <= irq_num <= 3. level must be 0 or 1 */
-static void pci_set_irq(void *opaque, int irq_num, int level)
+static int pci_set_irq(void *opaque, int irq_num, int level)
{
PCIDevice *pci_dev = (PCIDevice *)opaque;
PCIBus *bus;
@@ -493,7 +493,7 @@ static void pci_set_irq(void *opaque, int irq_num, int level)
change = level - pci_dev->irq_state[irq_num];
if (!change)
- return;
+ return 1;
pci_dev->irq_state[irq_num] = level;
for (;;) {
@@ -505,6 +505,8 @@ static void pci_set_irq(void *opaque, int irq_num, int level)
}
bus->irq_count[irq_num] += change;
bus->set_irq(bus->irq_opaque, irq_num, bus->irq_count[irq_num] != 0);
+
+ return 1;
}
/***********************************************************/
diff --git a/hw/ssd0323.c b/hw/ssd0323.c
index e2e619f..dc5eb88 100644
--- a/hw/ssd0323.c
+++ b/hw/ssd0323.c
@@ -265,11 +265,13 @@ static void ssd0323_invalidate_display(void * opaque)
}
/* Command/data input. */
-static void ssd0323_cd(void *opaque, int n, int level)
+static int ssd0323_cd(void *opaque, int n, int level)
{
ssd0323_state *s = (ssd0323_state *)opaque;
DPRINTF("%s mode\n", level ? "Data" : "Command");
s->mode = level ? SSD0323_DATA : SSD0323_CMD;
+
+ return 1;
}
void *ssd0323_init(DisplayState *ds, qemu_irq *cmd_p)
diff --git a/hw/twl92230.c b/hw/twl92230.c
index 8d0ce5d..6d49bea 100644
--- a/hw/twl92230.c
+++ b/hw/twl92230.c
@@ -195,16 +195,18 @@ static inline int from_bcd(uint8_t val)
return ((val >> 4) * 10) + (val & 0x0f);
}
-static void menelaus_gpio_set(void *opaque, int line, int level)
+static int menelaus_gpio_set(void *opaque, int line, int level)
{
struct menelaus_s *s = (struct menelaus_s *) opaque;
/* No interrupt generated */
s->inputs &= ~(1 << line);
s->inputs |= level << line;
+
+ return 1;
}
-static void menelaus_pwrbtn_set(void *opaque, int line, int level)
+static int menelaus_pwrbtn_set(void *opaque, int line, int level)
{
struct menelaus_s *s = (struct menelaus_s *) opaque;
@@ -213,6 +215,8 @@ static void menelaus_pwrbtn_set(void *opaque, int line, int level)
menelaus_update(s);
}
s->pwrbtn_state = level;
+
+ return 1;
}
#define MENELAUS_REV 0x01
^ permalink raw reply related [flat|nested] 29+ messages in thread
* [Qemu-devel] [PATCH 0/3] Fix guest time drift under heavy load.
@ 2008-06-29 14:02 Gleb Natapov
2008-06-29 14:02 ` [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information Gleb Natapov
` (3 more replies)
0 siblings, 4 replies; 29+ messages in thread
From: Gleb Natapov @ 2008-06-29 14:02 UTC (permalink / raw)
To: qemu-devel
Resending one more time. There was no response last time I've sent it.
Qemu device emulation for timers might be inaccurate and
causes coalescing of several IRQs into one. It happens when the
load on the host is high and the guest did not manage to ack the
previous IRQ. The first patch in the series fixes this by changing
qemu_irq subsystem to return IRQ delivery status information.
If device is notified that IRQs where lost it can regenerate them
as needed. The following two patches add IRQ regeneration to PIC and RTC
devices.
---
Gleb Natapov (3):
Fix time drift problem under high load when RTC is in use.
Fix time drift problem under high load when PIT is in use.
Change qemu_set_irq() to return status information.
hw/apic.c | 103 +++++++++++++++++++++++++++++++++++-------------------
hw/esp.c | 4 ++
hw/fdc.c | 4 ++
hw/i8254.c | 20 ++++++++++
hw/i8259.c | 19 +++++++---
hw/ide.c | 8 +++-
hw/irq.c | 10 +++--
hw/irq.h | 22 +++++++-----
hw/max7310.c | 4 ++
hw/mc146818rtc.c | 11 +++++-
hw/pc.c | 6 ++-
hw/pc.h | 2 +
hw/pci.c | 8 +++-
hw/ssd0323.c | 4 ++
hw/twl92230.c | 8 +++-
15 files changed, 159 insertions(+), 74 deletions(-)
--
Gleb.
^ permalink raw reply [flat|nested] 29+ messages in thread
* [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 14:02 [Qemu-devel] [PATCH 0/3] Fix guest time drift under heavy load Gleb Natapov
@ 2008-06-29 14:02 ` Gleb Natapov
2008-06-29 14:14 ` Avi Kivity
2008-06-29 14:38 ` Paul Brook
2008-06-29 14:02 ` [Qemu-devel] [PATCH 2/3] Fix time drift problem under high load when PIT is in use Gleb Natapov
` (2 subsequent siblings)
3 siblings, 2 replies; 29+ messages in thread
From: Gleb Natapov @ 2008-06-29 14:02 UTC (permalink / raw)
To: qemu-devel
The return value is less then zero if interrupt is masked, zero if it
is known that interrupt is lost (due to coalescing) or greater then zero
if interrupt is delivered or was successfully queued for delivery by
interrupt controller. Device emulation can use this info as it pleases.
Included patch adds detection of interrupt coalescing into PIC and APIC
code for edge triggered interrupts.
Signed-off-by: Gleb Natapov <gleb@qumranet.com>
---
hw/apic.c | 103 +++++++++++++++++++++++++++++++++++++--------------------
hw/esp.c | 4 ++
hw/fdc.c | 4 ++
hw/i8259.c | 19 +++++++----
hw/ide.c | 8 +++-
hw/irq.c | 10 +++---
hw/irq.h | 22 +++++++-----
hw/max7310.c | 4 ++
hw/pc.c | 6 ++-
hw/pc.h | 2 +
hw/pci.c | 8 +++-
hw/ssd0323.c | 4 ++
hw/twl92230.c | 8 +++-
13 files changed, 131 insertions(+), 71 deletions(-)
diff --git a/hw/apic.c b/hw/apic.c
index 6fd0160..9bdaed2 100644
--- a/hw/apic.c
+++ b/hw/apic.c
@@ -101,7 +101,7 @@ static APICState *local_apics[MAX_APICS + 1];
static int last_apic_id = 0;
static void apic_init_ipi(APICState *s);
-static void apic_set_irq(APICState *s, int vector_num, int trigger_mode);
+static int apic_set_irq(APICState *s, int vector_num, int trigger_mode);
static void apic_update_irq(APICState *s);
/* Find first bit starting from msb. Return 0 if value = 0 */
@@ -166,6 +166,14 @@ static inline void reset_bit(uint32_t *tab, int index)
tab[i] &= ~mask;
}
+static inline int get_bit(uint32_t *tab, int index)
+{
+ int i, mask;
+ i = index >> 5;
+ mask = 1 << (index & 0x1f);
+ return !!(tab[i] & mask);
+}
+
void apic_local_deliver(CPUState *env, int vector)
{
APICState *s = env->apic_state;
@@ -215,12 +223,13 @@ void apic_local_deliver(CPUState *env, int vector)
}\
}
-static void apic_bus_deliver(const uint32_t *deliver_bitmask,
+static int apic_bus_deliver(const uint32_t *deliver_bitmask,
uint8_t delivery_mode,
uint8_t vector_num, uint8_t polarity,
uint8_t trigger_mode)
{
APICState *apic_iter;
+ int ret = 0;
switch (delivery_mode) {
case APIC_DM_LOWPRI:
@@ -237,11 +246,12 @@ static void apic_bus_deliver(const uint32_t *deliver_bitmask,
if (d >= 0) {
apic_iter = local_apics[d];
if (apic_iter) {
- apic_set_irq(apic_iter, vector_num, trigger_mode);
+ ret = apic_set_irq(apic_iter, vector_num, trigger_mode);
}
- }
+ } else
+ ret = 1;
}
- return;
+ return ret;
case APIC_DM_FIXED:
break;
@@ -249,29 +259,33 @@ static void apic_bus_deliver(const uint32_t *deliver_bitmask,
case APIC_DM_SMI:
foreach_apic(apic_iter, deliver_bitmask,
cpu_interrupt(apic_iter->cpu_env, CPU_INTERRUPT_SMI) );
- return;
+ return 1;
case APIC_DM_NMI:
foreach_apic(apic_iter, deliver_bitmask,
cpu_interrupt(apic_iter->cpu_env, CPU_INTERRUPT_NMI) );
- return;
+ return 1;
case APIC_DM_INIT:
/* normal INIT IPI sent to processors */
foreach_apic(apic_iter, deliver_bitmask,
apic_init_ipi(apic_iter) );
- return;
+ return 1;
case APIC_DM_EXTINT:
/* handled in I/O APIC code */
break;
default:
- return;
+ return ret;
}
+ /* if interrupt should be delivered to more then one apic report it as
+ * delivered if at least one apic accepts it */
foreach_apic(apic_iter, deliver_bitmask,
- apic_set_irq(apic_iter, vector_num, trigger_mode) );
+ ret += apic_set_irq(apic_iter, vector_num, trigger_mode) );
+
+ return ret;
}
void cpu_set_apic_base(CPUState *env, uint64_t val)
@@ -361,14 +375,18 @@ static void apic_update_irq(APICState *s)
cpu_interrupt(s->cpu_env, CPU_INTERRUPT_HARD);
}
-static void apic_set_irq(APICState *s, int vector_num, int trigger_mode)
+static int apic_set_irq(APICState *s, int vector_num, int trigger_mode)
{
+ int ret = !get_bit(s->irr, vector_num);
+
set_bit(s->irr, vector_num);
if (trigger_mode)
set_bit(s->tmr, vector_num);
else
reset_bit(s->tmr, vector_num);
apic_update_irq(s);
+
+ return ret;
}
static void apic_eoi(APICState *s)
@@ -906,9 +924,8 @@ int apic_init(CPUState *env)
return 0;
}
-static void ioapic_service(IOAPICState *s)
+static int ioapic_service_one(IOAPICState *s, uint8_t pin)
{
- uint8_t i;
uint8_t trig_mode;
uint8_t vector;
uint8_t delivery_mode;
@@ -919,34 +936,44 @@ static void ioapic_service(IOAPICState *s)
uint8_t polarity;
uint32_t deliver_bitmask[MAX_APIC_WORDS];
+ mask = 1 << pin;
+ if (!(s->irr & mask))
+ return 1;
+
+ entry = s->ioredtbl[pin];
+ if ((entry & APIC_LVT_MASKED))
+ return -1;
+
+ trig_mode = ((entry >> 15) & 1);
+ dest = entry >> 56;
+ dest_mode = (entry >> 11) & 1;
+ delivery_mode = (entry >> 8) & 7;
+ polarity = (entry >> 13) & 1;
+ if (trig_mode == APIC_TRIGGER_EDGE)
+ s->irr &= ~mask;
+ if (delivery_mode == APIC_DM_EXTINT)
+ vector = pic_read_irq(isa_pic);
+ else
+ vector = entry & 0xff;
+
+ apic_get_delivery_bitmask(deliver_bitmask, dest, dest_mode);
+ return apic_bus_deliver(deliver_bitmask, delivery_mode, vector, polarity,
+ trig_mode);
+}
+
+static void ioapic_service(IOAPICState *s)
+{
+ uint8_t i;
+
for (i = 0; i < IOAPIC_NUM_PINS; i++) {
- mask = 1 << i;
- if (s->irr & mask) {
- entry = s->ioredtbl[i];
- if (!(entry & APIC_LVT_MASKED)) {
- trig_mode = ((entry >> 15) & 1);
- dest = entry >> 56;
- dest_mode = (entry >> 11) & 1;
- delivery_mode = (entry >> 8) & 7;
- polarity = (entry >> 13) & 1;
- if (trig_mode == APIC_TRIGGER_EDGE)
- s->irr &= ~mask;
- if (delivery_mode == APIC_DM_EXTINT)
- vector = pic_read_irq(isa_pic);
- else
- vector = entry & 0xff;
-
- apic_get_delivery_bitmask(deliver_bitmask, dest, dest_mode);
- apic_bus_deliver(deliver_bitmask, delivery_mode,
- vector, polarity, trig_mode);
- }
- }
+ ioapic_service_one(s, i);
}
}
-void ioapic_set_irq(void *opaque, int vector, int level)
+int ioapic_set_irq(void *opaque, int vector, int level)
{
IOAPICState *s = opaque;
+ int ret = 1;
if (vector >= 0 && vector < IOAPIC_NUM_PINS) {
uint32_t mask = 1 << vector;
@@ -956,7 +983,7 @@ void ioapic_set_irq(void *opaque, int vector, int level)
/* level triggered */
if (level) {
s->irr |= mask;
- ioapic_service(s);
+ ioapic_service_one(s, vector);
} else {
s->irr &= ~mask;
}
@@ -964,10 +991,12 @@ void ioapic_set_irq(void *opaque, int vector, int level)
/* edge triggered */
if (level) {
s->irr |= mask;
- ioapic_service(s);
+ ret = ioapic_service_one(s, vector);
}
}
}
+
+ return ret;
}
static uint32_t ioapic_mem_readl(void *opaque, target_phys_addr_t addr)
diff --git a/hw/esp.c b/hw/esp.c
index 1843fb8..aa5e546 100644
--- a/hw/esp.c
+++ b/hw/esp.c
@@ -409,10 +409,12 @@ static void esp_reset(void *opaque)
s->do_cmd = 0;
}
-static void parent_esp_reset(void *opaque, int irq, int level)
+static int parent_esp_reset(void *opaque, int irq, int level)
{
if (level)
esp_reset(opaque);
+
+ return 1;
}
static uint32_t esp_mem_readb(void *opaque, target_phys_addr_t addr)
diff --git a/hw/fdc.c b/hw/fdc.c
index cd00420..b212d89 100644
--- a/hw/fdc.c
+++ b/hw/fdc.c
@@ -713,7 +713,7 @@ static void fdctrl_external_reset(void *opaque)
fdctrl_reset(s, 0);
}
-static void fdctrl_handle_tc(void *opaque, int irq, int level)
+static int fdctrl_handle_tc(void *opaque, int irq, int level)
{
//fdctrl_t *s = opaque;
@@ -721,6 +721,8 @@ static void fdctrl_handle_tc(void *opaque, int irq, int level)
// XXX
FLOPPY_DPRINTF("TC pulsed\n");
}
+
+ return 1;
}
/* XXX: may change if moved to bdrv */
diff --git a/hw/i8259.c b/hw/i8259.c
index add6345..ab7eb2d 100644
--- a/hw/i8259.c
+++ b/hw/i8259.c
@@ -72,9 +72,9 @@ static uint64_t irq_count[16];
#endif
/* set irq level. If an edge is detected, then the IRR is set to 1 */
-static inline void pic_set_irq1(PicState *s, int irq, int level)
+static inline int pic_set_irq1(PicState *s, int irq, int level)
{
- int mask;
+ int mask, ret = 1;
mask = 1 << irq;
if (s->elcr & mask) {
/* level triggered */
@@ -88,13 +88,18 @@ static inline void pic_set_irq1(PicState *s, int irq, int level)
} else {
/* edge triggered */
if (level) {
- if ((s->last_irr & mask) == 0)
+ if ((s->last_irr & mask) == 0) {
+ if((s->irr & mask))
+ ret = 0;
s->irr |= mask;
+ }
s->last_irr |= mask;
} else {
s->last_irr &= ~mask;
}
}
+
+ return (s->imr & mask) ? -1 : ret;
}
/* return the highest priority found in mask (highest = smallest
@@ -178,9 +183,10 @@ void pic_update_irq(PicState2 *s)
int64_t irq_time[16];
#endif
-static void i8259_set_irq(void *opaque, int irq, int level)
+static int i8259_set_irq(void *opaque, int irq, int level)
{
PicState2 *s = opaque;
+ int pic_ret, ioapic_ret;
#if defined(DEBUG_PIC) || defined(DEBUG_IRQ_COUNT)
if (level != irq_level[irq]) {
@@ -199,11 +205,12 @@ static void i8259_set_irq(void *opaque, int irq, int level)
irq_time[irq] = qemu_get_clock(vm_clock);
}
#endif
- pic_set_irq1(&s->pics[irq >> 3], irq & 7, level);
+ pic_ret = pic_set_irq1(&s->pics[irq >> 3], irq & 7, level);
/* used for IOAPIC irqs */
if (s->alt_irq_func)
- s->alt_irq_func(s->alt_irq_opaque, irq, level);
+ ioapic_ret = s->alt_irq_func(s->alt_irq_opaque, irq, level);
pic_update_irq(s);
+ return MAX(pic_ret, ioapic_ret);
}
/* acknowledge interrupt 'irq' */
diff --git a/hw/ide.c b/hw/ide.c
index dc41982..d155bae 100644
--- a/hw/ide.c
+++ b/hw/ide.c
@@ -2942,7 +2942,7 @@ static void cmd646_update_irq(PCIIDEState *d)
}
/* the PCI irq level is the logical OR of the two channels */
-static void cmd646_set_irq(void *opaque, int channel, int level)
+static int cmd646_set_irq(void *opaque, int channel, int level)
{
PCIIDEState *d = opaque;
int irq_mask;
@@ -2953,6 +2953,8 @@ static void cmd646_set_irq(void *opaque, int channel, int level)
else
d->dev.config[MRDMODE] &= ~irq_mask;
cmd646_update_irq(d);
+
+ return 1;
}
/* CMD646 PCI IDE controller */
@@ -3345,7 +3347,7 @@ static inline void md_interrupt_update(struct md_s *s)
!(s->opt & OPT_SRESET));
}
-static void md_set_irq(void *opaque, int irq, int level)
+static int md_set_irq(void *opaque, int irq, int level)
{
struct md_s *s = (struct md_s *) opaque;
if (level)
@@ -3354,6 +3356,8 @@ static void md_set_irq(void *opaque, int irq, int level)
s->stat &= ~STAT_INT;
md_interrupt_update(s);
+
+ return 1;
}
static void md_reset(struct md_s *s)
diff --git a/hw/irq.c b/hw/irq.c
index eca707d..78ece4c 100644
--- a/hw/irq.c
+++ b/hw/irq.c
@@ -30,12 +30,12 @@ struct IRQState {
int n;
};
-void qemu_set_irq(qemu_irq irq, int level)
+int qemu_set_irq(qemu_irq irq, int level)
{
if (!irq)
- return;
+ return 1;
- irq->handler(irq->opaque, irq->n, level);
+ return irq->handler(irq->opaque, irq->n, level);
}
qemu_irq *qemu_allocate_irqs(qemu_irq_handler handler, void *opaque, int n)
@@ -56,11 +56,11 @@ qemu_irq *qemu_allocate_irqs(qemu_irq_handler handler, void *opaque, int n)
return s;
}
-static void qemu_notirq(void *opaque, int line, int level)
+static int qemu_notirq(void *opaque, int line, int level)
{
struct IRQState *irq = opaque;
- irq->handler(irq->opaque, irq->n, !level);
+ return irq->handler(irq->opaque, irq->n, !level);
}
qemu_irq qemu_irq_invert(qemu_irq irq)
diff --git a/hw/irq.h b/hw/irq.h
index 0880ad2..36abdae 100644
--- a/hw/irq.h
+++ b/hw/irq.h
@@ -4,25 +4,29 @@
/* Generic IRQ/GPIO pin infrastructure. */
/* FIXME: Rmove one of these. */
-typedef void (*qemu_irq_handler)(void *opaque, int n, int level);
-typedef void SetIRQFunc(void *opaque, int irq_num, int level);
+typedef int (*qemu_irq_handler)(void *opaque, int n, int level);
+typedef int SetIRQFunc(void *opaque, int irq_num, int level);
-void qemu_set_irq(qemu_irq irq, int level);
+int qemu_set_irq(qemu_irq irq, int level);
-static inline void qemu_irq_raise(qemu_irq irq)
+static inline int qemu_irq_raise(qemu_irq irq)
{
- qemu_set_irq(irq, 1);
+ return qemu_set_irq(irq, 1);
}
-static inline void qemu_irq_lower(qemu_irq irq)
+static inline int qemu_irq_lower(qemu_irq irq)
{
- qemu_set_irq(irq, 0);
+ return qemu_set_irq(irq, 0);
}
-static inline void qemu_irq_pulse(qemu_irq irq)
+static inline int qemu_irq_pulse(qemu_irq irq)
{
- qemu_set_irq(irq, 1);
+ int ret;
+
+ ret = qemu_set_irq(irq, 1);
qemu_set_irq(irq, 0);
+
+ return ret;
}
/* Returns an array of N IRQs. */
diff --git a/hw/max7310.c b/hw/max7310.c
index 397950a..6d498d5 100644
--- a/hw/max7310.c
+++ b/hw/max7310.c
@@ -179,7 +179,7 @@ static int max7310_load(QEMUFile *f, void *opaque, int version_id)
static int max7310_iid = 0;
-static void max7310_gpio_set(void *opaque, int line, int level)
+static int max7310_gpio_set(void *opaque, int line, int level)
{
struct max7310_s *s = (struct max7310_s *) opaque;
if (line >= sizeof(s->handler) / sizeof(*s->handler) || line < 0)
@@ -189,6 +189,8 @@ static void max7310_gpio_set(void *opaque, int line, int level)
s->level |= s->direction & (1 << line);
else
s->level &= ~(s->direction & (1 << line));
+
+ return 1;
}
/* MAX7310 is SMBus-compatible (can be used with only SMBus protocols),
diff --git a/hw/pc.c b/hw/pc.c
index 4c5e1c3..8e52041 100644
--- a/hw/pc.c
+++ b/hw/pc.c
@@ -114,18 +114,20 @@ int cpu_get_pic_interrupt(CPUState *env)
return intno;
}
-static void pic_irq_request(void *opaque, int irq, int level)
+static int pic_irq_request(void *opaque, int irq, int level)
{
CPUState *env = first_cpu;
if (!level)
- return;
+ return 1;
while (env) {
if (apic_accept_pic_intr(env))
apic_local_deliver(env, APIC_LINT0);
env = env->next_cpu;
}
+
+ return 1;
}
/* PC cmos mappings */
diff --git a/hw/pc.h b/hw/pc.h
index 0c98ff0..b789f98 100644
--- a/hw/pc.h
+++ b/hw/pc.h
@@ -47,7 +47,7 @@ int apic_accept_pic_intr(CPUState *env);
void apic_local_deliver(CPUState *env, int vector);
int apic_get_interrupt(CPUState *env);
IOAPICState *ioapic_init(void);
-void ioapic_set_irq(void *opaque, int vector, int level);
+int ioapic_set_irq(void *opaque, int vector, int level);
/* i8254.c */
diff --git a/hw/pci.c b/hw/pci.c
index bc55989..6d85ccb 100644
--- a/hw/pci.c
+++ b/hw/pci.c
@@ -47,7 +47,7 @@ struct PCIBus {
};
static void pci_update_mappings(PCIDevice *d);
-static void pci_set_irq(void *opaque, int irq_num, int level);
+static int pci_set_irq(void *opaque, int irq_num, int level);
target_phys_addr_t pci_mem_base;
static int pci_irq_index;
@@ -485,7 +485,7 @@ uint32_t pci_data_read(void *opaque, uint32_t addr, int len)
/* generic PCI irq support */
/* 0 <= irq_num <= 3. level must be 0 or 1 */
-static void pci_set_irq(void *opaque, int irq_num, int level)
+static int pci_set_irq(void *opaque, int irq_num, int level)
{
PCIDevice *pci_dev = (PCIDevice *)opaque;
PCIBus *bus;
@@ -493,7 +493,7 @@ static void pci_set_irq(void *opaque, int irq_num, int level)
change = level - pci_dev->irq_state[irq_num];
if (!change)
- return;
+ return 1;
pci_dev->irq_state[irq_num] = level;
for (;;) {
@@ -505,6 +505,8 @@ static void pci_set_irq(void *opaque, int irq_num, int level)
}
bus->irq_count[irq_num] += change;
bus->set_irq(bus->irq_opaque, irq_num, bus->irq_count[irq_num] != 0);
+
+ return 1;
}
/***********************************************************/
diff --git a/hw/ssd0323.c b/hw/ssd0323.c
index e2e619f..dc5eb88 100644
--- a/hw/ssd0323.c
+++ b/hw/ssd0323.c
@@ -265,11 +265,13 @@ static void ssd0323_invalidate_display(void * opaque)
}
/* Command/data input. */
-static void ssd0323_cd(void *opaque, int n, int level)
+static int ssd0323_cd(void *opaque, int n, int level)
{
ssd0323_state *s = (ssd0323_state *)opaque;
DPRINTF("%s mode\n", level ? "Data" : "Command");
s->mode = level ? SSD0323_DATA : SSD0323_CMD;
+
+ return 1;
}
void *ssd0323_init(DisplayState *ds, qemu_irq *cmd_p)
diff --git a/hw/twl92230.c b/hw/twl92230.c
index 8d0ce5d..6d49bea 100644
--- a/hw/twl92230.c
+++ b/hw/twl92230.c
@@ -195,16 +195,18 @@ static inline int from_bcd(uint8_t val)
return ((val >> 4) * 10) + (val & 0x0f);
}
-static void menelaus_gpio_set(void *opaque, int line, int level)
+static int menelaus_gpio_set(void *opaque, int line, int level)
{
struct menelaus_s *s = (struct menelaus_s *) opaque;
/* No interrupt generated */
s->inputs &= ~(1 << line);
s->inputs |= level << line;
+
+ return 1;
}
-static void menelaus_pwrbtn_set(void *opaque, int line, int level)
+static int menelaus_pwrbtn_set(void *opaque, int line, int level)
{
struct menelaus_s *s = (struct menelaus_s *) opaque;
@@ -213,6 +215,8 @@ static void menelaus_pwrbtn_set(void *opaque, int line, int level)
menelaus_update(s);
}
s->pwrbtn_state = level;
+
+ return 1;
}
#define MENELAUS_REV 0x01
^ permalink raw reply related [flat|nested] 29+ messages in thread
* [Qemu-devel] [PATCH 2/3] Fix time drift problem under high load when PIT is in use.
2008-06-29 14:02 [Qemu-devel] [PATCH 0/3] Fix guest time drift under heavy load Gleb Natapov
2008-06-29 14:02 ` [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information Gleb Natapov
@ 2008-06-29 14:02 ` Gleb Natapov
2008-06-29 14:40 ` [Qemu-devel] " Jan Kiszka
2008-06-29 14:02 ` [Qemu-devel] [PATCH 3/3] Fix time drift problem under high load when RTC " Gleb Natapov
2008-06-29 14:37 ` [Qemu-devel] Re: [PATCH 0/3] Fix guest time drift under heavy load Jan Kiszka
3 siblings, 1 reply; 29+ messages in thread
From: Gleb Natapov @ 2008-06-29 14:02 UTC (permalink / raw)
To: qemu-devel
Count the number of interrupts that was lost due to interrupt coalescing
and re-inject them back when possible. This fixes time drift problem when
pit is used as a time source.
Signed-off-by: Gleb Natapov <gleb@qumranet.com>
---
hw/i8254.c | 20 +++++++++++++++++++-
1 files changed, 19 insertions(+), 1 deletions(-)
diff --git a/hw/i8254.c b/hw/i8254.c
index 4813b03..c4f0f46 100644
--- a/hw/i8254.c
+++ b/hw/i8254.c
@@ -61,6 +61,8 @@ static PITState pit_state;
static void pit_irq_timer_update(PITChannelState *s, int64_t current_time);
+static uint32_t pit_irq_coalesced;
+
static int pit_get_count(PITChannelState *s)
{
uint64_t d;
@@ -369,12 +371,28 @@ static void pit_irq_timer_update(PITChannelState *s, int64_t current_time)
return;
expire_time = pit_get_next_transition_time(s, current_time);
irq_level = pit_get_out1(s, current_time);
- qemu_set_irq(s->irq, irq_level);
+ if(irq_level) {
+ if(!qemu_irq_raise(s->irq))
+ pit_irq_coalesced++;
+ } else {
+ qemu_irq_lower(s->irq);
+ if(pit_irq_coalesced > 0) {
+ if(qemu_irq_raise(s->irq))
+ pit_irq_coalesced--;
+ qemu_irq_lower(s->irq);
+ }
+ }
+
#ifdef DEBUG_PIT
printf("irq_level=%d next_delay=%f\n",
irq_level,
(double)(expire_time - current_time) / ticks_per_sec);
#endif
+ if(pit_irq_coalesced && expire_time != -1) {
+ uint32_t div = ((pit_irq_coalesced >> 10) & 0x7f) + 2;
+ expire_time -= ((expire_time - current_time) / div);
+ }
+
s->next_transition_time = expire_time;
if (expire_time != -1)
qemu_mod_timer(s->irq_timer, expire_time);
^ permalink raw reply related [flat|nested] 29+ messages in thread
* [Qemu-devel] [PATCH 3/3] Fix time drift problem under high load when RTC is in use.
2008-06-29 14:02 [Qemu-devel] [PATCH 0/3] Fix guest time drift under heavy load Gleb Natapov
2008-06-29 14:02 ` [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information Gleb Natapov
2008-06-29 14:02 ` [Qemu-devel] [PATCH 2/3] Fix time drift problem under high load when PIT is in use Gleb Natapov
@ 2008-06-29 14:02 ` Gleb Natapov
2008-06-29 14:37 ` [Qemu-devel] Re: [PATCH 0/3] Fix guest time drift under heavy load Jan Kiszka
3 siblings, 0 replies; 29+ messages in thread
From: Gleb Natapov @ 2008-06-29 14:02 UTC (permalink / raw)
To: qemu-devel
Count the number of interrupts that was lost due to interrupt coalescing
and re-inject them back when possible. This fixes time drift problem when
RTC is used as a time source.
Signed-off-by: Gleb Natapov <gleb@qumranet.com>
---
hw/mc146818rtc.c | 11 +++++++++--
1 files changed, 9 insertions(+), 2 deletions(-)
diff --git a/hw/mc146818rtc.c b/hw/mc146818rtc.c
index 30bb044..64e4c11 100644
--- a/hw/mc146818rtc.c
+++ b/hw/mc146818rtc.c
@@ -72,6 +72,7 @@ struct RTCState {
static void rtc_set_time(RTCState *s);
static void rtc_copy_date(RTCState *s);
+static uint32_t rtc_irq_coalesced;
static void rtc_timer_update(RTCState *s, int64_t current_time)
{
@@ -101,7 +102,8 @@ static void rtc_periodic_timer(void *opaque)
rtc_timer_update(s, s->next_periodic_time);
s->cmos_data[RTC_REG_C] |= 0xc0;
- qemu_irq_raise(s->irq);
+ if(!qemu_irq_raise(s->irq))
+ rtc_irq_coalesced++;
}
static void cmos_ioport_write(void *opaque, uint32_t addr, uint32_t data)
@@ -360,7 +362,12 @@ static uint32_t cmos_ioport_read(void *opaque, uint32_t addr)
case RTC_REG_C:
ret = s->cmos_data[s->cmos_index];
qemu_irq_lower(s->irq);
- s->cmos_data[RTC_REG_C] = 0x00;
+ if(!rtc_irq_coalesced) {
+ s->cmos_data[RTC_REG_C] = 0x00;
+ } else {
+ if(qemu_irq_raise(s->irq))
+ rtc_irq_coalesced--;
+ }
break;
default:
ret = s->cmos_data[s->cmos_index];
^ permalink raw reply related [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 14:02 ` [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information Gleb Natapov
@ 2008-06-29 14:14 ` Avi Kivity
2008-06-29 14:18 ` Gleb Natapov
2008-06-29 14:38 ` Paul Brook
1 sibling, 1 reply; 29+ messages in thread
From: Avi Kivity @ 2008-06-29 14:14 UTC (permalink / raw)
To: gleb; +Cc: qemu-devel
Gleb Natapov wrote:
> The return value is less then zero if interrupt is masked, zero if it
> is known that interrupt is lost (due to coalescing) or greater then zero
> if interrupt is delivered or was successfully queued for delivery by
> interrupt controller. Device emulation can use this info as it pleases.
> Included patch adds detection of interrupt coalescing into PIC and APIC
> code for edge triggered interrupts.
>
Instead of negative/positive/zero, consider returning an enum for
readability.
--
error compiling committee.c: too many arguments to function
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 14:14 ` Avi Kivity
@ 2008-06-29 14:18 ` Gleb Natapov
2008-06-29 14:53 ` Paul Brook
0 siblings, 1 reply; 29+ messages in thread
From: Gleb Natapov @ 2008-06-29 14:18 UTC (permalink / raw)
To: Avi Kivity; +Cc: qemu-devel
On Sun, Jun 29, 2008 at 05:14:01PM +0300, Avi Kivity wrote:
> Gleb Natapov wrote:
>> The return value is less then zero if interrupt is masked, zero if it
>> is known that interrupt is lost (due to coalescing) or greater then zero
>> if interrupt is delivered or was successfully queued for delivery by
>> interrupt controller. Device emulation can use this info as it pleases.
>> Included patch adds detection of interrupt coalescing into PIC and APIC
>> code for edge triggered interrupts.
>>
>
> Instead of negative/positive/zero, consider returning an enum for
> readability.
>
I thought about that, but I sometimes do arithmetics on those values
(when delivering interrupt to multiple CPUs), so result can be more then
1 sometimes.
--
Gleb.
^ permalink raw reply [flat|nested] 29+ messages in thread
* [Qemu-devel] Re: [PATCH 0/3] Fix guest time drift under heavy load.
2008-06-29 14:02 [Qemu-devel] [PATCH 0/3] Fix guest time drift under heavy load Gleb Natapov
` (2 preceding siblings ...)
2008-06-29 14:02 ` [Qemu-devel] [PATCH 3/3] Fix time drift problem under high load when RTC " Gleb Natapov
@ 2008-06-29 14:37 ` Jan Kiszka
3 siblings, 0 replies; 29+ messages in thread
From: Jan Kiszka @ 2008-06-29 14:37 UTC (permalink / raw)
To: qemu-devel
[-- Attachment #1: Type: text/plain, Size: 834 bytes --]
Gleb Natapov wrote:
> Resending one more time. There was no response last time I've sent it.
>
> Qemu device emulation for timers might be inaccurate and
> causes coalescing of several IRQs into one. It happens when the
> load on the host is high and the guest did not manage to ack the
> previous IRQ. The first patch in the series fixes this by changing
> qemu_irq subsystem to return IRQ delivery status information.
> If device is notified that IRQs where lost it can regenerate them
> as needed. The following two patches add IRQ regeneration to PIC and RTC
> devices.
s/PIC/PIT. :)
I must have overslept the first posting. In fact, we are currently
discussing such measures for our scenario as well - we are also
suffering from lost PIT IRQs. So I will definitely give your series a
try next week!
Jan
[-- Attachment #2: OpenPGP digital signature --]
[-- Type: application/pgp-signature, Size: 257 bytes --]
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 14:02 ` [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information Gleb Natapov
2008-06-29 14:14 ` Avi Kivity
@ 2008-06-29 14:38 ` Paul Brook
2008-06-29 15:40 ` Gleb Natapov
1 sibling, 1 reply; 29+ messages in thread
From: Paul Brook @ 2008-06-29 14:38 UTC (permalink / raw)
To: qemu-devel; +Cc: Gleb Natapov
On Sunday 29 June 2008, Gleb Natapov wrote:
> The return value is less then zero if interrupt is masked, zero if it
> is known that interrupt is lost (due to coalescing) or greater then zero
> if interrupt is delivered or was successfully queued for delivery by
> interrupt controller. Device emulation can use this info as it pleases.
> Included patch adds detection of interrupt coalescing into PIC and APIC
> code for edge triggered interrupts.
This is woefully incomplete, and obviously hasn't been tested on anything
other than x86 targets.
Paul
^ permalink raw reply [flat|nested] 29+ messages in thread
* [Qemu-devel] Re: [PATCH 2/3] Fix time drift problem under high load when PIT is in use.
2008-06-29 14:02 ` [Qemu-devel] [PATCH 2/3] Fix time drift problem under high load when PIT is in use Gleb Natapov
@ 2008-06-29 14:40 ` Jan Kiszka
2008-06-29 15:52 ` Gleb Natapov
0 siblings, 1 reply; 29+ messages in thread
From: Jan Kiszka @ 2008-06-29 14:40 UTC (permalink / raw)
To: qemu-devel
[-- Attachment #1: Type: text/plain, Size: 2262 bytes --]
Gleb Natapov wrote:
> Count the number of interrupts that was lost due to interrupt coalescing
> and re-inject them back when possible. This fixes time drift problem when
> pit is used as a time source.
>
> Signed-off-by: Gleb Natapov <gleb@qumranet.com>
> ---
>
> hw/i8254.c | 20 +++++++++++++++++++-
> 1 files changed, 19 insertions(+), 1 deletions(-)
>
> diff --git a/hw/i8254.c b/hw/i8254.c
> index 4813b03..c4f0f46 100644
> --- a/hw/i8254.c
> +++ b/hw/i8254.c
> @@ -61,6 +61,8 @@ static PITState pit_state;
>
> static void pit_irq_timer_update(PITChannelState *s, int64_t current_time);
>
> +static uint32_t pit_irq_coalesced;
> +
> static int pit_get_count(PITChannelState *s)
> {
> uint64_t d;
> @@ -369,12 +371,28 @@ static void pit_irq_timer_update(PITChannelState *s, int64_t current_time)
> return;
> expire_time = pit_get_next_transition_time(s, current_time);
> irq_level = pit_get_out1(s, current_time);
> - qemu_set_irq(s->irq, irq_level);
> + if(irq_level) {
> + if(!qemu_irq_raise(s->irq))
> + pit_irq_coalesced++;
> + } else {
> + qemu_irq_lower(s->irq);
> + if(pit_irq_coalesced > 0) {
> + if(qemu_irq_raise(s->irq))
> + pit_irq_coalesced--;
> + qemu_irq_lower(s->irq);
> + }
> + }
That's graspable for my poor brain: reinject one coalesced IRQ right
after the falling edge of an in-time delivery...
> +
> #ifdef DEBUG_PIT
> printf("irq_level=%d next_delay=%f\n",
> irq_level,
> (double)(expire_time - current_time) / ticks_per_sec);
> #endif
> + if(pit_irq_coalesced && expire_time != -1) {
> + uint32_t div = ((pit_irq_coalesced >> 10) & 0x7f) + 2;
> + expire_time -= ((expire_time - current_time) / div);
> + }
> +
... but could you comment on this algorithm? I think I got what it does:
splitting up the next regular period in short intervals. But there are a
bit too many magic numbers involved. Where do they come from? What
happens if pit_irq_coalesced becomes large (or: how large can it become
without risking an IRQ storm on the guest)? A few comments would help, I
guess.
Thanks,
Jan
[-- Attachment #2: OpenPGP digital signature --]
[-- Type: application/pgp-signature, Size: 257 bytes --]
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 14:18 ` Gleb Natapov
@ 2008-06-29 14:53 ` Paul Brook
2008-06-29 15:37 ` Gleb Natapov
0 siblings, 1 reply; 29+ messages in thread
From: Paul Brook @ 2008-06-29 14:53 UTC (permalink / raw)
To: qemu-devel; +Cc: Gleb Natapov
> >> The return value is less then zero if interrupt is masked, zero if it
> >> is known that interrupt is lost (due to coalescing) or greater then zero
> >> if interrupt is delivered or was successfully queued for delivery by
> >> interrupt controller. Device emulation can use this info as it pleases.
> >> Included patch adds detection of interrupt coalescing into PIC and APIC
> >> code for edge triggered interrupts.
> >
> > Instead of negative/positive/zero, consider returning an enum for
> > readability.
>
> I thought about that, but I sometimes do arithmetics on those values
> (when delivering interrupt to multiple CPUs), so result can be more then
> 1 sometimes.
At minimum you need to document the meaning of these values. Especially as
you've now given two contradictory definitions - "greater than zero" isn't
something you can do arithmetic with. If you require -1/0/+1 then you have to
say that.
Paul
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 14:53 ` Paul Brook
@ 2008-06-29 15:37 ` Gleb Natapov
0 siblings, 0 replies; 29+ messages in thread
From: Gleb Natapov @ 2008-06-29 15:37 UTC (permalink / raw)
To: Paul Brook; +Cc: qemu-devel
On Sun, Jun 29, 2008 at 03:53:55PM +0100, Paul Brook wrote:
> > >> The return value is less then zero if interrupt is masked, zero if it
> > >> is known that interrupt is lost (due to coalescing) or greater then zero
> > >> if interrupt is delivered or was successfully queued for delivery by
> > >> interrupt controller. Device emulation can use this info as it pleases.
> > >> Included patch adds detection of interrupt coalescing into PIC and APIC
> > >> code for edge triggered interrupts.
> > >
> > > Instead of negative/positive/zero, consider returning an enum for
> > > readability.
> >
> > I thought about that, but I sometimes do arithmetics on those values
> > (when delivering interrupt to multiple CPUs), so result can be more then
> > 1 sometimes.
>
> At minimum you need to document the meaning of these values. Especially as
> you've now given two contradictory definitions - "greater than zero" isn't
> something you can do arithmetic with. If you require -1/0/+1 then you have to
> say that.
In only place I do arithmetic on those values it is guarantied that the value
is either zero (cpu lost interrupt) or one (cpu received interrupt), so the sum
of those values make sense. If it greater then zero at least one processor will
process an interrupt. I will document the return value in a comment in the
next version of the patch.
--
Gleb.
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 14:38 ` Paul Brook
@ 2008-06-29 15:40 ` Gleb Natapov
2008-06-29 18:11 ` Paul Brook
0 siblings, 1 reply; 29+ messages in thread
From: Gleb Natapov @ 2008-06-29 15:40 UTC (permalink / raw)
To: Paul Brook; +Cc: qemu-devel
On Sun, Jun 29, 2008 at 03:38:10PM +0100, Paul Brook wrote:
> On Sunday 29 June 2008, Gleb Natapov wrote:
> > The return value is less then zero if interrupt is masked, zero if it
> > is known that interrupt is lost (due to coalescing) or greater then zero
> > if interrupt is delivered or was successfully queued for delivery by
> > interrupt controller. Device emulation can use this info as it pleases.
> > Included patch adds detection of interrupt coalescing into PIC and APIC
> > code for edge triggered interrupts.
>
> This is woefully incomplete, and obviously hasn't been tested on anything
> other than x86 targets.
>
Yes, you are right. It was not tested on anything other than x86. Do you
see why this approach will not work on other architectures? Can you
elaborate on what current patch is missing for other architectures
support? The initial goal is to fix RTC/PIT problem on x86 while do not
hurt any other architectures in any way.
--
Gleb.
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] Re: [PATCH 2/3] Fix time drift problem under high load when PIT is in use.
2008-06-29 14:40 ` [Qemu-devel] " Jan Kiszka
@ 2008-06-29 15:52 ` Gleb Natapov
0 siblings, 0 replies; 29+ messages in thread
From: Gleb Natapov @ 2008-06-29 15:52 UTC (permalink / raw)
To: qemu-devel
On Sun, Jun 29, 2008 at 04:40:43PM +0200, Jan Kiszka wrote:
> Gleb Natapov wrote:
> > Count the number of interrupts that was lost due to interrupt coalescing
> > and re-inject them back when possible. This fixes time drift problem when
> > pit is used as a time source.
> >
> > Signed-off-by: Gleb Natapov <gleb@qumranet.com>
> > ---
> >
> > hw/i8254.c | 20 +++++++++++++++++++-
> > 1 files changed, 19 insertions(+), 1 deletions(-)
> >
> > diff --git a/hw/i8254.c b/hw/i8254.c
> > index 4813b03..c4f0f46 100644
> > --- a/hw/i8254.c
> > +++ b/hw/i8254.c
> > @@ -61,6 +61,8 @@ static PITState pit_state;
> >
> > static void pit_irq_timer_update(PITChannelState *s, int64_t current_time);
> >
> > +static uint32_t pit_irq_coalesced;
> > +
> > static int pit_get_count(PITChannelState *s)
> > {
> > uint64_t d;
> > @@ -369,12 +371,28 @@ static void pit_irq_timer_update(PITChannelState *s, int64_t current_time)
> > return;
> > expire_time = pit_get_next_transition_time(s, current_time);
> > irq_level = pit_get_out1(s, current_time);
> > - qemu_set_irq(s->irq, irq_level);
> > + if(irq_level) {
> > + if(!qemu_irq_raise(s->irq))
> > + pit_irq_coalesced++;
> > + } else {
> > + qemu_irq_lower(s->irq);
> > + if(pit_irq_coalesced > 0) {
> > + if(qemu_irq_raise(s->irq))
> > + pit_irq_coalesced--;
> > + qemu_irq_lower(s->irq);
> > + }
> > + }
>
> That's graspable for my poor brain: reinject one coalesced IRQ right
> after the falling edge of an in-time delivery...
This works because I speed up timer that calls this function. I can
create another timer just for injection of lost interrupts instead of
doing it here.
>
> > +
> > #ifdef DEBUG_PIT
> > printf("irq_level=%d next_delay=%f\n",
> > irq_level,
> > (double)(expire_time - current_time) / ticks_per_sec);
> > #endif
> > + if(pit_irq_coalesced && expire_time != -1) {
> > + uint32_t div = ((pit_irq_coalesced >> 10) & 0x7f) + 2;
> > + expire_time -= ((expire_time - current_time) / div);
> > + }
> > +
>
> ... but could you comment on this algorithm? I think I got what it does:
> splitting up the next regular period in short intervals. But there are a
> bit too many magic numbers involved. Where do they come from? What
> happens if pit_irq_coalesced becomes large (or: how large can it become
> without risking an IRQ storm on the guest)? A few comments would help, I
> guess.
>
The numbers are come from empirical data :) The algorithm divide next
time interval by value that depends on number of coalesced interrupts.
The divider value can be any number between 2 and 129. The formula is:
div = (pit_irq_coalesced / A) % B + 2
I chose A and B so that bit operation could be used instead of
arithmetic.
--
Gleb.
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 15:40 ` Gleb Natapov
@ 2008-06-29 18:11 ` Paul Brook
2008-06-29 19:44 ` Gleb Natapov
0 siblings, 1 reply; 29+ messages in thread
From: Paul Brook @ 2008-06-29 18:11 UTC (permalink / raw)
To: Gleb Natapov; +Cc: qemu-devel
On Sunday 29 June 2008, Gleb Natapov wrote:
> On Sun, Jun 29, 2008 at 03:38:10PM +0100, Paul Brook wrote:
> > On Sunday 29 June 2008, Gleb Natapov wrote:
> > > The return value is less then zero if interrupt is masked, zero if it
> > > is known that interrupt is lost (due to coalescing) or greater then
> > > zero if interrupt is delivered or was successfully queued for delivery
> > > by interrupt controller. Device emulation can use this info as it
> > > pleases. Included patch adds detection of interrupt coalescing into PIC
> > > and APIC code for edge triggered interrupts.
> >
> > This is woefully incomplete, and obviously hasn't been tested on anything
> > other than x86 targets.
>
> Yes, you are right. It was not tested on anything other than x86. Do you
> see why this approach will not work on other architectures? Can you
> elaborate on what current patch is missing for other architectures
> support?
Well, if nothing else there's 40+ interrupt controllers that need fixing up
before it'll even compile cleanly (mismatching function prototypes are IMHO
not acceptable).
> The initial goal is to fix RTC/PIT problem on x86 while do not
> hurt any other architectures in any way.
Well, you're introducing a fair amount of churn, so it'd better work for other
architectures too. Otherwise we're liable to have to rewrite it later. I
can't say offhand whether your approach will work on other architectures.
qemu has quite a wide variety of interrupt controllers and timers, you should
check whether they fit into your model.
Paul
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 18:11 ` Paul Brook
@ 2008-06-29 19:44 ` Gleb Natapov
2008-06-29 20:34 ` Paul Brook
0 siblings, 1 reply; 29+ messages in thread
From: Gleb Natapov @ 2008-06-29 19:44 UTC (permalink / raw)
To: Paul Brook; +Cc: qemu-devel
On Sun, Jun 29, 2008 at 07:11:01PM +0100, Paul Brook wrote:
> On Sunday 29 June 2008, Gleb Natapov wrote:
> > On Sun, Jun 29, 2008 at 03:38:10PM +0100, Paul Brook wrote:
> > > On Sunday 29 June 2008, Gleb Natapov wrote:
> > > > The return value is less then zero if interrupt is masked, zero if it
> > > > is known that interrupt is lost (due to coalescing) or greater then
> > > > zero if interrupt is delivered or was successfully queued for delivery
> > > > by interrupt controller. Device emulation can use this info as it
> > > > pleases. Included patch adds detection of interrupt coalescing into PIC
> > > > and APIC code for edge triggered interrupts.
> > >
> > > This is woefully incomplete, and obviously hasn't been tested on anything
> > > other than x86 targets.
> >
> > Yes, you are right. It was not tested on anything other than x86. Do you
> > see why this approach will not work on other architectures? Can you
> > elaborate on what current patch is missing for other architectures
> > support?
>
> Well, if nothing else there's 40+ interrupt controllers that need fixing up
> before it'll even compile cleanly (mismatching function prototypes are IMHO
> not acceptable).
Yes. 60 actually. I'll fix all of them.
>
> > The initial goal is to fix RTC/PIT problem on x86 while do not
> > hurt any other architectures in any way.
>
> Well, you're introducing a fair amount of churn, so it'd better work for other
> architectures too. Otherwise we're liable to have to rewrite it later. I
> can't say offhand whether your approach will work on other architectures.
> qemu has quite a wide variety of interrupt controllers and timers, you should
> check whether they fit into your model.
>
The model takes into account that not all interrupt controller are
capable to detect missed interrupt (it is possible that there is no
interrupt controller at all). In this case irq function should
return one and everything will fall back to how it works now.
--
Gleb.
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 19:44 ` Gleb Natapov
@ 2008-06-29 20:34 ` Paul Brook
2008-06-29 20:49 ` Gleb Natapov
2008-06-29 20:58 ` [Qemu-devel] " Jan Kiszka
0 siblings, 2 replies; 29+ messages in thread
From: Paul Brook @ 2008-06-29 20:34 UTC (permalink / raw)
To: qemu-devel; +Cc: Gleb Natapov
> The model takes into account that not all interrupt controller are
> capable to detect missed interrupt (it is possible that there is no
> interrupt controller at all). In this case irq function should
> return one and everything will fall back to how it works now.
On a related note the correct way to fix this is "-icount auto".
You should make sure that your hacks are not enabled when we have a realistic
virtual timebase.
Paul
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 20:34 ` Paul Brook
@ 2008-06-29 20:49 ` Gleb Natapov
2008-06-30 13:26 ` Gleb Natapov
2008-06-29 20:58 ` [Qemu-devel] " Jan Kiszka
1 sibling, 1 reply; 29+ messages in thread
From: Gleb Natapov @ 2008-06-29 20:49 UTC (permalink / raw)
To: Paul Brook; +Cc: qemu-devel
On Sun, Jun 29, 2008 at 09:34:08PM +0100, Paul Brook wrote:
> > The model takes into account that not all interrupt controller are
> > capable to detect missed interrupt (it is possible that there is no
> > interrupt controller at all). In this case irq function should
> > return one and everything will fall back to how it works now.
>
> On a related note the correct way to fix this is "-icount auto".
> You should make sure that your hacks are not enabled when we have a realistic
> virtual timebase.
>
Can you educate me what "-icount auto" is? Quick grep in qemu tree shows
nothing.
--
Gleb.
^ permalink raw reply [flat|nested] 29+ messages in thread
* [Qemu-devel] Re: [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 20:34 ` Paul Brook
2008-06-29 20:49 ` Gleb Natapov
@ 2008-06-29 20:58 ` Jan Kiszka
2008-06-29 21:16 ` Paul Brook
2008-06-30 13:18 ` Gleb Natapov
1 sibling, 2 replies; 29+ messages in thread
From: Jan Kiszka @ 2008-06-29 20:58 UTC (permalink / raw)
To: qemu-devel; +Cc: Gleb Natapov
[-- Attachment #1: Type: text/plain, Size: 973 bytes --]
Paul Brook wrote:
>> The model takes into account that not all interrupt controller are
>> capable to detect missed interrupt (it is possible that there is no
>> interrupt controller at all). In this case irq function should
>> return one and everything will fall back to how it works now.
>
> On a related note the correct way to fix this is "-icount auto".
> You should make sure that your hacks are not enabled when we have a realistic
> virtual timebase.
Virtual timebases don't help if the guest has to interact with the real
life - ie. clocks you cannot tweak. In the end, you will have to bring
them in sync again, so this approach basically points in the right
direction.
However, I started to wonder if this model is already enough to handle
the case where QEMU itself looses ticks. At least the PIT should
currently not be able to deal with such issues, so you also won't see
coalesce counters increase. Or am I missing something?
Jan
[-- Attachment #2: OpenPGP digital signature --]
[-- Type: application/pgp-signature, Size: 257 bytes --]
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] Re: [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 20:58 ` [Qemu-devel] " Jan Kiszka
@ 2008-06-29 21:16 ` Paul Brook
2008-06-29 21:42 ` Dor Laor
2008-06-29 21:47 ` Jan Kiszka
2008-06-30 13:18 ` Gleb Natapov
1 sibling, 2 replies; 29+ messages in thread
From: Paul Brook @ 2008-06-29 21:16 UTC (permalink / raw)
To: qemu-devel; +Cc: Gleb Natapov, Jan Kiszka
On Sunday 29 June 2008, Jan Kiszka wrote:
> Paul Brook wrote:
> >> The model takes into account that not all interrupt controller are
> >> capable to detect missed interrupt (it is possible that there is no
> >> interrupt controller at all). In this case irq function should
> >> return one and everything will fall back to how it works now.
> >
> > On a related note the correct way to fix this is "-icount auto".
> > You should make sure that your hacks are not enabled when we have a
> > realistic virtual timebase.
>
> Virtual timebases don't help if the guest has to interact with the real
> life - ie. clocks you cannot tweak. In the end, you will have to bring
> them in sync again, so this approach basically points in the right
> direction.
That's exactly what -icount auto does. It gradually varies the virtual clock
rate to keep it in line with the outside world. You get some clock skew, but
that true whatever you do (including the proposed patch).
In my experience hacks to prevent "coalescing" of interrupts cause as many
problems as they solve. The guest OS can get awfully confused when it
compares two different time sources and gets wildly different and conflicting
answers. I believe VMware has some fairly sophisticated hacks for this, but
it often still doesn't work in practice.
Paul
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] Re: [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 21:16 ` Paul Brook
@ 2008-06-29 21:42 ` Dor Laor
2008-06-29 21:47 ` Jan Kiszka
1 sibling, 0 replies; 29+ messages in thread
From: Dor Laor @ 2008-06-29 21:42 UTC (permalink / raw)
To: qemu-devel; +Cc: Gleb Natapov, Jan Kiszka
On Sun, 2008-06-29 at 22:16 +0100, Paul Brook wrote:
> On Sunday 29 June 2008, Jan Kiszka wrote:
> > Paul Brook wrote:
> > >> The model takes into account that not all interrupt controller are
> > >> capable to detect missed interrupt (it is possible that there is no
> > >> interrupt controller at all). In this case irq function should
> > >> return one and everything will fall back to how it works now.
> > >
> > > On a related note the correct way to fix this is "-icount auto".
> > > You should make sure that your hacks are not enabled when we have a
> > > realistic virtual timebase.
> >
> > Virtual timebases don't help if the guest has to interact with the real
> > life - ie. clocks you cannot tweak. In the end, you will have to bring
> > them in sync again, so this approach basically points in the right
> > direction.
>
> That's exactly what -icount auto does. It gradually varies the virtual clock
> rate to keep it in line with the outside world. You get some clock skew, but
> that true whatever you do (including the proposed patch).
>
Do you mean it slows down the virtual clock?
It's good for emulation and correctness, but not for production VMs.
> In my experience hacks to prevent "coalescing" of interrupts cause as many
> problems as they solve. The guest OS can get awfully confused when it
> compares two different time sources and gets wildly different and conflicting
> answers. I believe VMware has some fairly sophisticated hacks for this, but
> it often still doesn't work in practice.
>
> Paul
>
The current approach works well for windows guests, whether they use rtc
(acpi HAL) or pit (standard HAL). It even works if dozens of coalesced
irqs are injected one after another.
The problem you're describing about two different time source can still
happen without time drift fix since there is no global synchronization
of all the time sources (including tsc [Xen do some of it]). Indeed in
theory such two time sources synchronization will jitter with this
patch, but practically it works for Windows. Linux will have its own
para virtual time and even without it offer greater control over the
time source.
The time drift problem is indeed something we need to deal since if you
use a RHEL host, it does not have a user space high precision time, so
qemu timer pops with up to 30-100msec delay. When multimedia is played
in windows guest the timer freq is 1000HZ. This is a potential loss of
100 irqs.
Regards,
Dor
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] Re: [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 21:16 ` Paul Brook
2008-06-29 21:42 ` Dor Laor
@ 2008-06-29 21:47 ` Jan Kiszka
2008-06-29 21:54 ` Paul Brook
1 sibling, 1 reply; 29+ messages in thread
From: Jan Kiszka @ 2008-06-29 21:47 UTC (permalink / raw)
To: Paul Brook; +Cc: Gleb Natapov, qemu-devel
[-- Attachment #1: Type: text/plain, Size: 1131 bytes --]
Paul Brook wrote:
> On Sunday 29 June 2008, Jan Kiszka wrote:
>> Paul Brook wrote:
>>>> The model takes into account that not all interrupt controller are
>>>> capable to detect missed interrupt (it is possible that there is no
>>>> interrupt controller at all). In this case irq function should
>>>> return one and everything will fall back to how it works now.
>>> On a related note the correct way to fix this is "-icount auto".
>>> You should make sure that your hacks are not enabled when we have a
>>> realistic virtual timebase.
>> Virtual timebases don't help if the guest has to interact with the real
>> life - ie. clocks you cannot tweak. In the end, you will have to bring
>> them in sync again, so this approach basically points in the right
>> direction.
>
> That's exactly what -icount auto does. It gradually varies the virtual clock
> rate to keep it in line with the outside world. You get some clock skew, but
> that true whatever you do (including the proposed patch).
Interesting. This seems to require a closer look, and maybe some
quantification of the potential overhead.
Jan
[-- Attachment #2: OpenPGP digital signature --]
[-- Type: application/pgp-signature, Size: 257 bytes --]
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] Re: [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 21:47 ` Jan Kiszka
@ 2008-06-29 21:54 ` Paul Brook
0 siblings, 0 replies; 29+ messages in thread
From: Paul Brook @ 2008-06-29 21:54 UTC (permalink / raw)
To: qemu-devel; +Cc: Gleb Natapov, Jan Kiszka
> > That's exactly what -icount auto does. It gradually varies the virtual
> > clock rate to keep it in line with the outside world. You get some clock
> > skew, but that true whatever you do (including the proposed patch).
>
> Interesting. This seems to require a closer look, and maybe some
> quantification of the potential overhead.
About 10% slower than normal qemu in my measurements.
Paul
^ permalink raw reply [flat|nested] 29+ messages in thread
* [Qemu-devel] Re: [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 20:58 ` [Qemu-devel] " Jan Kiszka
2008-06-29 21:16 ` Paul Brook
@ 2008-06-30 13:18 ` Gleb Natapov
1 sibling, 0 replies; 29+ messages in thread
From: Gleb Natapov @ 2008-06-30 13:18 UTC (permalink / raw)
To: Jan Kiszka; +Cc: qemu-devel
On Sun, Jun 29, 2008 at 10:58:46PM +0200, Jan Kiszka wrote:
> However, I started to wonder if this model is already enough to handle
> the case where QEMU itself looses ticks. At least the PIT should
> currently not be able to deal with such issues, so you also won't see
> coalesce counters increase. Or am I missing something?
>
You don't miss anything. If QEMU losses ticks the time will still drift
with this patches too.
--
Gleb.
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-29 20:49 ` Gleb Natapov
@ 2008-06-30 13:26 ` Gleb Natapov
2008-06-30 14:00 ` Paul Brook
0 siblings, 1 reply; 29+ messages in thread
From: Gleb Natapov @ 2008-06-30 13:26 UTC (permalink / raw)
To: Paul Brook; +Cc: qemu-devel
On Sun, Jun 29, 2008 at 11:49:07PM +0300, Gleb Natapov wrote:
> On Sun, Jun 29, 2008 at 09:34:08PM +0100, Paul Brook wrote:
> > > The model takes into account that not all interrupt controller are
> > > capable to detect missed interrupt (it is possible that there is no
> > > interrupt controller at all). In this case irq function should
> > > return one and everything will fall back to how it works now.
> >
> > On a related note the correct way to fix this is "-icount auto".
> > You should make sure that your hacks are not enabled when we have a realistic
> > virtual timebase.
> >
> Can you educate me what "-icount auto" is? Quick grep in qemu tree shows
> nothing.
>
I forgot to rebase my branch that is why grep showed nothing ;) But
there is no much documentation about virtual time base. I can't see why
this hack cannot coexist with virtual time base. If virtual time base
somehow guaranties that interrupts will never be lost then qemu_irq_rase()
will never return zero and the hack will be as good as disabled.
--
Gleb.
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-30 13:26 ` Gleb Natapov
@ 2008-06-30 14:00 ` Paul Brook
2008-06-30 14:28 ` Gleb Natapov
0 siblings, 1 reply; 29+ messages in thread
From: Paul Brook @ 2008-06-30 14:00 UTC (permalink / raw)
To: qemu-devel; +Cc: Gleb Natapov
> I forgot to rebase my branch that is why grep showed nothing ;) But
> there is no much documentation about virtual time base. I can't see why
> this hack cannot coexist with virtual time base. If virtual time base
> somehow guaranties that interrupts will never be lost then qemu_irq_rase()
> will never return zero and the hack will be as good as disabled.
The virtual time base guarantees that a reasonable number of instruction will
have been executed in a given virtual time period. Ticks can still be "lost"
if the guest OS keeps the IRQ disable for a long time. However this behaviour
matches that of real hardware, so they should not be reinserted later.
The only reason this is a problem with normal qemu is because the virtual CPU
speed is extremely variable, and can stall for very long periods of time.
Paul
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-30 14:00 ` Paul Brook
@ 2008-06-30 14:28 ` Gleb Natapov
2008-06-30 14:35 ` Paul Brook
0 siblings, 1 reply; 29+ messages in thread
From: Gleb Natapov @ 2008-06-30 14:28 UTC (permalink / raw)
To: Paul Brook; +Cc: qemu-devel
I am running QEMU with -icount auto and get many lines of
"Bad clock read" output.
--
Gleb.
^ permalink raw reply [flat|nested] 29+ messages in thread
* Re: [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-06-30 14:28 ` Gleb Natapov
@ 2008-06-30 14:35 ` Paul Brook
0 siblings, 0 replies; 29+ messages in thread
From: Paul Brook @ 2008-06-30 14:35 UTC (permalink / raw)
To: qemu-devel; +Cc: Gleb Natapov
On Monday 30 June 2008, Gleb Natapov wrote:
> I am running QEMU with -icount auto and get many lines of
> "Bad clock read" output.
I probably missed the rdtsc instructon.
Paul
^ permalink raw reply [flat|nested] 29+ messages in thread
* [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information.
2008-10-29 15:22 [Qemu-devel] [RESEND][PATCH " Gleb Natapov
@ 2008-10-29 15:22 ` Gleb Natapov
0 siblings, 0 replies; 29+ messages in thread
From: Gleb Natapov @ 2008-10-29 15:22 UTC (permalink / raw)
To: qemu-devel
The return value is less then zero if interrupt is masked, zero if it
is known that interrupt is lost (due to coalescing) or greater then zero
if interrupt is delivered or was successfully queued for delivery by
interrupt controller. If virtual clock is in use we fall back to old
behaviour by always returning 1. Device emulation can use this info as it
pleases. Included patch adds detection of interrupt coalescing into PIC and
APIC code for edge triggered interrupts.
Signed-off-by: Gleb Natapov <gleb@redhat.com>
---
hw/apic.c | 103 +++++++++++++++++++++++++++++++++-------------------
hw/arm_gic.c | 6 ++-
hw/arm_pic.c | 4 ++
hw/arm_timer.c | 4 +-
hw/cbus.c | 12 +++++-
hw/esp.c | 4 ++
hw/etraxfs_pic.c | 12 ++++--
hw/fdc.c | 4 ++
hw/heathrow_pic.c | 4 ++
hw/i8259.c | 19 +++++++---
hw/ide.c | 8 +++-
hw/integratorcp.c | 4 ++
hw/irq.c | 18 +++++++--
hw/irq.h | 35 ++++++++++++------
hw/max7310.c | 4 ++
hw/mcf5206.c | 4 ++
hw/mcf_intc.c | 6 ++-
hw/mips_int.c | 6 ++-
hw/mpcore.c | 4 ++
hw/mst_fpga.c | 4 ++
hw/musicpal.c | 4 ++
hw/nseries.c | 7 +++-
hw/omap.h | 2 +
hw/omap1.c | 44 +++++++++++++++++-----
hw/omap2.c | 12 +++++-
hw/omap_dma.c | 8 +++-
hw/omap_mmc.c | 4 ++
hw/openpic.c | 4 ++
hw/palm.c | 4 ++
hw/pc.c | 4 ++
hw/pc.h | 2 +
hw/pci.c | 8 +++-
hw/pcnet.c | 4 ++
hw/pl061.c | 4 ++
hw/pl190.c | 4 ++
hw/ppc.c | 18 ++++++---
hw/ppc4xx_devs.c | 6 ++-
hw/pxa2xx.c | 4 ++
hw/pxa2xx_gpio.c | 6 ++-
hw/pxa2xx_pcmcia.c | 6 ++-
hw/pxa2xx_pic.c | 4 ++
hw/rc4030.c | 4 ++
hw/sbi.c | 6 ++-
hw/sharpsl.h | 2 +
hw/slavio_intctl.c | 8 +++-
hw/sparc32_dma.c | 4 ++
hw/spitz.c | 20 ++++++++--
hw/ssd0323.c | 4 ++
hw/stellaris.c | 10 ++++-
hw/sun4c_intctl.c | 4 ++
hw/sun4m.c | 7 +++-
hw/tc6393xb.c | 5 ++-
hw/tusb6010.c | 4 ++
hw/twl92230.c | 8 +++-
hw/versatilepb.c | 4 ++
hw/zaurus.c | 4 ++
56 files changed, 361 insertions(+), 157 deletions(-)
diff --git a/hw/apic.c b/hw/apic.c
index a2915f8..908f2b6 100644
--- a/hw/apic.c
+++ b/hw/apic.c
@@ -102,7 +102,7 @@ static APICState *local_apics[MAX_APICS + 1];
static int last_apic_id = 0;
static void apic_init_ipi(APICState *s);
-static void apic_set_irq(APICState *s, int vector_num, int trigger_mode);
+static int apic_set_irq(APICState *s, int vector_num, int trigger_mode);
static void apic_update_irq(APICState *s);
/* Find first bit starting from msb */
@@ -133,6 +133,14 @@ static inline void reset_bit(uint32_t *tab, int index)
tab[i] &= ~mask;
}
+static inline int get_bit(uint32_t *tab, int index)
+{
+ int i, mask;
+ i = index >> 5;
+ mask = 1 << (index & 0x1f);
+ return !!(tab[i] & mask);
+}
+
static void apic_local_deliver(CPUState *env, int vector)
{
APICState *s = env->apic_state;
@@ -203,12 +211,13 @@ void apic_deliver_pic_intr(CPUState *env, int level)
}\
}
-static void apic_bus_deliver(const uint32_t *deliver_bitmask,
+static int apic_bus_deliver(const uint32_t *deliver_bitmask,
uint8_t delivery_mode,
uint8_t vector_num, uint8_t polarity,
uint8_t trigger_mode)
{
APICState *apic_iter;
+ int ret = 0;
switch (delivery_mode) {
case APIC_DM_LOWPRI:
@@ -225,11 +234,12 @@ static void apic_bus_deliver(const uint32_t *deliver_bitmask,
if (d >= 0) {
apic_iter = local_apics[d];
if (apic_iter) {
- apic_set_irq(apic_iter, vector_num, trigger_mode);
+ ret = apic_set_irq(apic_iter, vector_num, trigger_mode);
}
- }
+ } else
+ ret = 1;
}
- return;
+ return ret;
case APIC_DM_FIXED:
break;
@@ -237,29 +247,33 @@ static void apic_bus_deliver(const uint32_t *deliver_bitmask,
case APIC_DM_SMI:
foreach_apic(apic_iter, deliver_bitmask,
cpu_interrupt(apic_iter->cpu_env, CPU_INTERRUPT_SMI) );
- return;
+ return 1;
case APIC_DM_NMI:
foreach_apic(apic_iter, deliver_bitmask,
cpu_interrupt(apic_iter->cpu_env, CPU_INTERRUPT_NMI) );
- return;
+ return 1;
case APIC_DM_INIT:
/* normal INIT IPI sent to processors */
foreach_apic(apic_iter, deliver_bitmask,
apic_init_ipi(apic_iter) );
- return;
+ return 1;
case APIC_DM_EXTINT:
/* handled in I/O APIC code */
break;
default:
- return;
+ return ret;
}
+ /* if interrupt should be delivered to more then one apic report it as
+ * delivered if at least one apic accepts it */
foreach_apic(apic_iter, deliver_bitmask,
- apic_set_irq(apic_iter, vector_num, trigger_mode) );
+ ret += apic_set_irq(apic_iter, vector_num, trigger_mode) );
+
+ return ret;
}
void cpu_set_apic_base(CPUState *env, uint64_t val)
@@ -349,14 +363,18 @@ static void apic_update_irq(APICState *s)
cpu_interrupt(s->cpu_env, CPU_INTERRUPT_HARD);
}
-static void apic_set_irq(APICState *s, int vector_num, int trigger_mode)
+static int apic_set_irq(APICState *s, int vector_num, int trigger_mode)
{
+ int ret = !get_bit(s->irr, vector_num);
+
set_bit(s->irr, vector_num);
if (trigger_mode)
set_bit(s->tmr, vector_num);
else
reset_bit(s->tmr, vector_num);
apic_update_irq(s);
+
+ return ret;
}
static void apic_eoi(APICState *s)
@@ -903,9 +921,8 @@ int apic_init(CPUState *env)
return 0;
}
-static void ioapic_service(IOAPICState *s)
+static int ioapic_service_one(IOAPICState *s, uint8_t pin)
{
- uint8_t i;
uint8_t trig_mode;
uint8_t vector;
uint8_t delivery_mode;
@@ -916,34 +933,44 @@ static void ioapic_service(IOAPICState *s)
uint8_t polarity;
uint32_t deliver_bitmask[MAX_APIC_WORDS];
+ mask = 1 << pin;
+ if (!(s->irr & mask))
+ return 1;
+
+ entry = s->ioredtbl[pin];
+ if ((entry & APIC_LVT_MASKED))
+ return -1;
+
+ trig_mode = ((entry >> 15) & 1);
+ dest = entry >> 56;
+ dest_mode = (entry >> 11) & 1;
+ delivery_mode = (entry >> 8) & 7;
+ polarity = (entry >> 13) & 1;
+ if (trig_mode == APIC_TRIGGER_EDGE)
+ s->irr &= ~mask;
+ if (delivery_mode == APIC_DM_EXTINT)
+ vector = pic_read_irq(isa_pic);
+ else
+ vector = entry & 0xff;
+
+ apic_get_delivery_bitmask(deliver_bitmask, dest, dest_mode);
+ return apic_bus_deliver(deliver_bitmask, delivery_mode, vector, polarity,
+ trig_mode);
+}
+
+static void ioapic_service(IOAPICState *s)
+{
+ uint8_t i;
+
for (i = 0; i < IOAPIC_NUM_PINS; i++) {
- mask = 1 << i;
- if (s->irr & mask) {
- entry = s->ioredtbl[i];
- if (!(entry & APIC_LVT_MASKED)) {
- trig_mode = ((entry >> 15) & 1);
- dest = entry >> 56;
- dest_mode = (entry >> 11) & 1;
- delivery_mode = (entry >> 8) & 7;
- polarity = (entry >> 13) & 1;
- if (trig_mode == APIC_TRIGGER_EDGE)
- s->irr &= ~mask;
- if (delivery_mode == APIC_DM_EXTINT)
- vector = pic_read_irq(isa_pic);
- else
- vector = entry & 0xff;
-
- apic_get_delivery_bitmask(deliver_bitmask, dest, dest_mode);
- apic_bus_deliver(deliver_bitmask, delivery_mode,
- vector, polarity, trig_mode);
- }
- }
+ ioapic_service_one(s, i);
}
}
-void ioapic_set_irq(void *opaque, int vector, int level)
+int ioapic_set_irq(void *opaque, int vector, int level)
{
IOAPICState *s = opaque;
+ int ret = 1;
if (vector >= 0 && vector < IOAPIC_NUM_PINS) {
uint32_t mask = 1 << vector;
@@ -953,7 +980,7 @@ void ioapic_set_irq(void *opaque, int vector, int level)
/* level triggered */
if (level) {
s->irr |= mask;
- ioapic_service(s);
+ ioapic_service_one(s, vector);
} else {
s->irr &= ~mask;
}
@@ -961,10 +988,12 @@ void ioapic_set_irq(void *opaque, int vector, int level)
/* edge triggered */
if (level) {
s->irr |= mask;
- ioapic_service(s);
+ ret = ioapic_service_one(s, vector);
}
}
}
+
+ return ret;
}
static uint32_t ioapic_mem_readl(void *opaque, target_phys_addr_t addr)
diff --git a/hw/arm_gic.c b/hw/arm_gic.c
index 54e99f4..a0fc3f0 100644
--- a/hw/arm_gic.c
+++ b/hw/arm_gic.c
@@ -154,13 +154,13 @@ gic_set_pending_private(gic_state *s, int cpu, int irq)
}
/* Process a change in an external IRQ input. */
-static void gic_set_irq(void *opaque, int irq, int level)
+static int gic_set_irq(void *opaque, int irq, int level)
{
gic_state *s = (gic_state *)opaque;
/* The first external input line is internal interrupt 32. */
irq += 32;
if (level == GIC_TEST_LEVEL(irq, ALL_CPU_MASK))
- return;
+ return 1;
if (level) {
GIC_SET_LEVEL(irq, ALL_CPU_MASK);
@@ -172,6 +172,8 @@ static void gic_set_irq(void *opaque, int irq, int level)
GIC_CLEAR_LEVEL(irq, ALL_CPU_MASK);
}
gic_update(s);
+
+ return 1;
}
static void gic_set_running_irq(gic_state *s, int cpu, int irq)
diff --git a/hw/arm_pic.c b/hw/arm_pic.c
index 1fe55b7..753a404 100644
--- a/hw/arm_pic.c
+++ b/hw/arm_pic.c
@@ -21,7 +21,7 @@ void irq_info(void)
/* Input 0 is IRQ and input 1 is FIQ. */
-static void arm_pic_cpu_handler(void *opaque, int irq, int level)
+static int arm_pic_cpu_handler(void *opaque, int irq, int level)
{
CPUState *env = (CPUState *)opaque;
switch (irq) {
@@ -40,6 +40,8 @@ static void arm_pic_cpu_handler(void *opaque, int irq, int level)
default:
cpu_abort(env, "arm_pic_cpu_handler: Bad interrput line %d\n", irq);
}
+
+ return 1;
}
qemu_irq *arm_pic_init_cpu(CPUState *env)
diff --git a/hw/arm_timer.c b/hw/arm_timer.c
index 5150fe9..635c7e2 100644
--- a/hw/arm_timer.c
+++ b/hw/arm_timer.c
@@ -195,12 +195,12 @@ typedef struct {
} sp804_state;
/* Merge the IRQs from the two component devices. */
-static void sp804_set_irq(void *opaque, int irq, int level)
+static int sp804_set_irq(void *opaque, int irq, int level)
{
sp804_state *s = (sp804_state *)opaque;
s->level[irq] = level;
- qemu_set_irq(s->irq, s->level[0] || s->level[1]);
+ return qemu_set_irq(s->irq, s->level[0] || s->level[1]);
}
static uint32_t sp804_read(void *opaque, target_phys_addr_t offset)
diff --git a/hw/cbus.c b/hw/cbus.c
index 03218b4..9a57cec 100644
--- a/hw/cbus.c
+++ b/hw/cbus.c
@@ -97,7 +97,7 @@ static void cbus_cycle(struct cbus_priv_s *s)
}
}
-static void cbus_clk(void *opaque, int line, int level)
+static int cbus_clk(void *opaque, int line, int level)
{
struct cbus_priv_s *s = (struct cbus_priv_s *) opaque;
@@ -112,16 +112,20 @@ static void cbus_clk(void *opaque, int line, int level)
}
s->clk = level;
+
+ return 1;
}
-static void cbus_dat(void *opaque, int line, int level)
+static int cbus_dat(void *opaque, int line, int level)
{
struct cbus_priv_s *s = (struct cbus_priv_s *) opaque;
s->dat = level;
+
+ return 1;
}
-static void cbus_sel(void *opaque, int line, int level)
+static int cbus_sel(void *opaque, int line, int level)
{
struct cbus_priv_s *s = (struct cbus_priv_s *) opaque;
@@ -132,6 +136,8 @@ static void cbus_sel(void *opaque, int line, int level)
}
s->sel = level;
+
+ return 1;
}
struct cbus_s *cbus_init(qemu_irq dat)
diff --git a/hw/esp.c b/hw/esp.c
index 6b16cf4..abc2a2a 100644
--- a/hw/esp.c
+++ b/hw/esp.c
@@ -409,10 +409,12 @@ static void esp_reset(void *opaque)
s->do_cmd = 0;
}
-static void parent_esp_reset(void *opaque, int irq, int level)
+static int parent_esp_reset(void *opaque, int irq, int level)
{
if (level)
esp_reset(opaque);
+
+ return 1;
}
static uint32_t esp_mem_readb(void *opaque, target_phys_addr_t addr)
diff --git a/hw/etraxfs_pic.c b/hw/etraxfs_pic.c
index d145bec..0f7c8ed 100644
--- a/hw/etraxfs_pic.c
+++ b/hw/etraxfs_pic.c
@@ -144,7 +144,7 @@ void irq_info(void)
{
}
-static void irq_handler(void *opaque, int irq, int level)
+static int irq_handler(void *opaque, int irq, int level)
{
struct fs_pic_state_t *fs = (void *)opaque;
CPUState *env = fs->env;
@@ -186,9 +186,11 @@ static void irq_handler(void *opaque, int irq, int level)
cpu_reset_interrupt(env, CPU_INTERRUPT_HARD);
D(printf("%s reset irqs\n", __func__));
}
+
+ return 1;
}
-static void nmi_handler(void *opaque, int irq, int level)
+static int nmi_handler(void *opaque, int irq, int level)
{
struct fs_pic_state_t *fs = (void *)opaque;
CPUState *env = fs->env;
@@ -204,14 +206,16 @@ static void nmi_handler(void *opaque, int irq, int level)
cpu_interrupt(env, CPU_INTERRUPT_NMI);
else
cpu_reset_interrupt(env, CPU_INTERRUPT_NMI);
+
+ return 1;
}
-static void guru_handler(void *opaque, int irq, int level)
+static int guru_handler(void *opaque, int irq, int level)
{
struct fs_pic_state_t *fs = (void *)opaque;
CPUState *env = fs->env;
cpu_abort(env, "%s unsupported exception\n", __func__);
-
+ return 1;
}
diff --git a/hw/fdc.c b/hw/fdc.c
index cd00420..b212d89 100644
--- a/hw/fdc.c
+++ b/hw/fdc.c
@@ -713,7 +713,7 @@ static void fdctrl_external_reset(void *opaque)
fdctrl_reset(s, 0);
}
-static void fdctrl_handle_tc(void *opaque, int irq, int level)
+static int fdctrl_handle_tc(void *opaque, int irq, int level)
{
//fdctrl_t *s = opaque;
@@ -721,6 +721,8 @@ static void fdctrl_handle_tc(void *opaque, int irq, int level)
// XXX
FLOPPY_DPRINTF("TC pulsed\n");
}
+
+ return 1;
}
/* XXX: may change if moved to bdrv */
diff --git a/hw/heathrow_pic.c b/hw/heathrow_pic.c
index dc2a30c..81657cf 100644
--- a/hw/heathrow_pic.c
+++ b/hw/heathrow_pic.c
@@ -135,7 +135,7 @@ static CPUReadMemoryFunc *pic_read[] = {
};
-static void heathrow_pic_set_irq(void *opaque, int num, int level)
+static int heathrow_pic_set_irq(void *opaque, int num, int level)
{
HeathrowPICS *s = opaque;
HeathrowPIC *pic;
@@ -159,6 +159,8 @@ static void heathrow_pic_set_irq(void *opaque, int num, int level)
pic->levels &= ~irq_bit;
}
heathrow_pic_update(s);
+
+ return 1;
}
qemu_irq *heathrow_pic_init(int *pmem_index,
diff --git a/hw/i8259.c b/hw/i8259.c
index 750a76c..5ea3415 100644
--- a/hw/i8259.c
+++ b/hw/i8259.c
@@ -72,9 +72,9 @@ static uint64_t irq_count[16];
#endif
/* set irq level. If an edge is detected, then the IRR is set to 1 */
-static inline void pic_set_irq1(PicState *s, int irq, int level)
+static inline int pic_set_irq1(PicState *s, int irq, int level)
{
- int mask;
+ int mask, ret = 1;
mask = 1 << irq;
if (s->elcr & mask) {
/* level triggered */
@@ -88,13 +88,18 @@ static inline void pic_set_irq1(PicState *s, int irq, int level)
} else {
/* edge triggered */
if (level) {
- if ((s->last_irr & mask) == 0)
+ if ((s->last_irr & mask) == 0) {
+ if((s->irr & mask))
+ ret = 0;
s->irr |= mask;
+ }
s->last_irr |= mask;
} else {
s->last_irr &= ~mask;
}
}
+
+ return (s->imr & mask) ? -1 : ret;
}
/* return the highest priority found in mask (highest = smallest
@@ -180,9 +185,10 @@ void pic_update_irq(PicState2 *s)
int64_t irq_time[16];
#endif
-static void i8259_set_irq(void *opaque, int irq, int level)
+static int i8259_set_irq(void *opaque, int irq, int level)
{
PicState2 *s = opaque;
+ int pic_ret, ioapic_ret = -1;
#if defined(DEBUG_PIC) || defined(DEBUG_IRQ_COUNT)
if (level != irq_level[irq]) {
@@ -201,11 +207,12 @@ static void i8259_set_irq(void *opaque, int irq, int level)
irq_time[irq] = qemu_get_clock(vm_clock);
}
#endif
- pic_set_irq1(&s->pics[irq >> 3], irq & 7, level);
+ pic_ret = pic_set_irq1(&s->pics[irq >> 3], irq & 7, level);
/* used for IOAPIC irqs */
if (s->alt_irq_func)
- s->alt_irq_func(s->alt_irq_opaque, irq, level);
+ ioapic_ret = s->alt_irq_func(s->alt_irq_opaque, irq, level);
pic_update_irq(s);
+ return MAX(pic_ret, ioapic_ret);
}
/* acknowledge interrupt 'irq' */
diff --git a/hw/ide.c b/hw/ide.c
index 33e8b39..6aec211 100644
--- a/hw/ide.c
+++ b/hw/ide.c
@@ -3135,7 +3135,7 @@ static void cmd646_update_irq(PCIIDEState *d)
}
/* the PCI irq level is the logical OR of the two channels */
-static void cmd646_set_irq(void *opaque, int channel, int level)
+static int cmd646_set_irq(void *opaque, int channel, int level)
{
PCIIDEState *d = opaque;
int irq_mask;
@@ -3146,6 +3146,8 @@ static void cmd646_set_irq(void *opaque, int channel, int level)
else
d->dev.config[MRDMODE] &= ~irq_mask;
cmd646_update_irq(d);
+
+ return 1;
}
/* CMD646 PCI IDE controller */
@@ -3545,7 +3547,7 @@ static inline void md_interrupt_update(struct md_s *s)
!(s->opt & OPT_SRESET));
}
-static void md_set_irq(void *opaque, int irq, int level)
+static int md_set_irq(void *opaque, int irq, int level)
{
struct md_s *s = (struct md_s *) opaque;
if (level)
@@ -3554,6 +3556,8 @@ static void md_set_irq(void *opaque, int irq, int level)
s->stat &= ~STAT_INT;
md_interrupt_update(s);
+
+ return 1;
}
static void md_reset(struct md_s *s)
diff --git a/hw/integratorcp.c b/hw/integratorcp.c
index 779d46b..b69512e 100644
--- a/hw/integratorcp.c
+++ b/hw/integratorcp.c
@@ -290,7 +290,7 @@ static void icp_pic_update(icp_pic_state *s)
qemu_set_irq(s->parent_fiq, flags != 0);
}
-static void icp_pic_set_irq(void *opaque, int irq, int level)
+static int icp_pic_set_irq(void *opaque, int irq, int level)
{
icp_pic_state *s = (icp_pic_state *)opaque;
if (level)
@@ -298,6 +298,8 @@ static void icp_pic_set_irq(void *opaque, int irq, int level)
else
s->level &= ~(1 << irq);
icp_pic_update(s);
+
+ return 1;
}
static uint32_t icp_pic_read(void *opaque, target_phys_addr_t offset)
diff --git a/hw/irq.c b/hw/irq.c
index eca707d..2159604 100644
--- a/hw/irq.c
+++ b/hw/irq.c
@@ -24,18 +24,26 @@
#include "qemu-common.h"
#include "irq.h"
+extern int use_icount;
+
struct IRQState {
qemu_irq_handler handler;
void *opaque;
int n;
};
-void qemu_set_irq(qemu_irq irq, int level)
+int qemu_set_irq(qemu_irq irq, int level)
{
+ int ret;
+
if (!irq)
- return;
+ return 1;
+
+ ret = irq->handler(irq->opaque, irq->n, level);
- irq->handler(irq->opaque, irq->n, level);
+ /* if virtual clock is in use then emulation is as close to real HW as
+ * possible, so we never re-inject lost interrupts in this case */
+ return use_icount ? 1 : ret;
}
qemu_irq *qemu_allocate_irqs(qemu_irq_handler handler, void *opaque, int n)
@@ -56,11 +64,11 @@ qemu_irq *qemu_allocate_irqs(qemu_irq_handler handler, void *opaque, int n)
return s;
}
-static void qemu_notirq(void *opaque, int line, int level)
+static int qemu_notirq(void *opaque, int line, int level)
{
struct IRQState *irq = opaque;
- irq->handler(irq->opaque, irq->n, !level);
+ return irq->handler(irq->opaque, irq->n, !level);
}
qemu_irq qemu_irq_invert(qemu_irq irq)
diff --git a/hw/irq.h b/hw/irq.h
index 0880ad2..53e5921 100644
--- a/hw/irq.h
+++ b/hw/irq.h
@@ -4,25 +4,38 @@
/* Generic IRQ/GPIO pin infrastructure. */
/* FIXME: Rmove one of these. */
-typedef void (*qemu_irq_handler)(void *opaque, int n, int level);
-typedef void SetIRQFunc(void *opaque, int irq_num, int level);
-
-void qemu_set_irq(qemu_irq irq, int level);
-
-static inline void qemu_irq_raise(qemu_irq irq)
+/*
+ * Negative return value indicates that interrupt is masked.
+ * Positive return value indicates that interrupt was delivered
+ * to at least one CPU or was queued in interrupt controller for
+ * delivery. If return value is greater then one it indicates the
+ * number of CPUs that handled the interrupt.
+ * Zero value indicates that interrupt was lost (due to coalescing
+ * for instance).
+ */
+typedef int (*qemu_irq_handler)(void *opaque, int n, int level);
+typedef int SetIRQFunc(void *opaque, int irq_num, int level);
+
+int qemu_set_irq(qemu_irq irq, int level);
+
+static inline int qemu_irq_raise(qemu_irq irq)
{
- qemu_set_irq(irq, 1);
+ return qemu_set_irq(irq, 1);
}
-static inline void qemu_irq_lower(qemu_irq irq)
+static inline int qemu_irq_lower(qemu_irq irq)
{
- qemu_set_irq(irq, 0);
+ return qemu_set_irq(irq, 0);
}
-static inline void qemu_irq_pulse(qemu_irq irq)
+static inline int qemu_irq_pulse(qemu_irq irq)
{
- qemu_set_irq(irq, 1);
+ int ret;
+
+ ret = qemu_set_irq(irq, 1);
qemu_set_irq(irq, 0);
+
+ return ret;
}
/* Returns an array of N IRQs. */
diff --git a/hw/max7310.c b/hw/max7310.c
index 2816611..a8e759f 100644
--- a/hw/max7310.c
+++ b/hw/max7310.c
@@ -177,7 +177,7 @@ static int max7310_load(QEMUFile *f, void *opaque, int version_id)
return 0;
}
-static void max7310_gpio_set(void *opaque, int line, int level)
+static int max7310_gpio_set(void *opaque, int line, int level)
{
struct max7310_s *s = (struct max7310_s *) opaque;
if (line >= sizeof(s->handler) / sizeof(*s->handler) || line < 0)
@@ -187,6 +187,8 @@ static void max7310_gpio_set(void *opaque, int line, int level)
s->level |= s->direction & (1 << line);
else
s->level &= ~(s->direction & (1 << line));
+
+ return 1;
}
/* MAX7310 is SMBus-compatible (can be used with only SMBus protocols),
diff --git a/hw/mcf5206.c b/hw/mcf5206.c
index 449ca12..79d9e8e 100644
--- a/hw/mcf5206.c
+++ b/hw/mcf5206.c
@@ -228,7 +228,7 @@ static void m5206_mbar_update(m5206_mbar_state *s)
m68k_set_irq_level(s->env, level, vector);
}
-static void m5206_mbar_set_irq(void *opaque, int irq, int level)
+static int m5206_mbar_set_irq(void *opaque, int irq, int level)
{
m5206_mbar_state *s = (m5206_mbar_state *)opaque;
if (level) {
@@ -237,6 +237,8 @@ static void m5206_mbar_set_irq(void *opaque, int irq, int level)
s->ipr &= ~(1 << irq);
}
m5206_mbar_update(s);
+
+ return 1;
}
/* System Integration Module. */
diff --git a/hw/mcf_intc.c b/hw/mcf_intc.c
index 4e99aeb..edca76f 100644
--- a/hw/mcf_intc.c
+++ b/hw/mcf_intc.c
@@ -106,16 +106,18 @@ static void mcf_intc_write(void *opaque, target_phys_addr_t addr, uint32_t val)
mcf_intc_update(s);
}
-static void mcf_intc_set_irq(void *opaque, int irq, int level)
+static int mcf_intc_set_irq(void *opaque, int irq, int level)
{
mcf_intc_state *s = (mcf_intc_state *)opaque;
if (irq >= 64)
- return;
+ return 1;
if (level)
s->ipr |= 1ull << irq;
else
s->ipr &= ~(1ull << irq);
mcf_intc_update(s);
+
+ return 1;
}
static void mcf_intc_reset(mcf_intc_state *s)
diff --git a/hw/mips_int.c b/hw/mips_int.c
index ad48b4f..7e18e1b 100644
--- a/hw/mips_int.c
+++ b/hw/mips_int.c
@@ -18,12 +18,12 @@ void cpu_mips_update_irq(CPUState *env)
cpu_reset_interrupt(env, CPU_INTERRUPT_HARD);
}
-static void cpu_mips_irq_request(void *opaque, int irq, int level)
+static int cpu_mips_irq_request(void *opaque, int irq, int level)
{
CPUState *env = (CPUState *)opaque;
if (irq < 0 || irq > 7)
- return;
+ return 1;
if (level) {
env->CP0_Cause |= 1 << (irq + CP0Ca_IP);
@@ -31,6 +31,8 @@ static void cpu_mips_irq_request(void *opaque, int irq, int level)
env->CP0_Cause &= ~(1 << (irq + CP0Ca_IP));
}
cpu_mips_update_irq(env);
+
+ return 1;
}
void cpu_mips_irq_init_cpu(CPUState *env)
diff --git a/hw/mpcore.c b/hw/mpcore.c
index d5b28fe..6e71081 100644
--- a/hw/mpcore.c
+++ b/hw/mpcore.c
@@ -293,7 +293,7 @@ static const int mpcore_irq_map[32] = {
-1, -1, -1, -1, 9, 3, -1, -1,
};
-static void mpcore_rirq_set_irq(void *opaque, int irq, int level)
+static int mpcore_rirq_set_irq(void *opaque, int irq, int level)
{
mpcore_rirq_state *s = (mpcore_rirq_state *)opaque;
int i;
@@ -307,6 +307,8 @@ static void mpcore_rirq_set_irq(void *opaque, int irq, int level)
qemu_set_irq(s->cpuic[irq], level);
}
}
+
+ return 1;
}
qemu_irq *mpcore_irq_init(qemu_irq *cpu_irq)
diff --git a/hw/mst_fpga.c b/hw/mst_fpga.c
index 2d5ac5a..1773c2a 100644
--- a/hw/mst_fpga.c
+++ b/hw/mst_fpga.c
@@ -62,7 +62,7 @@ mst_fpga_update_gpio(mst_irq_state *s)
s->prev_level = level;
}
-static void
+static int
mst_fpga_set_irq(void *opaque, int irq, int level)
{
mst_irq_state *s = (mst_irq_state *)opaque;
@@ -76,6 +76,8 @@ mst_fpga_set_irq(void *opaque, int irq, int level)
s->intsetclr = 1u << irq;
qemu_set_irq(s->parent[0], level);
}
+
+ return 1;
}
diff --git a/hw/musicpal.c b/hw/musicpal.c
index c7c11de..0a1cf01 100644
--- a/hw/musicpal.c
+++ b/hw/musicpal.c
@@ -951,7 +951,7 @@ static void mv88w8618_pic_update(mv88w8618_pic_state *s)
qemu_set_irq(s->parent_irq, (s->level & s->enabled));
}
-static void mv88w8618_pic_set_irq(void *opaque, int irq, int level)
+static int mv88w8618_pic_set_irq(void *opaque, int irq, int level)
{
mv88w8618_pic_state *s = opaque;
@@ -960,6 +960,8 @@ static void mv88w8618_pic_set_irq(void *opaque, int irq, int level)
else
s->level &= ~(1 << irq);
mv88w8618_pic_update(s);
+
+ return 1;
}
static uint32_t mv88w8618_pic_read(void *opaque, target_phys_addr_t offset)
diff --git a/hw/nseries.c b/hw/nseries.c
index 80fd9e8..1ddc28e 100644
--- a/hw/nseries.c
+++ b/hw/nseries.c
@@ -123,13 +123,14 @@ struct n800_s {
#define N8X0_BD_ADDR 0x00, 0x1a, 0x89, 0x9e, 0x3e, 0x81
-static void n800_mmc_cs_cb(void *opaque, int line, int level)
+static int n800_mmc_cs_cb(void *opaque, int line, int level)
{
/* TODO: this seems to actually be connected to the menelaus, to
* which also both MMC slots connect. */
omap_mmc_enable((struct omap_mmc_s *) opaque, !level);
printf("%s: MMC slot %i active\n", __FUNCTION__, level + 1);
+ return 1;
}
static void n8x0_gpio_setup(struct n800_s *s)
@@ -755,11 +756,13 @@ static void n8x0_uart_setup(struct n800_s *s)
omap_uart_attach(s->cpu->uart[BT_UART], radio);
}
-static void n8x0_usb_power_cb(void *opaque, int line, int level)
+static int n8x0_usb_power_cb(void *opaque, int line, int level)
{
struct n800_s *s = opaque;
tusb6010_power(s->usb, level);
+
+ return 1;
}
static void n8x0_usb_setup(struct n800_s *s)
diff --git a/hw/omap.h b/hw/omap.h
index 4c30436..5d2f729 100644
--- a/hw/omap.h
+++ b/hw/omap.h
@@ -992,7 +992,7 @@ uint32_t omap_badwidth_read32(void *opaque, target_phys_addr_t addr);
void omap_badwidth_write32(void *opaque, target_phys_addr_t addr,
uint32_t value);
-void omap_mpu_wakeup(void *opaque, int irq, int req);
+int omap_mpu_wakeup(void *opaque, int irq, int req);
# define OMAP_BAD_REG(paddr) \
fprintf(stderr, "%s: Bad register " OMAP_FMT_plx "\n", \
diff --git a/hw/omap1.c b/hw/omap1.c
index a32563b..7066f2e 100644
--- a/hw/omap1.c
+++ b/hw/omap1.c
@@ -153,7 +153,7 @@ static inline void omap_inth_update(struct omap_intr_handler_s *s, int is_fiq)
#define INT_FALLING_EDGE 0
#define INT_LOW_LEVEL 1
-static void omap_set_intr(void *opaque, int irq, int req)
+static int omap_set_intr(void *opaque, int irq, int req)
{
struct omap_intr_handler_s *ih = (struct omap_intr_handler_s *) opaque;
uint32_t rise;
@@ -177,10 +177,12 @@ static void omap_set_intr(void *opaque, int irq, int req)
bank->irqs &= ~rise;
bank->inputs &= ~(1 << n);
}
+
+ return 1;
}
/* Simplified version with no edge detection */
-static void omap_set_intr_noedge(void *opaque, int irq, int req)
+static int omap_set_intr_noedge(void *opaque, int irq, int req)
{
struct omap_intr_handler_s *ih = (struct omap_intr_handler_s *) opaque;
uint32_t rise;
@@ -197,6 +199,8 @@ static void omap_set_intr_noedge(void *opaque, int irq, int req)
}
} else
bank->irqs = (bank->inputs &= ~(1 << n)) | bank->swi;
+
+ return 1;
}
static uint32_t omap_inth_read(void *opaque, target_phys_addr_t addr)
@@ -738,13 +742,15 @@ static void omap_timer_tick(void *opaque)
omap_timer_update(timer);
}
-static void omap_timer_clk_update(void *opaque, int line, int on)
+static int omap_timer_clk_update(void *opaque, int line, int on)
{
struct omap_mpu_timer_s *timer = (struct omap_mpu_timer_s *) opaque;
omap_timer_sync(timer);
timer->rate = on ? omap_clk_getrate(timer->clk) : 0;
omap_timer_update(timer);
+
+ return 1;
}
static void omap_timer_clk_setup(struct omap_mpu_timer_s *timer)
@@ -2575,7 +2581,7 @@ struct omap_mpuio_s {
int clk;
};
-static void omap_mpuio_set(void *opaque, int line, int level)
+static int omap_mpuio_set(void *opaque, int line, int level)
{
struct omap_mpuio_s *s = (struct omap_mpuio_s *) opaque;
uint16_t prev = s->inputs;
@@ -2595,6 +2601,8 @@ static void omap_mpuio_set(void *opaque, int line, int level)
(s->event >> 1) == line) /* PIN_SELECT */
s->latch = s->inputs;
}
+
+ return 1;
}
static void omap_mpuio_kbd_update(struct omap_mpuio_s *s)
@@ -2766,13 +2774,15 @@ static void omap_mpuio_reset(struct omap_mpuio_s *s)
s->clk = 1;
}
-static void omap_mpuio_onoff(void *opaque, int line, int on)
+static int omap_mpuio_onoff(void *opaque, int line, int on)
{
struct omap_mpuio_s *s = (struct omap_mpuio_s *) opaque;
s->clk = on;
if (on)
omap_mpuio_kbd_update(s);
+
+ return 1;
}
struct omap_mpuio_s *omap_mpuio_init(target_phys_addr_t base,
@@ -2841,7 +2851,7 @@ struct omap_gpio_s {
uint16_t pins;
};
-static void omap_gpio_set(void *opaque, int line, int level)
+static int omap_gpio_set(void *opaque, int line, int level)
{
struct omap_gpio_s *s = (struct omap_gpio_s *) opaque;
uint16_t prev = s->inputs;
@@ -2856,6 +2866,8 @@ static void omap_gpio_set(void *opaque, int line, int level)
s->ints |= 1 << line;
qemu_irq_raise(s->irq);
}
+
+ return 1;
}
static uint32_t omap_gpio_read(void *opaque, target_phys_addr_t addr)
@@ -3247,12 +3259,14 @@ static void omap_pwl_reset(struct omap_mpu_state_s *s)
omap_pwl_update(s);
}
-static void omap_pwl_clk_update(void *opaque, int line, int on)
+static int omap_pwl_clk_update(void *opaque, int line, int on)
{
struct omap_mpu_state_s *s = (struct omap_mpu_state_s *) opaque;
s->pwl.clk = on;
omap_pwl_update(s);
+
+ return 1;
}
static void omap_pwl_init(target_phys_addr_t base, struct omap_mpu_state_s *s,
@@ -4311,7 +4325,7 @@ struct omap_mcbsp_s *omap_mcbsp_init(target_phys_addr_t base,
return s;
}
-static void omap_mcbsp_i2s_swallow(void *opaque, int line, int level)
+static int omap_mcbsp_i2s_swallow(void *opaque, int line, int level)
{
struct omap_mcbsp_s *s = (struct omap_mcbsp_s *) opaque;
@@ -4319,9 +4333,11 @@ static void omap_mcbsp_i2s_swallow(void *opaque, int line, int level)
s->rx_req = s->codec->in.len;
omap_mcbsp_rx_newdata(s);
}
+
+ return 1;
}
-static void omap_mcbsp_i2s_start(void *opaque, int line, int level)
+static int omap_mcbsp_i2s_start(void *opaque, int line, int level)
{
struct omap_mcbsp_s *s = (struct omap_mcbsp_s *) opaque;
@@ -4329,6 +4345,8 @@ static void omap_mcbsp_i2s_start(void *opaque, int line, int level)
s->tx_req = s->codec->out.size;
omap_mcbsp_tx_newdata(s);
}
+
+ return 1;
}
void omap_mcbsp_i2s_attach(struct omap_mcbsp_s *s, struct i2s_codec_s *slave)
@@ -4459,12 +4477,14 @@ static CPUWriteMemoryFunc *omap_lpg_writefn[] = {
omap_badwidth_write8,
};
-static void omap_lpg_clk_update(void *opaque, int line, int on)
+static int omap_lpg_clk_update(void *opaque, int line, int on)
{
struct omap_lpg_s *s = (struct omap_lpg_s *) opaque;
s->clk = on;
omap_lpg_update(s);
+
+ return 1;
}
struct omap_lpg_s *omap_lpg_init(target_phys_addr_t base, omap_clk clk)
@@ -4599,12 +4619,14 @@ static void omap_setup_dsp_mapping(const struct omap_map_s *map)
}
}
-void omap_mpu_wakeup(void *opaque, int irq, int req)
+int omap_mpu_wakeup(void *opaque, int irq, int req)
{
struct omap_mpu_state_s *mpu = (struct omap_mpu_state_s *) opaque;
if (mpu->env->halted)
cpu_interrupt(mpu->env, CPU_INTERRUPT_EXITTB);
+
+ return 1;
}
static const struct dma_irq_map omap1_dma_irq_map[] = {
diff --git a/hw/omap2.c b/hw/omap2.c
index 5add059..e171dbb 100644
--- a/hw/omap2.c
+++ b/hw/omap2.c
@@ -193,7 +193,7 @@ static void omap_gp_timer_match(void *opaque)
omap_gp_timer_intr(timer, GPT_MAT_IT);
}
-static void omap_gp_timer_input(void *opaque, int line, int on)
+static int omap_gp_timer_input(void *opaque, int line, int on)
{
struct omap_gp_timer_s *s = (struct omap_gp_timer_s *) opaque;
int trigger;
@@ -221,15 +221,19 @@ static void omap_gp_timer_input(void *opaque, int line, int on)
if (s->capt2 == s->capt_num ++)
omap_gp_timer_intr(s, GPT_TCAR_IT);
}
+
+ return 1;
}
-static void omap_gp_timer_clk_update(void *opaque, int line, int on)
+static int omap_gp_timer_clk_update(void *opaque, int line, int on)
{
struct omap_gp_timer_s *timer = (struct omap_gp_timer_s *) opaque;
omap_gp_timer_sync(timer);
timer->rate = on ? omap_clk_getrate(timer->clk) : 0;
omap_gp_timer_update(timer);
+
+ return 1;
}
static void omap_gp_timer_clk_setup(struct omap_gp_timer_s *timer)
@@ -632,7 +636,7 @@ static inline void omap_gpio_module_int(struct omap2_gpio_s *s, int line)
omap_gpio_module_wake(s, line);
}
-static void omap_gpio_module_set(void *opaque, int line, int level)
+static int omap_gpio_module_set(void *opaque, int line, int level)
{
struct omap2_gpio_s *s = (struct omap2_gpio_s *) opaque;
@@ -645,6 +649,8 @@ static void omap_gpio_module_set(void *opaque, int line, int level)
omap_gpio_module_int(s, line);
s->inputs &= ~(1 << line);
}
+
+ return 1;
}
static void omap_gpio_module_reset(struct omap2_gpio_s *s)
diff --git a/hw/omap_dma.c b/hw/omap_dma.c
index ba980df..52ba18e 100644
--- a/hw/omap_dma.c
+++ b/hw/omap_dma.c
@@ -1541,7 +1541,7 @@ static CPUWriteMemoryFunc *omap_dma_writefn[] = {
omap_badwidth_write16,
};
-static void omap_dma_request(void *opaque, int drq, int req)
+static int omap_dma_request(void *opaque, int drq, int req)
{
struct omap_dma_s *s = (struct omap_dma_s *) opaque;
/* The request pins are level triggered in QEMU. */
@@ -1552,10 +1552,12 @@ static void omap_dma_request(void *opaque, int drq, int req)
}
} else
s->dma->drqbmp &= ~(1 << drq);
+
+ return 1;
}
/* XXX: this won't be needed once soc_dma knows about clocks. */
-static void omap_dma_clk_update(void *opaque, int line, int on)
+static int omap_dma_clk_update(void *opaque, int line, int on)
{
struct omap_dma_s *s = (struct omap_dma_s *) opaque;
int i;
@@ -1565,6 +1567,8 @@ static void omap_dma_clk_update(void *opaque, int line, int on)
for (i = 0; i < s->chans; i ++)
if (s->ch[i].active)
soc_dma_set_request(s->ch[i].dma, on);
+
+ return 1;
}
static void omap_dma_setcaps(struct omap_dma_s *s)
diff --git a/hw/omap_mmc.c b/hw/omap_mmc.c
index bc46edf..e4e3088 100644
--- a/hw/omap_mmc.c
+++ b/hw/omap_mmc.c
@@ -555,7 +555,7 @@ static CPUWriteMemoryFunc *omap_mmc_writefn[] = {
omap_badwidth_write16,
};
-static void omap_mmc_cover_cb(void *opaque, int line, int level)
+static int omap_mmc_cover_cb(void *opaque, int line, int level)
{
struct omap_mmc_s *host = (struct omap_mmc_s *) opaque;
@@ -570,6 +570,8 @@ static void omap_mmc_cover_cb(void *opaque, int line, int level)
qemu_set_irq(host->coverswitch, level);
host->cdet_state = level;
}
+
+ return 1;
}
struct omap_mmc_s *omap_mmc_init(target_phys_addr_t base,
diff --git a/hw/openpic.c b/hw/openpic.c
index def20eb..3f8d7b0 100644
--- a/hw/openpic.c
+++ b/hw/openpic.c
@@ -346,7 +346,7 @@ static void openpic_update_irq(openpic_t *opp, int n_IRQ)
}
}
-static void openpic_set_irq(void *opaque, int n_IRQ, int level)
+static int openpic_set_irq(void *opaque, int n_IRQ, int level)
{
openpic_t *opp = opaque;
IRQ_src_t *src;
@@ -365,6 +365,8 @@ static void openpic_set_irq(void *opaque, int n_IRQ, int level)
src->pending = 1;
}
openpic_update_irq(opp, n_IRQ);
+
+ return 1;
}
static void openpic_reset (openpic_t *opp)
diff --git a/hw/palm.c b/hw/palm.c
index 9bc6eec..96c12a0 100644
--- a/hw/palm.c
+++ b/hw/palm.c
@@ -138,7 +138,7 @@ static void palmte_button_event(void *opaque, int keycode)
!(keycode & 0x80));
}
-static void palmte_onoff_gpios(void *opaque, int line, int level)
+static int palmte_onoff_gpios(void *opaque, int line, int level)
{
switch (line) {
case 0:
@@ -163,6 +163,8 @@ static void palmte_onoff_gpios(void *opaque, int line, int level)
__FUNCTION__, line - 4, level ? "high" : "low");
break;
}
+
+ return 1;
}
static void palmte_gpio_setup(struct omap_mpu_state_s *cpu)
diff --git a/hw/pc.c b/hw/pc.c
index 167d628..54b9b0b 100644
--- a/hw/pc.c
+++ b/hw/pc.c
@@ -116,7 +116,7 @@ int cpu_get_pic_interrupt(CPUState *env)
return intno;
}
-static void pic_irq_request(void *opaque, int irq, int level)
+static int pic_irq_request(void *opaque, int irq, int level)
{
CPUState *env = first_cpu;
@@ -132,6 +132,8 @@ static void pic_irq_request(void *opaque, int irq, int level)
else
cpu_reset_interrupt(env, CPU_INTERRUPT_HARD);
}
+
+ return 1;
}
/* PC cmos mappings */
diff --git a/hw/pc.h b/hw/pc.h
index d64d8a6..0ed9037 100644
--- a/hw/pc.h
+++ b/hw/pc.h
@@ -45,7 +45,7 @@ int apic_accept_pic_intr(CPUState *env);
void apic_deliver_pic_intr(CPUState *env, int level);
int apic_get_interrupt(CPUState *env);
IOAPICState *ioapic_init(void);
-void ioapic_set_irq(void *opaque, int vector, int level);
+int ioapic_set_irq(void *opaque, int vector, int level);
/* i8254.c */
diff --git a/hw/pci.c b/hw/pci.c
index a0f91a8..dc7f9ff 100644
--- a/hw/pci.c
+++ b/hw/pci.c
@@ -47,7 +47,7 @@ struct PCIBus {
};
static void pci_update_mappings(PCIDevice *d);
-static void pci_set_irq(void *opaque, int irq_num, int level);
+static int pci_set_irq(void *opaque, int irq_num, int level);
target_phys_addr_t pci_mem_base;
static int pci_irq_index;
@@ -485,7 +485,7 @@ uint32_t pci_data_read(void *opaque, uint32_t addr, int len)
/* generic PCI irq support */
/* 0 <= irq_num <= 3. level must be 0 or 1 */
-static void pci_set_irq(void *opaque, int irq_num, int level)
+static int pci_set_irq(void *opaque, int irq_num, int level)
{
PCIDevice *pci_dev = (PCIDevice *)opaque;
PCIBus *bus;
@@ -493,7 +493,7 @@ static void pci_set_irq(void *opaque, int irq_num, int level)
change = level - pci_dev->irq_state[irq_num];
if (!change)
- return;
+ return 1;
pci_dev->irq_state[irq_num] = level;
for (;;) {
@@ -505,6 +505,8 @@ static void pci_set_irq(void *opaque, int irq_num, int level)
}
bus->irq_count[irq_num] += change;
bus->set_irq(bus->irq_opaque, irq_num, bus->irq_count[irq_num] != 0);
+
+ return 1;
}
/***********************************************************/
diff --git a/hw/pcnet.c b/hw/pcnet.c
index 188e5ff..0c9c1a9 100644
--- a/hw/pcnet.c
+++ b/hw/pcnet.c
@@ -2047,10 +2047,12 @@ void pci_pcnet_init(PCIBus *bus, NICInfo *nd, int devfn)
#if defined (TARGET_SPARC) && !defined(TARGET_SPARC64) // Avoid compile failure
#include "sun4m.h"
-static void parent_lance_reset(void *opaque, int irq, int level)
+static int parent_lance_reset(void *opaque, int irq, int level)
{
if (level)
pcnet_h_reset(opaque);
+
+ return 1;
}
static void lance_mem_writew(void *opaque, target_phys_addr_t addr,
diff --git a/hw/pl061.c b/hw/pl061.c
index 6db5e39..09899e7 100644
--- a/hw/pl061.c
+++ b/hw/pl061.c
@@ -214,7 +214,7 @@ static void pl061_reset(pl061_state *s)
s->cr = 0xff;
}
-static void pl061_set_irq(void * opaque, int irq, int level)
+static int pl061_set_irq(void * opaque, int irq, int level)
{
pl061_state *s = (pl061_state *)opaque;
uint8_t mask;
@@ -226,6 +226,8 @@ static void pl061_set_irq(void * opaque, int irq, int level)
s->data |= mask;
pl061_update(s);
}
+
+ return 1;
}
static CPUReadMemoryFunc *pl061_readfn[] = {
diff --git a/hw/pl190.c b/hw/pl190.c
index 267c26b..ef5094c 100644
--- a/hw/pl190.c
+++ b/hw/pl190.c
@@ -56,7 +56,7 @@ static void pl190_update(pl190_state *s)
qemu_set_irq(s->fiq, set);
}
-static void pl190_set_irq(void *opaque, int irq, int level)
+static int pl190_set_irq(void *opaque, int irq, int level)
{
pl190_state *s = (pl190_state *)opaque;
@@ -65,6 +65,8 @@ static void pl190_set_irq(void *opaque, int irq, int level)
else
s->level &= ~(1u << irq);
pl190_update(s);
+
+ return 1;
}
static void pl190_update_vectors(pl190_state *s)
diff --git a/hw/ppc.c b/hw/ppc.c
index 60d6e86..8ce522d 100644
--- a/hw/ppc.c
+++ b/hw/ppc.c
@@ -54,7 +54,7 @@ static void ppc_set_irq (CPUState *env, int n_IRQ, int level)
}
/* PowerPC 6xx / 7xx internal IRQ controller */
-static void ppc6xx_set_irq (void *opaque, int pin, int level)
+static int ppc6xx_set_irq (void *opaque, int pin, int level)
{
CPUState *env = opaque;
int cur_level;
@@ -163,13 +163,15 @@ static void ppc6xx_set_irq (void *opaque, int pin, int level)
fprintf(logfile, "%s: unknown IRQ pin %d\n", __func__, pin);
}
#endif
- return;
+ return 1;
}
if (level)
env->irq_input_state |= 1 << pin;
else
env->irq_input_state &= ~(1 << pin);
}
+
+ return 1;
}
void ppc6xx_irq_init (CPUState *env)
@@ -180,7 +182,7 @@ void ppc6xx_irq_init (CPUState *env)
#if defined(TARGET_PPC64)
/* PowerPC 970 internal IRQ controller */
-static void ppc970_set_irq (void *opaque, int pin, int level)
+static int ppc970_set_irq (void *opaque, int pin, int level)
{
CPUState *env = opaque;
int cur_level;
@@ -287,13 +289,15 @@ static void ppc970_set_irq (void *opaque, int pin, int level)
fprintf(logfile, "%s: unknown IRQ pin %d\n", __func__, pin);
}
#endif
- return;
+ return 1;
}
if (level)
env->irq_input_state |= 1 << pin;
else
env->irq_input_state &= ~(1 << pin);
}
+
+ return 1;
}
void ppc970_irq_init (CPUState *env)
@@ -304,7 +308,7 @@ void ppc970_irq_init (CPUState *env)
#endif /* defined(TARGET_PPC64) */
/* PowerPC 40x internal IRQ controller */
-static void ppc40x_set_irq (void *opaque, int pin, int level)
+static int ppc40x_set_irq (void *opaque, int pin, int level)
{
CPUState *env = opaque;
int cur_level;
@@ -406,13 +410,15 @@ static void ppc40x_set_irq (void *opaque, int pin, int level)
fprintf(logfile, "%s: unknown IRQ pin %d\n", __func__, pin);
}
#endif
- return;
+ return 1;
}
if (level)
env->irq_input_state |= 1 << pin;
else
env->irq_input_state &= ~(1 << pin);
}
+
+ return 1;
}
void ppc40x_irq_init (CPUState *env)
diff --git a/hw/ppc4xx_devs.c b/hw/ppc4xx_devs.c
index d240f0e..e55da8b 100644
--- a/hw/ppc4xx_devs.c
+++ b/hw/ppc4xx_devs.c
@@ -357,7 +357,7 @@ static void ppcuic_trigger_irq (ppcuic_t *uic)
}
}
-static void ppcuic_set_irq (void *opaque, int irq_num, int level)
+static int ppcuic_set_irq (void *opaque, int irq_num, int level)
{
ppcuic_t *uic;
uint32_t mask, sr;
@@ -373,7 +373,7 @@ static void ppcuic_set_irq (void *opaque, int irq_num, int level)
}
#endif
if (irq_num < 0 || irq_num > 31)
- return;
+ return 1;
sr = uic->uicsr;
/* Update status register */
@@ -399,6 +399,8 @@ static void ppcuic_set_irq (void *opaque, int irq_num, int level)
#endif
if (sr != uic->uicsr)
ppcuic_trigger_irq(uic);
+
+ return 1;
}
static target_ulong dcr_read_uic (void *opaque, int dcrn)
diff --git a/hw/pxa2xx.c b/hw/pxa2xx.c
index 2c838e5..a804c97 100644
--- a/hw/pxa2xx.c
+++ b/hw/pxa2xx.c
@@ -2016,7 +2016,7 @@ static struct pxa2xx_fir_s *pxa2xx_fir_init(target_phys_addr_t base,
return s;
}
-static void pxa2xx_reset(void *opaque, int line, int level)
+static int pxa2xx_reset(void *opaque, int line, int level)
{
struct pxa2xx_state_s *s = (struct pxa2xx_state_s *) opaque;
@@ -2024,6 +2024,8 @@ static void pxa2xx_reset(void *opaque, int line, int level)
cpu_reset(s->env);
/* TODO: reset peripherals */
}
+
+ return 1;
}
/* Initialise a PXA270 integrated chip (ARM based core). */
diff --git a/hw/pxa2xx_gpio.c b/hw/pxa2xx_gpio.c
index e3a30bc..3295f8d 100644
--- a/hw/pxa2xx_gpio.c
+++ b/hw/pxa2xx_gpio.c
@@ -87,7 +87,7 @@ static const int pxa2xx_gpio_wake[PXA2XX_GPIO_BANKS] = {
0x8003fe1b, 0x002001fc, 0xec080000, 0x0012007f,
};
-static void pxa2xx_gpio_set(void *opaque, int line, int level)
+static int pxa2xx_gpio_set(void *opaque, int line, int level)
{
struct pxa2xx_gpio_info_s *s = (struct pxa2xx_gpio_info_s *) opaque;
int bank;
@@ -95,7 +95,7 @@ static void pxa2xx_gpio_set(void *opaque, int line, int level)
if (line >= s->lines) {
printf("%s: No GPIO pin %i\n", __FUNCTION__, line);
- return;
+ return 1;
}
bank = line >> 5;
@@ -117,6 +117,8 @@ static void pxa2xx_gpio_set(void *opaque, int line, int level)
/* Wake-up GPIOs */
if (s->cpu_env->halted && (mask & ~s->dir[bank] & pxa2xx_gpio_wake[bank]))
cpu_interrupt(s->cpu_env, CPU_INTERRUPT_EXITTB);
+
+ return 1;
}
static void pxa2xx_gpio_handler_update(struct pxa2xx_gpio_info_s *s) {
diff --git a/hw/pxa2xx_pcmcia.c b/hw/pxa2xx_pcmcia.c
index 1e96ee4..84f27dd 100644
--- a/hw/pxa2xx_pcmcia.c
+++ b/hw/pxa2xx_pcmcia.c
@@ -130,13 +130,13 @@ static CPUWriteMemoryFunc *pxa2xx_pcmcia_io_writefn[] = {
pxa2xx_pcmcia_io_write,
};
-static void pxa2xx_pcmcia_set_irq(void *opaque, int line, int level)
+static int pxa2xx_pcmcia_set_irq(void *opaque, int line, int level)
{
struct pxa2xx_pcmcia_s *s = (struct pxa2xx_pcmcia_s *) opaque;
if (!s->irq)
- return;
+ return 1;
- qemu_set_irq(s->irq, level);
+ return qemu_set_irq(s->irq, level);
}
struct pxa2xx_pcmcia_s *pxa2xx_pcmcia_init(target_phys_addr_t base)
diff --git a/hw/pxa2xx_pic.c b/hw/pxa2xx_pic.c
index a3611b8..0328f24 100644
--- a/hw/pxa2xx_pic.c
+++ b/hw/pxa2xx_pic.c
@@ -68,7 +68,7 @@ static void pxa2xx_pic_update(void *opaque)
/* Note: Here level means state of the signal on a pin, not
* IRQ/FIQ distinction as in PXA Developer Manual. */
-static void pxa2xx_pic_set_irq(void *opaque, int irq, int level)
+static int pxa2xx_pic_set_irq(void *opaque, int irq, int level)
{
struct pxa2xx_pic_state_s *s = (struct pxa2xx_pic_state_s *) opaque;
int int_set = (irq >= 32);
@@ -80,6 +80,8 @@ static void pxa2xx_pic_set_irq(void *opaque, int irq, int level)
s->int_pending[int_set] &= ~(1 << irq);
pxa2xx_pic_update(opaque);
+
+ return 1;
}
static inline uint32_t pxa2xx_pic_highest(struct pxa2xx_pic_state_s *s) {
diff --git a/hw/rc4030.c b/hw/rc4030.c
index bf440db..245118d 100644
--- a/hw/rc4030.c
+++ b/hw/rc4030.c
@@ -420,7 +420,7 @@ static void update_jazz_irq(rc4030State *s)
qemu_irq_lower(s->jazz_bus_irq);
}
-static void rc4030_irq_jazz_request(void *opaque, int irq, int level)
+static int rc4030_irq_jazz_request(void *opaque, int irq, int level)
{
rc4030State *s = opaque;
@@ -431,6 +431,8 @@ static void rc4030_irq_jazz_request(void *opaque, int irq, int level)
}
update_jazz_irq(s);
+
+ return 1;
}
static void rc4030_periodic_timer(void *opaque)
diff --git a/hw/sbi.c b/hw/sbi.c
index 8d264f1..0e767e5 100644
--- a/hw/sbi.c
+++ b/hw/sbi.c
@@ -52,12 +52,14 @@ static void sbi_check_interrupts(void *opaque)
{
}
-static void sbi_set_irq(void *opaque, int irq, int level)
+static int sbi_set_irq(void *opaque, int irq, int level)
{
+ return 1;
}
-static void sbi_set_timer_irq_cpu(void *opaque, int cpu, int level)
+static int sbi_set_timer_irq_cpu(void *opaque, int cpu, int level)
{
+ return 1;
}
static uint32_t sbi_mem_readl(void *opaque, target_phys_addr_t addr)
diff --git a/hw/sharpsl.h b/hw/sharpsl.h
index 184aae6..2054017 100644
--- a/hw/sharpsl.h
+++ b/hw/sharpsl.h
@@ -12,7 +12,7 @@
/* zaurus.c */
struct scoop_info_s *scoop_init(struct pxa2xx_state_s *cpu,
int instance, target_phys_addr_t target_base);
-void scoop_gpio_set(void *opaque, int line, int level);
+int scoop_gpio_set(void *opaque, int line, int level);
qemu_irq *scoop_gpio_in_get(struct scoop_info_s *s);
void scoop_gpio_out_set(struct scoop_info_s *s, int line,
qemu_irq handler);
diff --git a/hw/slavio_intctl.c b/hw/slavio_intctl.c
index 6a5d505..dec137b 100644
--- a/hw/slavio_intctl.c
+++ b/hw/slavio_intctl.c
@@ -284,7 +284,7 @@ static void slavio_check_interrupts(void *opaque)
* "irq" here is the bit number in the system interrupt register to
* separate serial and keyboard interrupts sharing a level.
*/
-static void slavio_set_irq(void *opaque, int irq, int level)
+static int slavio_set_irq(void *opaque, int irq, int level)
{
SLAVIO_INTCTLState *s = opaque;
uint32_t mask = 1 << irq;
@@ -305,9 +305,11 @@ static void slavio_set_irq(void *opaque, int irq, int level)
}
slavio_check_interrupts(s);
}
+
+ return 1;
}
-static void slavio_set_timer_irq_cpu(void *opaque, int cpu, int level)
+static int slavio_set_timer_irq_cpu(void *opaque, int cpu, int level)
{
SLAVIO_INTCTLState *s = opaque;
@@ -322,6 +324,8 @@ static void slavio_set_timer_irq_cpu(void *opaque, int cpu, int level)
}
slavio_check_interrupts(s);
+
+ return 1;
}
static void slavio_intctl_save(QEMUFile *f, void *opaque)
diff --git a/hw/sparc32_dma.c b/hw/sparc32_dma.c
index c69b559..8b9fda6 100644
--- a/hw/sparc32_dma.c
+++ b/hw/sparc32_dma.c
@@ -116,7 +116,7 @@ void ledma_memory_write(void *opaque, target_phys_addr_t addr,
}
}
-static void dma_set_irq(void *opaque, int irq, int level)
+static int dma_set_irq(void *opaque, int irq, int level)
{
DMAState *s = opaque;
if (level) {
@@ -128,6 +128,8 @@ static void dma_set_irq(void *opaque, int irq, int level)
DPRINTF("Lower IRQ\n");
qemu_irq_lower(s->irq);
}
+
+ return 1;
}
void espdma_memory_read(void *opaque, uint8_t *buf, int len)
diff --git a/hw/spitz.c b/hw/spitz.c
index fc77174..33e6a17 100644
--- a/hw/spitz.c
+++ b/hw/spitz.c
@@ -261,7 +261,7 @@ static void spitz_keyboard_sense_update(struct spitz_keyboard_s *s)
s->sense_state = sense;
}
-static void spitz_keyboard_strobe(void *opaque, int line, int level)
+static int spitz_keyboard_strobe(void *opaque, int line, int level)
{
struct spitz_keyboard_s *s = (struct spitz_keyboard_s *) opaque;
@@ -270,6 +270,8 @@ static void spitz_keyboard_strobe(void *opaque, int line, int level)
else
s->strobe_state &= ~(1 << line);
spitz_keyboard_sense_update(s);
+
+ return 1;
}
static void spitz_keyboard_keydown(struct spitz_keyboard_s *s, int keycode)
@@ -621,7 +623,7 @@ static void corgi_ssp_write(void *opaque, uint32_t value)
max111x_write(max1111, value);
}
-static void corgi_ssp_gpio_cs(void *opaque, int line, int level)
+static int corgi_ssp_gpio_cs(void *opaque, int line, int level)
{
switch (line) {
case 0:
@@ -634,6 +636,8 @@ static void corgi_ssp_gpio_cs(void *opaque, int line, int level)
max_en = !level;
break;
}
+
+ return 1;
}
#define MAX1111_BATT_VOLT 1
@@ -729,13 +733,15 @@ static void spitz_microdrive_attach(struct pxa2xx_state_s *cpu)
#define SPITZ_GPIO_WM 5
#ifdef HAS_AUDIO
-static void spitz_wm8750_addr(void *opaque, int line, int level)
+static int spitz_wm8750_addr(void *opaque, int line, int level)
{
i2c_slave *wm = (i2c_slave *) opaque;
if (level)
i2c_set_slave_address(wm, SPITZ_WM_ADDRH);
else
i2c_set_slave_address(wm, SPITZ_WM_ADDRL);
+
+ return 1;
}
#endif
@@ -774,7 +780,7 @@ static void spitz_akita_i2c_setup(struct pxa2xx_state_s *cpu)
/* Other peripherals */
-static void spitz_out_switch(void *opaque, int line, int level)
+static int spitz_out_switch(void *opaque, int line, int level)
{
switch (line) {
case 0:
@@ -799,6 +805,8 @@ static void spitz_out_switch(void *opaque, int line, int level)
spitz_adc_temp_on(opaque, line, level);
break;
}
+
+ return 1;
}
#define SPITZ_SCP_LED_GREEN 1
@@ -846,11 +854,13 @@ static void spitz_scoop_gpio_setup(struct pxa2xx_state_s *cpu,
static int spitz_hsync;
-static void spitz_lcd_hsync_handler(void *opaque, int line, int level)
+static int spitz_lcd_hsync_handler(void *opaque, int line, int level)
{
struct pxa2xx_state_s *cpu = (struct pxa2xx_state_s *) opaque;
qemu_set_irq(pxa2xx_gpio_in_get(cpu->gpio)[SPITZ_GPIO_HSYNC], spitz_hsync);
spitz_hsync ^= 1;
+
+ return 1;
}
static void spitz_gpio_setup(struct pxa2xx_state_s *cpu, int slots)
diff --git a/hw/ssd0323.c b/hw/ssd0323.c
index e496fe7..9b0e45e 100644
--- a/hw/ssd0323.c
+++ b/hw/ssd0323.c
@@ -268,11 +268,13 @@ static void ssd0323_invalidate_display(void * opaque)
}
/* Command/data input. */
-static void ssd0323_cd(void *opaque, int n, int level)
+static int ssd0323_cd(void *opaque, int n, int level)
{
ssd0323_state *s = (ssd0323_state *)opaque;
DPRINTF("%s mode\n", level ? "Data" : "Command");
s->mode = level ? SSD0323_DATA : SSD0323_CMD;
+
+ return 1;
}
static void ssd0323_save(QEMUFile *f, void *opaque)
diff --git a/hw/stellaris.c b/hw/stellaris.c
index 5948079..b5fcf1e 100644
--- a/hw/stellaris.c
+++ b/hw/stellaris.c
@@ -980,12 +980,12 @@ static void stellaris_adc_update(stellaris_adc_state *s)
qemu_set_irq(s->irq, level);
}
-static void stellaris_adc_trigger(void *opaque, int irq, int level)
+static int stellaris_adc_trigger(void *opaque, int irq, int level)
{
stellaris_adc_state *s = (stellaris_adc_state *)opaque;
if ((s->actss & 1) == 0) {
- return;
+ return 1;
}
/* Some applications use the ADC as a random number source, so introduce
@@ -995,6 +995,8 @@ static void stellaris_adc_trigger(void *opaque, int irq, int level)
stellaris_adc_fifo_write(s, 0, 0x200 + ((s->noise >> 16) & 7));
s->ris |= 1;
stellaris_adc_update(s);
+
+ return 1;
}
static void stellaris_adc_reset(stellaris_adc_state *s)
@@ -1221,11 +1223,13 @@ typedef struct {
int current_dev;
} stellaris_ssi_bus_state;
-static void stellaris_ssi_bus_select(void *opaque, int irq, int level)
+static int stellaris_ssi_bus_select(void *opaque, int irq, int level)
{
stellaris_ssi_bus_state *s = (stellaris_ssi_bus_state *)opaque;
s->current_dev = level;
+
+ return 1;
}
static int stellaris_ssi_bus_xfer(void *opaque, int val)
diff --git a/hw/sun4c_intctl.c b/hw/sun4c_intctl.c
index 88cd4a5..462f62c 100644
--- a/hw/sun4c_intctl.c
+++ b/hw/sun4c_intctl.c
@@ -146,7 +146,7 @@ static void sun4c_check_interrupts(void *opaque)
/*
* "irq" here is the bit number in the system interrupt register
*/
-static void sun4c_set_irq(void *opaque, int irq, int level)
+static int sun4c_set_irq(void *opaque, int irq, int level)
{
Sun4c_INTCTLState *s = opaque;
uint32_t mask = 1 << irq;
@@ -165,6 +165,8 @@ static void sun4c_set_irq(void *opaque, int irq, int level)
}
sun4c_check_interrupts(s);
}
+
+ return 1;
}
static void sun4c_intctl_save(QEMUFile *f, void *opaque)
diff --git a/hw/sun4m.c b/hw/sun4m.c
index d1c5b94..945926a 100644
--- a/hw/sun4m.c
+++ b/hw/sun4m.c
@@ -318,7 +318,7 @@ void cpu_check_irqs(CPUState *env)
}
}
-static void cpu_set_irq(void *opaque, int irq, int level)
+static int cpu_set_irq(void *opaque, int irq, int level)
{
CPUState *env = opaque;
@@ -332,10 +332,13 @@ static void cpu_set_irq(void *opaque, int irq, int level)
env->pil_in &= ~(1 << irq);
cpu_check_irqs(env);
}
+
+ return 1;
}
-static void dummy_cpu_set_irq(void *opaque, int irq, int level)
+static int dummy_cpu_set_irq(void *opaque, int irq, int level)
{
+ return 1;
}
static void *slavio_misc;
diff --git a/hw/tc6393xb.c b/hw/tc6393xb.c
index 6db6dcb..0b10bcb 100644
--- a/hw/tc6393xb.c
+++ b/hw/tc6393xb.c
@@ -78,16 +78,17 @@ qemu_irq *tc6393xb_gpio_in_get(struct tc6393xb_s *s)
return s->gpio_in;
}
-static void tc6393xb_gpio_set(void *opaque, int line, int level)
+static int tc6393xb_gpio_set(void *opaque, int line, int level)
{
// struct tc6393xb_s *s = opaque;
if (line > TC6393XB_GPIOS) {
printf("%s: No GPIO pin %i\n", __FUNCTION__, line);
- return;
+ return 1;
}
// FIXME: how does the chip reflect the GPIO input level change?
+ return 1;
}
void tc6393xb_gpio_out_set(struct tc6393xb_s *s, int line,
diff --git a/hw/tusb6010.c b/hw/tusb6010.c
index 6f37779..96a4e73 100644
--- a/hw/tusb6010.c
+++ b/hw/tusb6010.c
@@ -683,7 +683,7 @@ static void tusb_power_tick(void *opaque)
}
}
-static void tusb_musb_core_intr(void *opaque, int source, int level)
+static int tusb_musb_core_intr(void *opaque, int source, int level)
{
struct tusb_s *s = (struct tusb_s *) opaque;
uint16_t otg_status = s->otg_status;
@@ -730,6 +730,8 @@ static void tusb_musb_core_intr(void *opaque, int source, int level)
tusb_intr_update(s);
break;
}
+
+ return 1;
}
struct tusb_s *tusb6010_init(qemu_irq intr)
diff --git a/hw/twl92230.c b/hw/twl92230.c
index ad49eac..4573c6f 100644
--- a/hw/twl92230.c
+++ b/hw/twl92230.c
@@ -195,16 +195,18 @@ static inline int from_bcd(uint8_t val)
return ((val >> 4) * 10) + (val & 0x0f);
}
-static void menelaus_gpio_set(void *opaque, int line, int level)
+static int menelaus_gpio_set(void *opaque, int line, int level)
{
struct menelaus_s *s = (struct menelaus_s *) opaque;
/* No interrupt generated */
s->inputs &= ~(1 << line);
s->inputs |= level << line;
+
+ return 1;
}
-static void menelaus_pwrbtn_set(void *opaque, int line, int level)
+static int menelaus_pwrbtn_set(void *opaque, int line, int level)
{
struct menelaus_s *s = (struct menelaus_s *) opaque;
@@ -213,6 +215,8 @@ static void menelaus_pwrbtn_set(void *opaque, int line, int level)
menelaus_update(s);
}
s->pwrbtn_state = level;
+
+ return 1;
}
#define MENELAUS_REV 0x01
diff --git a/hw/versatilepb.c b/hw/versatilepb.c
index f9e9988..a85afd2 100644
--- a/hw/versatilepb.c
+++ b/hw/versatilepb.c
@@ -49,7 +49,7 @@ static void vpb_sic_update_pic(vpb_sic_state *s)
}
}
-static void vpb_sic_set_irq(void *opaque, int irq, int level)
+static int vpb_sic_set_irq(void *opaque, int irq, int level)
{
vpb_sic_state *s = (vpb_sic_state *)opaque;
if (level)
@@ -59,6 +59,8 @@ static void vpb_sic_set_irq(void *opaque, int irq, int level)
if (s->pic_enable & (1u << irq))
qemu_set_irq(s->parent[irq], level);
vpb_sic_update(s);
+
+ return 1;
}
static uint32_t vpb_sic_read(void *opaque, target_phys_addr_t offset)
diff --git a/hw/zaurus.c b/hw/zaurus.c
index c475eaa..0b66859 100644
--- a/hw/zaurus.c
+++ b/hw/zaurus.c
@@ -166,7 +166,7 @@ static CPUWriteMemoryFunc *scoop_writefn[] = {
scoop_writeb,
};
-void scoop_gpio_set(void *opaque, int line, int level)
+int scoop_gpio_set(void *opaque, int line, int level)
{
struct scoop_info_s *s = (struct scoop_info_s *) s;
@@ -174,6 +174,8 @@ void scoop_gpio_set(void *opaque, int line, int level)
s->gpio_level |= (1 << line);
else
s->gpio_level &= ~(1 << line);
+
+ return 1;
}
qemu_irq *scoop_gpio_in_get(struct scoop_info_s *s)
^ permalink raw reply related [flat|nested] 29+ messages in thread
end of thread, other threads:[~2008-10-29 15:22 UTC | newest]
Thread overview: 29+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2008-06-29 14:02 [Qemu-devel] [PATCH 0/3] Fix guest time drift under heavy load Gleb Natapov
2008-06-29 14:02 ` [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information Gleb Natapov
2008-06-29 14:14 ` Avi Kivity
2008-06-29 14:18 ` Gleb Natapov
2008-06-29 14:53 ` Paul Brook
2008-06-29 15:37 ` Gleb Natapov
2008-06-29 14:38 ` Paul Brook
2008-06-29 15:40 ` Gleb Natapov
2008-06-29 18:11 ` Paul Brook
2008-06-29 19:44 ` Gleb Natapov
2008-06-29 20:34 ` Paul Brook
2008-06-29 20:49 ` Gleb Natapov
2008-06-30 13:26 ` Gleb Natapov
2008-06-30 14:00 ` Paul Brook
2008-06-30 14:28 ` Gleb Natapov
2008-06-30 14:35 ` Paul Brook
2008-06-29 20:58 ` [Qemu-devel] " Jan Kiszka
2008-06-29 21:16 ` Paul Brook
2008-06-29 21:42 ` Dor Laor
2008-06-29 21:47 ` Jan Kiszka
2008-06-29 21:54 ` Paul Brook
2008-06-30 13:18 ` Gleb Natapov
2008-06-29 14:02 ` [Qemu-devel] [PATCH 2/3] Fix time drift problem under high load when PIT is in use Gleb Natapov
2008-06-29 14:40 ` [Qemu-devel] " Jan Kiszka
2008-06-29 15:52 ` Gleb Natapov
2008-06-29 14:02 ` [Qemu-devel] [PATCH 3/3] Fix time drift problem under high load when RTC " Gleb Natapov
2008-06-29 14:37 ` [Qemu-devel] Re: [PATCH 0/3] Fix guest time drift under heavy load Jan Kiszka
-- strict thread matches above, loose matches on Subject: below --
2008-10-29 15:22 [Qemu-devel] [RESEND][PATCH " Gleb Natapov
2008-10-29 15:22 ` [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information Gleb Natapov
2008-06-23 10:49 [Qemu-devel] [PATCH 0/3] Fix guest time drift under heavy load Gleb Natapov
2008-06-23 10:49 ` [Qemu-devel] [PATCH 1/3] Change qemu_set_irq() to return status information Gleb Natapov
This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).