summaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
authorAmaan Cheval <amaan.cheval@gmail.com>2018-08-13 16:25:34 +0530
committerJoel Sherrill <joel@rtems.org>2018-08-13 10:48:20 -0500
commitbc7313134f8192214cf74116c0b54d3eb6081fcf (patch)
tree77479c6478f98046f00a5f2817494fa2e682baf5
parentbsps/x86_64: Add support for RTEMS interrupts (diff)
downloadrtems-bc7313134f8192214cf74116c0b54d3eb6081fcf.tar.bz2
bsps/x86_64: Add APIC timer based clock driver
The APIC timer is calibrated by running the i8254 PIT for a fraction of a second (determined by PIT_CALIBRATE_DIVIDER) and counting how many times the APIC counter has ticked. The calibration can be run multiple times (determined by APIC_TIMER_NUM_CALIBRATIONS) and averaged out. Updates #2898.
-rw-r--r--bsps/x86_64/amd64/clock/clock.c299
-rw-r--r--bsps/x86_64/amd64/headers.am3
-rw-r--r--bsps/x86_64/amd64/include/apic.h62
-rw-r--r--bsps/x86_64/amd64/include/clock.h99
-rw-r--r--bsps/x86_64/amd64/include/pic.h75
-rw-r--r--bsps/x86_64/amd64/interrupts/pic.c76
-rw-r--r--c/src/lib/libbsp/x86_64/amd64/Makefile.am4
-rw-r--r--cpukit/score/cpu/x86_64/include/rtems/score/cpu_asm.h23
8 files changed, 640 insertions, 1 deletions
diff --git a/bsps/x86_64/amd64/clock/clock.c b/bsps/x86_64/amd64/clock/clock.c
new file mode 100644
index 0000000000..76e537755a
--- /dev/null
+++ b/bsps/x86_64/amd64/clock/clock.c
@@ -0,0 +1,299 @@
+/*
+ * Copyright (c) 2018.
+ * Amaan Cheval <amaan.cheval@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
+ * SUCH DAMAGE.
+ */
+
+#include <stdio.h>
+#include <assert.h>
+#include <bsp.h>
+#include <rtems.h>
+#include <pic.h>
+#include <apic.h>
+#include <clock.h>
+#include <rtems/score/idt.h>
+#include <rtems/timecounter.h>
+#include <rtems/score/cpu.h>
+#include <rtems/score/cpuimpl.h>
+#include <rtems/score/x86_64.h>
+#include <bsp/irq-generic.h>
+
+/* Use the amd64_apic_base as an array of 32-bit APIC registers */
+volatile uint32_t *amd64_apic_base;
+static struct timecounter amd64_clock_tc;
+
+extern volatile uint32_t Clock_driver_ticks;
+extern void apic_spurious_handler(void);
+extern void Clock_isr(void *param);
+
+static uint32_t amd64_clock_get_timecount(struct timecounter *tc)
+{
+ return Clock_driver_ticks;
+}
+
+/*
+ * When the CPUID instruction is executed with a source operand of 1 in the EAX
+ * register, bit 9 of the CPUID feature flags returned in the EDX register
+ * indicates the presence (set) or absence (clear) of a local APIC.
+ */
+bool has_apic_support()
+{
+ uint32_t eax, ebx, ecx, edx;
+ cpuid(1, &eax, &ebx, &ecx, &edx);
+ return (edx >> 9) & 1;
+}
+
+/*
+ * Initializes the APIC by hardware and software enabling it, and sets up the
+ * amd64_apic_base pointer that can be used as a 32-bit addressable array to
+ * access APIC registers.
+ */
+void apic_initialize(void)
+{
+ if ( !has_apic_support() ) {
+ printf("warning: cpuid claims no APIC support - trying anyway.\n");
+ }
+
+ /*
+ * The APIC base address is a 36-bit physical address.
+ * We have identity-paging setup at the moment, which makes this simpler, but
+ * that's something to note since the variables below use virtual addresses.
+ *
+ * Bits 0-11 (inclusive) are 0, making the address page (4KiB) aligned.
+ * Bits 12-35 (inclusive) of the MSR point to the rest of the address.
+ */
+ uint64_t apic_base_msr = rdmsr(APIC_BASE_MSR);
+ amd64_apic_base = (uint32_t*) apic_base_msr;
+ amd64_apic_base = (uint32_t*) ((uintptr_t) amd64_apic_base & 0x0ffffff000);
+
+ /* Hardware enable the APIC just to be sure */
+ wrmsr(
+ APIC_BASE_MSR,
+ apic_base_msr | APIC_BASE_MSR_ENABLE,
+ apic_base_msr >> 32
+ );
+
+ DBG_PRINTF("APIC is at 0x%" PRIxPTR "\n", (uintptr_t) amd64_apic_base);
+ DBG_PRINTF(
+ "APIC ID at *0x%" PRIxPTR "=0x%" PRIx32 "\n",
+ (uintptr_t) &amd64_apic_base[APIC_REGISTER_APICID],
+ amd64_apic_base[APIC_REGISTER_APICID]
+ );
+
+ DBG_PRINTF(
+ "APIC spurious vector register *0x%" PRIxPTR "=0x%" PRIx32 "\n",
+ (uintptr_t) &amd64_apic_base[APIC_REGISTER_SPURIOUS],
+ amd64_apic_base[APIC_REGISTER_SPURIOUS]
+ );
+
+ /*
+ * Software enable the APIC by mapping spurious vector and setting enable bit.
+ */
+ uintptr_t old;
+ amd64_install_raw_interrupt(
+ BSP_VECTOR_SPURIOUS,
+ (uintptr_t) apic_spurious_handler,
+ &old
+ );
+ amd64_apic_base[APIC_REGISTER_SPURIOUS] =
+ APIC_SPURIOUS_ENABLE | BSP_VECTOR_SPURIOUS;
+
+ DBG_PRINTF(
+ "APIC spurious vector register *0x%" PRIxPTR "=0x%" PRIx32 "\n",
+ (uintptr_t) &amd64_apic_base[APIC_REGISTER_SPURIOUS],
+ amd64_apic_base[APIC_REGISTER_SPURIOUS]
+ );
+
+ /*
+ * The PIC may send spurious IRQs even when disabled, and without remapping
+ * IRQ7 would look like an exception.
+ */
+ pic_remap(PIC1_REMAP_DEST, PIC2_REMAP_DEST);
+ pic_disable();
+}
+
+static void apic_isr(void *param)
+{
+ Clock_isr(param);
+ amd64_apic_base[APIC_REGISTER_EOI] = APIC_EOI_ACK;
+}
+
+void apic_timer_install_handler(void)
+{
+ rtems_status_code sc = rtems_interrupt_handler_install(
+ BSP_VECTOR_APIC_TIMER,
+ "APIC timer",
+ RTEMS_INTERRUPT_UNIQUE,
+ apic_isr,
+ NULL
+ );
+ assert(sc == RTEMS_SUCCESSFUL);
+}
+
+uint32_t apic_timer_calibrate(void)
+{
+ /* Configure APIC timer in one-shot mode to prepare for calibration */
+ amd64_apic_base[APIC_REGISTER_LVT_TIMER] = BSP_VECTOR_APIC_TIMER;
+ amd64_apic_base[APIC_REGISTER_TIMER_DIV] = APIC_TIMER_SELECT_DIVIDER;
+
+ /* Enable the channel 2 timer gate and disable the speaker output */
+ uint8_t chan2_value = (inport_byte(PIT_PORT_CHAN2_GATE) | PIT_CHAN2_TIMER_BIT)
+ & ~PIT_CHAN2_SPEAKER_BIT;
+ outport_byte(PIT_PORT_CHAN2_GATE, chan2_value);
+
+ /* Initialize PIT in one-shot mode on Channel 2 */
+ outport_byte(
+ PIT_PORT_MCR,
+ PIT_SELECT_CHAN2 | PIT_SELECT_ACCESS_LOHI |
+ PIT_SELECT_ONE_SHOT_MODE | PIT_SELECT_BINARY_MODE
+ );
+
+ /*
+ * Disable interrupts while we calibrate for 2 reasons:
+ * - Writing values to the PIT should be atomic (for now, this is okay
+ * because we're the only ones ever touching the PIT ports, but an
+ * interrupt resetting the PIT could mess calibration up).
+ * - We need to make sure that no interrupts throw our synchronization of
+ * the APIC timer off.
+ */
+ amd64_disable_interrupts();
+
+ /* Set PIT reload value */
+ uint32_t pit_ticks = PIT_CALIBRATE_TICKS;
+ uint8_t low_tick = pit_ticks & 0xff;
+ uint8_t high_tick = (pit_ticks >> 8) & 0xff;
+
+ outport_byte(PIT_PORT_CHAN2, low_tick);
+ stub_io_wait();
+ outport_byte(PIT_PORT_CHAN2, high_tick);
+
+ /* Start APIC timer's countdown */
+ const uint32_t apic_calibrate_init_count = 0xffffffff;
+
+ /* Restart PIT by disabling the gated input and then re-enabling it */
+ chan2_value &= ~PIT_CHAN2_TIMER_BIT;
+ outport_byte(PIT_PORT_CHAN2_GATE, chan2_value);
+ chan2_value |= PIT_CHAN2_TIMER_BIT;
+ outport_byte(PIT_PORT_CHAN2_GATE, chan2_value);
+ amd64_apic_base[APIC_REGISTER_TIMER_INITCNT] = apic_calibrate_init_count;
+
+ while ( pit_ticks <= PIT_CALIBRATE_TICKS ) {
+ /* Send latch command to read multi-byte value atomically */
+ outport_byte(PIT_PORT_MCR, PIT_SELECT_CHAN2);
+ pit_ticks = inport_byte(PIT_PORT_CHAN2);
+ pit_ticks |= inport_byte(PIT_PORT_CHAN2) << 8;
+ }
+ uint32_t apic_currcnt = amd64_apic_base[APIC_REGISTER_TIMER_CURRCNT];
+
+ DBG_PRINTF("PIT stopped at 0x%" PRIx32 "\n", pit_ticks);
+
+ /* Stop APIC timer to calculate ticks to time ratio */
+ amd64_apic_base[APIC_REGISTER_LVT_TIMER] = APIC_DISABLE;
+
+ /* Get counts passed since we started counting */
+ uint32_t apic_ticks_per_sec = apic_calibrate_init_count - apic_currcnt;
+
+ DBG_PRINTF(
+ "APIC ticks passed in 1/%d of a second: 0x%" PRIx32 "\n",
+ PIT_CALIBRATE_DIVIDER,
+ apic_ticks_per_sec
+ );
+
+ /* We ran the PIT for a fraction of a second */
+ apic_ticks_per_sec = apic_ticks_per_sec * PIT_CALIBRATE_DIVIDER;
+
+ /* Re-enable interrupts now that calibration is complete */
+ amd64_enable_interrupts();
+
+ /* Confirm that the APIC timer never hit 0 and IRQ'd during calibration */
+ assert(Clock_driver_ticks == 0);
+ assert(apic_ticks_per_sec != 0 &&
+ apic_ticks_per_sec != apic_calibrate_init_count);
+
+ DBG_PRINTF(
+ "CPU frequency: 0x%" PRIu64 "\nAPIC ticks/sec: 0x%" PRIu32 "\n",
+ /* Multiply to undo effects of divider */
+ (uint64_t) apic_ticks_per_sec * APIC_TIMER_DIVIDE_VALUE,
+ apic_ticks_per_sec
+ );
+
+ return apic_ticks_per_sec;
+}
+
+void apic_timer_initialize(uint64_t desired_freq_hz)
+{
+ uint32_t apic_ticks_per_sec = 0;
+ uint32_t apic_tick_collections[APIC_TIMER_NUM_CALIBRATIONS] = {0};
+ uint64_t apic_tick_total = 0;
+ for (uint32_t i = 0; i < APIC_TIMER_NUM_CALIBRATIONS; i++) {
+ apic_tick_collections[i] = apic_timer_calibrate();
+ apic_tick_total += apic_tick_collections[i];
+ }
+ apic_ticks_per_sec = apic_tick_total / APIC_TIMER_NUM_CALIBRATIONS;
+
+ /*
+ * The APIC timer counter is decremented at the speed of the CPU bus
+ * frequency (and we use a frequency divider).
+ *
+ * This means:
+ * apic_ticks_per_sec = (cpu_bus_frequency / timer_divide_value)
+ *
+ * Therefore:
+ * reload_value = apic_ticks_per_sec / desired_freq_hz
+ */
+ uint32_t apic_timer_reload_value = apic_ticks_per_sec / desired_freq_hz;
+
+ amd64_apic_base[APIC_REGISTER_LVT_TIMER] = BSP_VECTOR_APIC_TIMER | APIC_SELECT_TMR_PERIODIC;
+ amd64_apic_base[APIC_REGISTER_TIMER_DIV] = APIC_TIMER_SELECT_DIVIDER;
+ amd64_apic_base[APIC_REGISTER_TIMER_INITCNT] = apic_timer_reload_value;
+}
+
+void amd64_clock_driver_initialize(void)
+{
+ uint64_t us_per_tick = rtems_configuration_get_microseconds_per_tick();
+ uint64_t irq_ticks_per_sec = 1000000 / us_per_tick;
+ DBG_PRINTF(
+ "us_per_tick = %d\nDesired frequency = %d irqs/sec\n",
+ us_per_tick,
+ irq_ticks_per_sec
+ );
+
+ /* Setup and enable the APIC itself */
+ apic_initialize();
+ /* Setup and initialize the APIC timer */
+ apic_timer_initialize(irq_ticks_per_sec);
+
+ amd64_clock_tc.tc_get_timecount = amd64_clock_get_timecount;
+ amd64_clock_tc.tc_counter_mask = 0xffffffff;
+ amd64_clock_tc.tc_frequency = irq_ticks_per_sec;
+ amd64_clock_tc.tc_quality = RTEMS_TIMECOUNTER_QUALITY_CLOCK_DRIVER;
+ rtems_timecounter_install(&amd64_clock_tc);
+}
+
+#define Clock_driver_support_install_isr(_new) \
+ apic_timer_install_handler()
+
+#define Clock_driver_support_initialize_hardware() \
+ amd64_clock_driver_initialize()
+
+#include "../../../shared/dev/clock/clockimpl.h"
diff --git a/bsps/x86_64/amd64/headers.am b/bsps/x86_64/amd64/headers.am
index f9f42e7fd3..68f5858406 100644
--- a/bsps/x86_64/amd64/headers.am
+++ b/bsps/x86_64/amd64/headers.am
@@ -1,7 +1,10 @@
## This file was generated by "./boostrap -H".
include_HEADERS =
+include_HEADERS += ../../../../../../bsps/x86_64/amd64/include/apic.h
include_HEADERS += ../../../../../../bsps/x86_64/amd64/include/bsp.h
include_HEADERS += include/bspopts.h
+include_HEADERS += ../../../../../../bsps/x86_64/amd64/include/clock.h
+include_HEADERS += ../../../../../../bsps/x86_64/amd64/include/pic.h
include_HEADERS += ../../../../../../bsps/x86_64/amd64/include/start.h
include_HEADERS += ../../../../../../bsps/x86_64/amd64/include/tm27.h
diff --git a/bsps/x86_64/amd64/include/apic.h b/bsps/x86_64/amd64/include/apic.h
new file mode 100644
index 0000000000..f1e6495daa
--- /dev/null
+++ b/bsps/x86_64/amd64/include/apic.h
@@ -0,0 +1,62 @@
+/*
+ * Copyright (c) 2018.
+ * Amaan Cheval <amaan.cheval@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
+ * SUCH DAMAGE.
+ */
+
+#ifndef _AMD64_APIC_H
+#define _AMD64_APIC_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* The address of the MSR pointing to the APIC base physical address */
+#define APIC_BASE_MSR 0x1B
+/* Value to hardware-enable the APIC through the APIC_BASE_MSR */
+#define APIC_BASE_MSR_ENABLE 0x800
+
+/*
+ * Since amd64_apic_base is an array of 32-bit elements, these byte-offsets
+ * need to be divided by 4 to index the array.
+ */
+#define APIC_OFFSET(val) (val >> 2)
+
+#define APIC_REGISTER_APICID APIC_OFFSET(0x20)
+#define APIC_REGISTER_EOI APIC_OFFSET(0x0B0)
+#define APIC_REGISTER_SPURIOUS APIC_OFFSET(0x0F0)
+#define APIC_REGISTER_LVT_TIMER APIC_OFFSET(0x320)
+#define APIC_REGISTER_TIMER_INITCNT APIC_OFFSET(0x380)
+#define APIC_REGISTER_TIMER_CURRCNT APIC_OFFSET(0x390)
+#define APIC_REGISTER_TIMER_DIV APIC_OFFSET(0x3E0)
+
+#define APIC_DISABLE 0x10000
+#define APIC_EOI_ACK 0
+#define APIC_SELECT_TMR_PERIODIC 0x20000
+#define APIC_SPURIOUS_ENABLE 0x100
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _AMD64_APIC_H */
diff --git a/bsps/x86_64/amd64/include/clock.h b/bsps/x86_64/amd64/include/clock.h
new file mode 100644
index 0000000000..4219c92d48
--- /dev/null
+++ b/bsps/x86_64/amd64/include/clock.h
@@ -0,0 +1,99 @@
+/*
+ * Copyright (c) 2018.
+ * Amaan Cheval <amaan.cheval@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
+ * SUCH DAMAGE.
+ */
+
+#ifndef _AMD64_CLOCK_H
+#define _AMD64_CLOCK_H
+
+#include <rtems/score/basedefs.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef ASM
+ extern volatile uint32_t *amd64_apic_base;
+ bool has_apic_support(void);
+ void apic_initialize(void);
+ void apic_timer_install_handler(void);
+ uint32_t apic_timer_calibrate(void);
+ void apic_timer_initialize(uint64_t desired_freq_hz);
+ void amd64_clock_driver_initialize(void);
+#endif
+
+/* Number of times to calibrate the APIC timer to average it out */
+#define APIC_TIMER_NUM_CALIBRATIONS 5
+/* Default divide value used by APIC timer */
+#define APIC_TIMER_DIVIDE_VALUE 16
+/* Value to set in register to pick the divide value above */
+#define APIC_TIMER_SELECT_DIVIDER 3
+
+#define PIT_FREQUENCY 1193180
+/*
+ * The PIT_FREQUENCY determines how many times the PIT counter is decremented
+ * per second - therefore, we can calculate how many ticks we set based on what
+ * fraction of a second we're okay with spending on calibration
+ */
+#define PIT_CALIBRATE_DIVIDER 20
+#define PIT_CALIBRATE_TICKS (PIT_FREQUENCY/PIT_CALIBRATE_DIVIDER)
+/* Since the PIT only has 2 one-byte registers, the maximum tick value is
+ * limited to 16-bits. We can set the PIT to use a frequency divider if
+ * needed. */
+RTEMS_STATIC_ASSERT(
+ PIT_CALIBRATE_TICKS <= 0xffff,
+ PIT_CALIBRATE_DIVIDER
+);
+
+/* I/O ports for the PIT */
+#define PIT_PORT_CHAN0 0x40
+#define PIT_PORT_CHAN1 0x41
+#define PIT_PORT_CHAN2 0x42
+/*
+ * The input to channel 2 can be gated through software, using bit 0 of port
+ * 0x61.
+ */
+#define PIT_PORT_CHAN2_GATE 0x61
+#define PIT_CHAN2_TIMER_BIT 1
+#define PIT_CHAN2_SPEAKER_BIT 2
+/* The PIT mode/command register */
+#define PIT_PORT_MCR 0x43
+
+/* PIT values to select channels, access, and operating modes */
+#define PIT_SELECT_CHAN0 0b00000000
+#define PIT_SELECT_CHAN1 0b01000000
+#define PIT_SELECT_CHAN2 0b10000000
+/*
+ * In the lo/hi mode, the low-byte is sent to the data port, followed by the
+ * high-byte; this makes it important that this be an atomic operation.
+ */
+#define PIT_SELECT_ACCESS_LOHI 0b00110000
+#define PIT_SELECT_ONE_SHOT_MODE 0b00000010
+#define PIT_SELECT_BINARY_MODE 0
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _AMD64_CLOCK_H */
diff --git a/bsps/x86_64/amd64/include/pic.h b/bsps/x86_64/amd64/include/pic.h
new file mode 100644
index 0000000000..f2b0aa83e2
--- /dev/null
+++ b/bsps/x86_64/amd64/include/pic.h
@@ -0,0 +1,75 @@
+/*
+ * Copyright (c) 2018.
+ * Amaan Cheval <amaan.cheval@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
+ * SUCH DAMAGE.
+ */
+
+#ifndef _AMD64_PIC_H
+#define _AMD64_PIC_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#define PIC1 0x20 /* IO base address for master PIC */
+#define PIC2 0xA0 /* IO base address for slave PIC */
+#define PIC1_COMMAND PIC1
+#define PIC1_DATA (PIC1+1)
+#define PIC2_COMMAND PIC2
+#define PIC2_DATA (PIC2+1)
+
+/* reinitialize the PIC controllers, giving them specified vector offsets
+ rather than 8h and 70h, as configured by default */
+
+#define PIC_ICW1_ICW4 0x01 /* ICW4 (not) needed */
+#define PIC_ICW1_SINGLE 0x02 /* Single (cascade) mode */
+#define PIC_ICW1_INTERVAL4 0x04 /* Call address interval 4 (8) */
+#define PIC_ICW1_LEVEL 0x08 /* Level triggered (edge) mode */
+#define PIC_ICW1_INIT 0x10 /* Initialization - required! */
+
+#define PIC_ICW4_8086 0x01 /* 8086/88 (MCS-80/85) mode */
+#define PIC_ICW4_AUTO 0x02 /* Auto (normal) EOI */
+#define PIC_ICW4_BUF_SLAVE 0x08 /* Buffered mode/slave */
+#define PIC_ICW4_BUF_MASTER 0x0C /* Buffered mode/master */
+#define PIC_ICW4_SFNM 0x10 /* Special fully nested (not) */
+
+/* This remaps IRQ0 to vector number 0x20 and so on (i.e. IDT[32]) */
+#define PIC1_REMAP_DEST 0x20
+#define PIC2_REMAP_DEST 0x28
+
+/* Remap PIC1's interrupts to offset1 and PIC2's to offset2 */
+void pic_remap(uint8_t offset1, uint8_t offset2);
+
+/**
+ * Mask all interrupt requests on PIC.
+ *
+ * @note Even with all interrupts masked, the PIC may still send spurious
+ * interrupts (IRQ7), so we should handle them still.
+ */
+void pic_disable(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _AMD64_PIC_H */
diff --git a/bsps/x86_64/amd64/interrupts/pic.c b/bsps/x86_64/amd64/interrupts/pic.c
new file mode 100644
index 0000000000..c5a890b885
--- /dev/null
+++ b/bsps/x86_64/amd64/interrupts/pic.c
@@ -0,0 +1,76 @@
+/*
+ * Copyright (c) 2018.
+ * Amaan Cheval <amaan.cheval@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
+ * SUCH DAMAGE.
+ */
+
+#include <stdint.h>
+#include <rtems.h>
+#include <rtems/score/basedefs.h>
+#include <rtems/score/x86_64.h>
+#include <rtems/score/cpuimpl.h>
+#include <bsp/irq-generic.h>
+#include <pic.h>
+
+void pic_remap(uint8_t offset1, uint8_t offset2)
+{
+ uint8_t a1, a2;
+
+ /* save masks */
+ a1 = inport_byte(PIC1_DATA);
+ a2 = inport_byte(PIC2_DATA);
+
+ /* start the initialization sequence in cascade mode */
+ outport_byte(PIC1_COMMAND, PIC_ICW1_INIT | PIC_ICW1_ICW4);
+ stub_io_wait();
+ outport_byte(PIC2_COMMAND, PIC_ICW1_INIT | PIC_ICW1_ICW4);
+ stub_io_wait();
+ /* ICW2: Master PIC vector offset */
+ outport_byte(PIC1_DATA, offset1);
+ stub_io_wait();
+ /* ICW2: Slave PIC vector offset */
+ outport_byte(PIC2_DATA, offset2);
+ stub_io_wait();
+ /* ICW3: tell Master PIC that there is a slave PIC at IRQ2 (0000 0100) */
+ outport_byte(PIC1_DATA, 4);
+ stub_io_wait();
+ /* ICW3: tell Slave PIC its cascade identity (0000 0010) */
+ outport_byte(PIC2_DATA, 2);
+ stub_io_wait();
+
+ outport_byte(PIC1_DATA, PIC_ICW4_8086);
+ stub_io_wait();
+ outport_byte(PIC2_DATA, PIC_ICW4_8086);
+ stub_io_wait();
+
+ /* restore saved masks. */
+ outport_byte(PIC1_DATA, a1);
+ outport_byte(PIC2_DATA, a2);
+}
+
+void pic_disable(void)
+{
+ /* Mask all lines on both master and slave PIC to disable */
+ outport_byte(PIC1_DATA, 0xff);
+ outport_byte(PIC2_DATA, 0xff);
+}
diff --git a/c/src/lib/libbsp/x86_64/amd64/Makefile.am b/c/src/lib/libbsp/x86_64/amd64/Makefile.am
index d4102cdfb4..101c98b96c 100644
--- a/c/src/lib/libbsp/x86_64/amd64/Makefile.am
+++ b/c/src/lib/libbsp/x86_64/amd64/Makefile.am
@@ -27,11 +27,13 @@ librtemsbsp_a_SOURCES += ../../../../../../bsps/x86_64/amd64/start/page.c
librtemsbsp_a_SOURCES += ../../../../../../bsps/shared/start/sbrk.c
librtemsbsp_a_SOURCES += ../../../../../../bsps/shared/dev/getentropy/getentropy-cpucounter.c
librtemsbsp_a_SOURCES += ../../../../../../bsps/shared/start/bspreset-empty.c
+# interrupts
+librtemsbsp_a_SOURCES += ../../../../../../bsps/x86_64/amd64/interrupts/pic.c
librtemsbsp_a_SOURCES += ../../../../../../bsps/x86_64/amd64/interrupts/idt.c
librtemsbsp_a_SOURCES += ../../../../../../bsps/x86_64/amd64/interrupts/isr_handler.S
librtemsbsp_a_SOURCES += ../../../../../../bsps/shared/irq/irq-default-handler.c
# clock
-librtemsbsp_a_SOURCES += ../../../../../../bsps/shared/dev/clock/clock-simidle.c
+librtemsbsp_a_SOURCES += ../../../../../../bsps/x86_64/amd64/clock/clock.c
# console
librtemsbsp_a_SOURCES += ../../../../../../bsps/shared/dev/serial/console-termios-init.c
librtemsbsp_a_SOURCES += ../../../../../../bsps/shared/dev/serial/console-termios.c
diff --git a/cpukit/score/cpu/x86_64/include/rtems/score/cpu_asm.h b/cpukit/score/cpu/x86_64/include/rtems/score/cpu_asm.h
index 09807f1489..4ad50b9f42 100644
--- a/cpukit/score/cpu/x86_64/include/rtems/score/cpu_asm.h
+++ b/cpukit/score/cpu/x86_64/include/rtems/score/cpu_asm.h
@@ -67,6 +67,21 @@ RTEMS_INLINE_ROUTINE void cpuid(
: "a" (code) );
}
+RTEMS_INLINE_ROUTINE uint64_t rdmsr(uint32_t msr)
+{
+ uint32_t low, high;
+ __asm__ volatile ( "rdmsr" :
+ "=a" (low), "=d" (high) :
+ "c" (msr) );
+ return low | (uint64_t) high << 32;
+}
+
+RTEMS_INLINE_ROUTINE void wrmsr(uint32_t msr, uint32_t low, uint32_t high)
+{
+ __asm__ volatile ( "wrmsr" : :
+ "a" (low), "d" (high), "c" (msr) );
+}
+
RTEMS_INLINE_ROUTINE void amd64_enable_interrupts(void)
{
__asm__ volatile ( "sti" );
@@ -76,6 +91,14 @@ RTEMS_INLINE_ROUTINE void amd64_disable_interrupts(void)
{
__asm__ volatile ( "cli" );
}
+
+RTEMS_INLINE_ROUTINE void stub_io_wait(void)
+{
+ /* XXX: This likely won't be required on any modern boards, but this function
+ * exists so it's easier to find all the places it may be used.
+ */
+}
+
#endif /* !ASM */
#endif