feat: user mode api for timer/rtc through fs mapping.
feat: interrupt handlers now have the option to accept customized payload.
refactor: creare a new device class of pseudo device, hope that it will clear things
refactor: move ps2 keyboard driver out of kernel code base.
fix: pcache is now abandon the use of valloc api, as the access is unaligned when allocating page size buffer.
fix: pcached write/read should use direct file i/o and must not failed with ENOMEM when buffer allocation failed.
chore: group the device file ops for better clarity
isrm_bindiv(LUNAIX_SYS_CALL, syscall_hndlr);
}
-struct hwtimer_context*
+struct hwtimer*
hwtimer_choose()
{
- struct hwtimer_context* timer;
+ struct hwtimer* timer;
timer = apic_hwtimer_context();
if (timer->supported(timer)) {
// TODO select alternatives...
panick("no timer to use.");
-}
-
-struct hwrtc*
-hwrtc_choose()
-{
- struct hwrtc* rtc = mc146818a_rtc_context();
-
- return rtc;
}
\ No newline at end of file
static char iv_bmp[(IV_EX_END - IV_BASE_END) / 8];
static isr_cb handlers[TOTAL_IV];
+static ptr_t ivhand_payload[TOTAL_IV];
extern void
intr_routine_fallback(const isr_param* param);
assert(iv < 256);
return handlers[iv];
+}
+
+ptr_t
+isrm_get_payload(int iv)
+{
+ assert(iv < 256);
+
+ return ivhand_payload[iv];
+}
+
+void
+isrm_set_payload(int iv, ptr_t payload)
+{
+ assert(iv < 256);
+
+ ivhand_payload[iv] = payload;
}
\ No newline at end of file
#include <lunaix/clock.h>
+#include <lunaix/ds/mutex.h>
#include <lunaix/input.h>
#include <lunaix/isrm.h>
-#include <lunaix/peripheral/ps2kbd.h>
+#include <lunaix/keyboard.h>
#include <lunaix/syslog.h>
#include <lunaix/timer.h>
#include <hal/intc.h>
-#include <sys/cpu.h>
#include <klibc/string.h>
+#include <sys/cpu.h>
#include <sys/interrupts.h>
#include <sys/port_io.h>
+#define PS2_PORT_ENC_DATA 0x60
+#define PS2_PORT_ENC_CMDREG 0x60
+#define PS2_PORT_CTRL_STATUS 0x64
+#define PS2_PORT_CTRL_CMDREG 0x64
+
+#define PS2_STATUS_OFULL 0x1
+#define PS2_STATUS_IFULL 0x2
+
+#define PS2_RESULT_ACK 0xfa
+#define PS2_RESULT_NAK 0xfe // resend
+#define PS2_RESULT_ECHO 0xee
+#define PS2_RESULT_TEST_OK 0x55
+
+// PS/2 keyboard device related commands
+#define PS2_KBD_CMD_SETLED 0xed
+#define PS2_KBD_CMD_ECHO 0xee
+#define PS2_KBD_CMD_SCANCODE_SET 0xf0
+#define PS2_KBD_CMD_IDENTIFY 0xf2
+#define PS2_KBD_CMD_SCAN_ENABLE 0xf4
+#define PS2_KBD_CMD_SCAN_DISABLE 0xf5
+
+// PS/2 *controller* related commands
+#define PS2_CMD_PORT1_DISABLE 0xad
+#define PS2_CMD_PORT1_ENABLE 0xae
+#define PS2_CMD_PORT2_DISABLE 0xa7
+#define PS2_CMD_PORT2_ENABLE 0xa8
+#define PS2_CMD_SELFTEST 0xaa
+#define PS2_CMD_SELFTEST_PORT1 0xab
+
+#define PS2_CMD_READ_CFG 0x20
+#define PS2_CMD_WRITE_CFG 0x60
+
+#define PS2_CFG_P1INT 0x1
+#define PS2_CFG_P2INT 0x2
+#define PS2_CFG_TRANSLATION 0x40
+
+#define PS2_DELAY 1000
+
+#define PS2_CMD_QUEUE_SIZE 8
+
+#define PS2_NO_ARG 0xff00
+
+struct ps2_cmd
+{
+ char cmd;
+ char arg;
+};
+
+struct ps2_kbd_state
+{
+ volatile char state;
+ volatile char masked;
+ volatile kbd_kstate_t key_state;
+ kbd_keycode_t* translation_table;
+};
+
+struct ps2_cmd_queue
+{
+ struct ps2_cmd cmd_queue[PS2_CMD_QUEUE_SIZE];
+ int queue_ptr;
+ int queue_len;
+ mutex_t mutex;
+};
+
+/**
+ * @brief 向PS/2控制器的控制端口(0x64)发送指令并等待返回代码。
+ * 注意,对于没有返回代码的命令请使用`ps2_post_cmd`,否则会造成死锁。
+ * 通过调用该方法向控制器发送指令,请区别 ps2_issue_dev_cmd
+ *
+ * @param cmd
+ * @param args
+ */
+static u8_t
+ps2_issue_cmd(char cmd, u16_t arg);
+
+/**
+ * @brief 向PS/2控制器的编码器端口(0x60)发送指令并等待返回代码。
+ * 注意,对于没有返回代码的命令请使用`ps2_post_cmd`,否则会造成死锁。
+ * 通过调用该方法向PS/2设备发送指令,请区别 ps2_issue_cmd
+ *
+ * @param cmd
+ * @param args
+ */
+static u8_t
+ps2_issue_dev_cmd(char cmd, u16_t arg);
+
+/**
+ * @brief 向PS/2控制器发送指令,不等待返回代码。
+ *
+ * @param port 端口号
+ * @param cmd
+ * @param args
+ * @return char
+ */
+static void
+ps2_post_cmd(u8_t port, char cmd, u16_t arg);
+
+static void
+ps2_device_post_cmd(char cmd, char arg);
+
+static void
+ps2_kbd_init();
+
+static void
+ps2_process_cmd(void* arg);
+
#define PS2_DEV_CMD_MAX_ATTEMPTS 5
LOG_MODULE("i8042");
#define KBD_ENABLE_SPIRQ_FIX2
// #define KBD_DBGLOG
-void
+static void
intr_ps2_kbd_handler(const isr_param* param);
static u8_t
ps2_issue_cmd_wretry(char cmd, u16_t arg);
-void
+static void
ps2_device_post_cmd(char cmd, char arg)
{
mutex_lock(&cmd_q.mutex);
cpu_enable_interrupt();
}
+EXPORT_INPUT_DEV(i8042_keyboard, ps2_kbd_init);
-void
+static void
ps2_process_cmd(void* arg)
{
/*
cmd_q.queue_len--;
}
-void
+static void
kbd_buffer_key_event(kbd_keycode_t key, u8_t scancode, kbd_kstate_t state)
{
/*
}
}
-void
+static void
intr_ps2_kbd_handler(const isr_param* param)
{
--- /dev/null
+#include <lunaix/device.h>
+#include <lunaix/mm/page.h>
+
+static inline void
+rng_fill(void* data, size_t len)
+{
+ asm volatile("1:\n"
+ "rdrand %%eax\n"
+ "movl %%eax, (%0)\n"
+ "addl $4, %%eax\n"
+ "subl $4, %1\n"
+ "jnz 1b" ::"r"((ptr_t)data),
+ "r"((len & ~0x3))
+ : "%eax");
+}
+
+static int
+__rand_rd_pg(struct device* dev, void* buf, size_t offset)
+{
+ rng_fill(buf, PG_SIZE);
+ return PG_SIZE;
+}
+
+static int
+__rand_rd(struct device* dev, void* buf, size_t offset, size_t len)
+{
+ rng_fill(buf, len);
+ return len;
+}
+
+void
+pdev_randdev_init()
+{
+ struct device* devrand = device_addseq(NULL, NULL, "rand");
+ devrand->ops.read = __rand_rd;
+ devrand->ops.read_page = __rand_rd_pg;
+}
+EXPORT_PSEUDODEV(randdev, pdev_randdev_init);
\ No newline at end of file
#include <hal/hwrtc.h>
-const struct hwrtc* current_rtc;
+#include <lunaix/fs/twifs.h>
+#include <lunaix/fs/twimap.h>
+#include <lunaix/mm/valloc.h>
+#include <lunaix/status.h>
+
+#include <usr/lunaix/ioctl_defs.h>
+
+const struct hwrtc* primary_rtc;
+static int rtc_count = 0;
+
+DEFINE_LLIST(rtcs);
void
hwrtc_init()
{
- current_rtc = hwrtc_choose();
-
- current_rtc->init(current_rtc);
+ ptr_t init;
+ int index;
+ ldga_foreach(rtcdev, ptr_t, index, init)
+ {
+ ((void (*)())init)();
+ }
}
void
hwrtc_walltime(datetime_t* dt)
{
- current_rtc->get_walltime(current_rtc, dt);
-}
\ No newline at end of file
+ primary_rtc->get_walltime(primary_rtc, dt);
+}
+
+static int
+hwrtc_ioctl(struct device* dev, u32_t req, va_list args)
+{
+ struct hwrtc* rtc = (struct hwrtc*)dev->underlay;
+ switch (req) {
+ case RTCIO_IMSK:
+ rtc->set_mask(rtc);
+ break;
+ case RTCIO_IUNMSK:
+ rtc->cls_mask(rtc);
+ break;
+ case RTCIO_SETDT:
+ datetime_t* dt = va_arg(args, datetime_t*);
+ rtc->set_walltime(rtc, dt);
+ break;
+ case RTCIO_SETFREQ:
+ ticks_t* freq = va_arg(args, ticks_t*);
+
+ if (!freq) {
+ return EINVAL;
+ }
+ if (*freq) {
+ return rtc->chfreq(rtc, *freq);
+ }
+
+ *freq = rtc->base_freq;
+
+ break;
+ default:
+ return EINVAL;
+ }
+
+ return 0;
+}
+
+static int
+hwrtc_read(struct device* dev, void* buf, size_t offset, size_t len)
+{
+ struct hwrtc* rtc = (struct hwrtc*)dev->underlay;
+ *((ticks_t*)buf) = rtc->get_counts(rtc);
+
+ return sizeof(ticks_t);
+}
+
+struct hwrtc*
+hwrtc_alloc_new(char* name)
+{
+ struct hwrtc* rtc_instance = valloc(sizeof(struct hwrtc));
+
+ if (!rtc_instance) {
+ return NULL;
+ }
+
+ llist_append(&rtcs, &rtc_instance->rtc_list);
+
+ if (!primary_rtc) {
+ primary_rtc = rtc_instance;
+ }
+
+ rtc_instance->name = name;
+ struct device* rtcdev =
+ device_addsys(NULL, rtc_instance, "rtc%d", rtc_count);
+
+ rtcdev->ops.exec_cmd = hwrtc_ioctl;
+ rtcdev->ops.read = hwrtc_read;
+
+ rtc_instance->rtc_dev = rtcdev;
+
+ rtc_count++;
+
+ return rtc_instance;
+}
+
+static void
+__hwrtc_readinfo(struct twimap* mapping)
+{
+ struct hwrtc* rtc = twimap_data(mapping, struct hwrtc*);
+ twimap_printf(mapping, "device: %s\n", rtc->name);
+ twimap_printf(mapping, "frequency: %dHz\n", rtc->base_freq);
+ twimap_printf(mapping, "ticks count: %d\n", rtc->get_counts(rtc));
+ twimap_printf(
+ mapping, "ticking: %s\n", (rtc->state & RTC_STATE_MASKED) ? "no" : "yes");
+
+ datetime_t dt;
+ rtc->get_walltime(rtc, &dt);
+
+ twimap_printf(
+ mapping, "recorded date: %d/%d/%d\n", dt.year, dt.month, dt.day);
+ twimap_printf(
+ mapping, "recorded time: %d:%d:%d\n", dt.hour, dt.minute, dt.second);
+ twimap_printf(mapping, "recorded weekday: %d\n", dt.weekday);
+}
+
+static void
+hwrtc_twifs_export(struct hwrtc* rtc)
+{
+ const char* name = rtc->rtc_dev->name.value;
+ struct twimap* rtc_mapping = twifs_mapping(NULL, rtc, name);
+ rtc_mapping->read = __hwrtc_readinfo;
+}
+
+static void
+hwrtc_twifs_export_all()
+{
+ struct hwrtc *pos, *next;
+ llist_for_each(pos, next, &rtcs, rtc_list)
+ {
+ hwrtc_twifs_export(pos);
+ }
+}
+EXPORT_TWIFS_PLUGIN(rtc_fsexport, hwrtc_twifs_export_all);
\ No newline at end of file
*/
#include <lunaix/isrm.h>
+#include <lunaix/mm/valloc.h>
+#include <lunaix/status.h>
#include <hal/rtc/mc146818a.h>
#define RTC_REG_C 0xC
#define RTC_REG_D 0xD
+#define RTC_SET 0x80
+#define RTC_BIN (1 << 2)
+#define RTC_HOURFORM24 (1 << 1)
+
#define RTC_BIN_ENCODED(reg) (reg & 0x04)
#define RTC_24HRS_ENCODED(reg) (reg & 0x02)
{
struct hwrtc* rtc_context;
u32_t rtc_iv;
- int ticking;
- void (*on_tick_cb)(const struct hwrtc*);
+ u32_t tick_counts;
};
#define rtc_state(data) ((struct mc146818*)(data))
port_wrbyte(RTC_TARGET_PORT, val);
}
-static u8_t
-bcd2dec(u8_t bcd)
-{
- return ((bcd & 0xF0) >> 1) + ((bcd & 0xF0) >> 3) + (bcd & 0xf);
-}
-
static void
rtc_enable_timer()
{
- u8_t regB = rtc_read_reg(RTC_REG_B | WITH_NMI_DISABLED);
- rtc_write_reg(RTC_REG_B | WITH_NMI_DISABLED, regB | RTC_TIMER_ON);
+ u8_t regB = rtc_read_reg(RTC_REG_B);
+ rtc_write_reg(RTC_REG_B, regB | RTC_TIMER_ON);
}
static void
rtc_disable_timer()
{
- u8_t regB = rtc_read_reg(RTC_REG_B | WITH_NMI_DISABLED);
- rtc_write_reg(RTC_REG_B | WITH_NMI_DISABLED, regB & ~RTC_TIMER_ON);
+ u8_t regB = rtc_read_reg(RTC_REG_B);
+ rtc_write_reg(RTC_REG_B, regB & ~RTC_TIMER_ON);
}
static void
-clock_walltime(struct hwrtc* rtc, datetime_t* datetime)
+rtc_getwalltime(struct hwrtc* rtc, datetime_t* datetime)
{
datetime_t current;
datetime->second = rtc_read_reg(RTC_REG_SEC);
} while (!datatime_eq(datetime, ¤t));
- u8_t regbv = rtc_read_reg(RTC_REG_B);
+ datetime->year += RTC_CURRENT_CENTRY * 100;
+}
- // Convert from bcd to binary when needed
- if (!RTC_BIN_ENCODED(regbv)) {
- datetime->year = bcd2dec(datetime->year);
- datetime->month = bcd2dec(datetime->month);
- datetime->day = bcd2dec(datetime->day);
- datetime->hour = bcd2dec(datetime->hour);
- datetime->minute = bcd2dec(datetime->minute);
- datetime->second = bcd2dec(datetime->second);
- }
+static void
+rtc_setwalltime(struct hwrtc* rtc, datetime_t* datetime)
+{
+ u8_t reg = rtc_read_reg(RTC_REG_B);
+ reg = reg & ~RTC_SET;
- // To 24 hour format
- if (!RTC_24HRS_ENCODED(regbv) && (datetime->hour >> 7)) {
- datetime->hour = 12 + (datetime->hour & 0x80);
- }
+ rtc_write_reg(RTC_REG_B, reg | RTC_SET);
- datetime->year += RTC_CURRENT_CENTRY * 100;
+ rtc_write_reg(RTC_REG_YRS, datetime->year - RTC_CURRENT_CENTRY * 100);
+ rtc_write_reg(RTC_REG_MTH, datetime->month);
+ rtc_write_reg(RTC_REG_DAY, datetime->day);
+ rtc_write_reg(RTC_REG_WDY, datetime->weekday);
+ rtc_write_reg(RTC_REG_HRS, datetime->hour);
+ rtc_write_reg(RTC_REG_MIN, datetime->minute);
+ rtc_write_reg(RTC_REG_SEC, datetime->second);
+
+ rtc_write_reg(RTC_REG_B, reg & ~RTC_SET);
}
static int
}
static void
-rtc_init(struct hwrtc* rtc)
+__rtc_tick(const isr_param* param)
{
- u8_t regA = rtc_read_reg(RTC_REG_A | WITH_NMI_DISABLED);
- regA = (regA & ~0x7f) | RTC_FREQUENCY_1024HZ | RTC_DIVIDER_33KHZ;
- rtc_write_reg(RTC_REG_A | WITH_NMI_DISABLED, regA);
+ struct mc146818* state =
+ (struct mc146818*)isrm_get_payload(param->execp->vector);
- rtc_state(rtc->data)->rtc_context = rtc;
+ state->tick_counts++;
- // Make sure the rtc timer is disabled by default
- rtc_disable_timer();
+ (void)rtc_read_reg(RTC_REG_C);
}
-static struct mc146818 rtc_state = { .ticking = 0 };
-
static void
-__rtc_tick(const isr_param* param)
+rtc_set_mask(struct hwrtc* rtc)
{
- rtc_state.on_tick_cb(rtc_state.rtc_context);
-
- (void)rtc_read_reg(RTC_REG_C);
+ rtc->state = RTC_STATE_MASKED;
+ rtc_disable_timer();
}
static void
-rtc_do_ticking(struct hwrtc* rtc, void (*on_tick)())
+rtc_cls_mask(struct hwrtc* rtc)
{
- if (!on_tick || rtc_state(rtc->data)->ticking) {
- return;
- }
-
struct mc146818* state = rtc_state(rtc->data);
- state->ticking = 1;
- state->on_tick_cb = on_tick;
-
- /* We realise that using rtc to tick something has an extremely rare use
- * case (e.g., calibrating some timer). Therefore, we will release this
- * allocated IV when rtc ticking is no longer required to save IV
- * resources.
- */
- state->rtc_iv = isrm_bindirq(PC_AT_IRQ_RTC, __rtc_tick);
+ rtc->state = 0;
+ state->tick_counts = 0;
rtc_enable_timer();
}
-static void
-rtc_end_ticking(struct hwrtc* rtc)
+static int
+rtc_chfreq(struct hwrtc* rtc, int freq)
{
- if (!rtc_state(rtc->data)->ticking) {
- return;
- }
+ return ENOTSUP;
+}
- rtc_disable_timer();
+static int
+rtc_getcnt(struct hwrtc* rtc)
+{
+ struct mc146818* state = rtc_state(rtc->data);
+ return state->tick_counts;
+}
- // do some delay, ensure there is no more interrupt from rtc before we
- // release isr
- port_delay(1000);
+static void
+rtc_init()
+{
+ u8_t reg = rtc_read_reg(RTC_REG_A);
+ reg = (reg & ~0x7f) | RTC_FREQUENCY_1024HZ | RTC_DIVIDER_33KHZ;
+ rtc_write_reg(RTC_REG_A, reg);
- isrm_ivfree(rtc_state(rtc->data)->rtc_iv);
+ reg = RTC_BIN | RTC_HOURFORM24;
+ rtc_write_reg(RTC_REG_B, reg);
- rtc_state(rtc->data)->ticking = 0;
-}
+ // Make sure the rtc timer is disabled by default
+ rtc_disable_timer();
-static struct hwrtc hwrtc_mc146818a = { .name = "mc146818a",
- .data = &rtc_state,
- .init = rtc_init,
- .base_freq = RTC_TIMER_BASE_FREQUENCY,
- .supported = mc146818_check_support,
- .get_walltime = clock_walltime,
- .do_ticking = rtc_do_ticking,
- .end_ticking = rtc_end_ticking };
-
-struct hwrtc*
-mc146818a_rtc_context()
-{
- return &hwrtc_mc146818a;
+ struct hwrtc* rtc = hwrtc_alloc_new("mc146818");
+ struct mc146818* state = valloc(sizeof(struct mc146818));
+
+ state->rtc_context = rtc;
+ state->rtc_iv = isrm_bindirq(PC_AT_IRQ_RTC, __rtc_tick);
+ isrm_set_payload(state->rtc_iv, (ptr_t)state);
+
+ rtc->state = RTC_STATE_MASKED;
+ rtc->data = state;
+ rtc->base_freq = RTC_TIMER_BASE_FREQUENCY;
+ rtc->get_walltime = rtc_getwalltime;
+ rtc->set_walltime = rtc_setwalltime;
+ rtc->set_mask = rtc_set_mask;
+ rtc->cls_mask = rtc_cls_mask;
+ rtc->get_counts = rtc_getcnt;
+ rtc->chfreq = rtc_chfreq;
}
+EXPORT_RTC_DEVICE(mc146818, rtc_init);
\ No newline at end of file
LOG_MODULE("APIC_TIMER")
#define LVT_ENTRY_TIMER(vector, mode) (LVT_DELIVERY_FIXED | mode | vector)
-#define APIC_CALIBRATION_CONST 0x100000
+#define APIC_BASETICKS 0x100000
// Don't optimize them! Took me an half hour to figure that out...
-static volatile u32_t rtc_counter = 0;
static volatile u8_t apic_timer_done = 0;
static volatile ticks_t base_freq = 0;
static volatile ticks_t systicks = 0;
static timer_tick_cb tick_cb = NULL;
-static void
-__rtc_on_tick_cb(struct hwrtc* param)
-{
- rtc_counter++;
-}
-
static void
temp_intr_routine_apic_timer(const isr_param* param)
{
- base_freq = APIC_CALIBRATION_CONST / rtc_counter * current_rtc->base_freq;
apic_timer_done = 1;
}
}
static int
-apic_timer_check(struct hwtimer_context* hwt)
+apic_timer_check(struct hwtimer* hwt)
{
// TODO check whether apic timer is supported
return 1;
}
void
-apic_timer_init(struct hwtimer_context* timer,
- u32_t hertz,
- timer_tick_cb timer_cb)
+apic_timer_init(struct hwtimer* timer, u32_t hertz, timer_tick_cb timer_cb)
{
ticks_t frequency = hertz;
tick_cb = timer_cb;
}
#endif
- rtc_counter = 0;
apic_timer_done = 0;
- current_rtc->do_ticking(current_rtc, __rtc_on_tick_cb);
- apic_write_reg(APIC_TIMER_ICR, APIC_CALIBRATION_CONST); // start APIC timer
+ primary_rtc->cls_mask(primary_rtc);
+ apic_write_reg(APIC_TIMER_ICR, APIC_BASETICKS); // start APIC timer
// enable interrupt, just for our RTC start ticking!
cpu_enable_interrupt();
wait_until(apic_timer_done);
- current_rtc->end_ticking(current_rtc);
-
cpu_disable_interrupt();
+ primary_rtc->set_mask(primary_rtc);
+
+ base_freq = primary_rtc->get_counts(primary_rtc);
+ base_freq = APIC_BASETICKS / base_freq * primary_rtc->base_freq;
+
assert_msg(base_freq, "Fail to initialize timer (NOFREQ)");
kprintf(KINFO "hw: %u Hz; os: %u Hz\n", base_freq, frequency);
apic_write_reg(APIC_TIMER_ICR, tphz);
}
-struct hwtimer_context*
+struct hwtimer*
apic_hwtimer_context()
{
- static struct hwtimer_context apic_hwt = { .name = "apic_timer",
- .init = apic_timer_init,
- .supported = apic_timer_check,
- .systicks = apic_get_systicks };
+ static struct hwtimer apic_hwt = { .name = "apic_timer",
+ .init = apic_timer_init,
+ .supported = apic_timer_check,
+ .systicks = apic_get_systicks };
return &apic_hwt;
}
#include <hal/hwtimer.h>
#include <lunaix/spike.h>
-struct hwtimer_context* current_timer;
+#include <usr/lunaix/ioctl_defs.h>
-void
-hwtimer_init(u32_t hertz, void* tick_callback)
-{
- struct hwtimer_context* hwt_ctx = hwtimer_choose();
-
- hwt_ctx->init(hwt_ctx, hertz, tick_callback);
- hwt_ctx->running_freq = hertz;
-
- current_timer = hwt_ctx;
-}
+struct hwtimer* current_timer;
ticks_t
hwtimer_base_frequency()
ticks_t freq_ms = current_timer->running_freq / 1000;
return freq_ms * value;
+}
+
+static int
+__hwtimer_ioctl(struct device* dev, u32_t req, va_list args)
+{
+ struct hwtimer* hwt = (struct hwtimer*)dev->underlay;
+ switch (req) {
+ case TIMERIO_GETINFO:
+ // TODO
+ break;
+
+ default:
+ break;
+ }
+ return 0;
+}
+
+void
+hwtimer_init(u32_t hertz, void* tick_callback)
+{
+ struct hwtimer* hwt_ctx = hwtimer_choose();
+
+ hwt_ctx->init(hwt_ctx, hertz, tick_callback);
+ hwt_ctx->running_freq = hertz;
+
+ current_timer = hwt_ctx;
+
+ struct device* timerdev = device_addsys(NULL, hwt_ctx, hwt_ctx->name);
+
+ timerdev->ops.exec_cmd = __hwtimer_ioctl;
}
\ No newline at end of file
#include <hal/hwtimer.h>
-struct hwtimer_context* apic_hwtimer_context();
+struct hwtimer* apic_hwtimer_context();
#endif /* __LUNAIX_APIC_TIMER_H */
#ifndef __LUNAIX_HWRTC_H
#define __LUNAIX_HWRTC_H
+#include <lunaix/device.h>
+#include <lunaix/ds/ldga.h>
+#include <lunaix/ds/llist.h>
#include <lunaix/time.h>
+#define RTC_STATE_MASKED 0x1
+
+#define EXPORT_RTC_DEVICE(id, init_fn) \
+ export_ldga_el(rtcdev, id, ptr_t, init_fn)
+
struct hwrtc
{
+ struct llist_header rtc_list;
+ struct device* rtc_dev;
+
char* name;
void* data;
-
ticks_t base_freq;
-
- int (*supported)(struct hwrtc*);
- void (*init)(struct hwrtc*);
+ int state;
void (*get_walltime)(struct hwrtc*, datetime_t*);
-
- void (*do_ticking)(struct hwrtc*, void (*on_tick)());
- void (*end_ticking)(struct hwrtc*);
+ void (*set_walltime)(struct hwrtc*, datetime_t*);
+ void (*set_mask)(struct hwrtc*);
+ void (*cls_mask)(struct hwrtc*);
+ int (*get_counts)(struct hwrtc*);
+ int (*chfreq)(struct hwrtc*, int);
};
-extern const struct hwrtc* current_rtc;
+extern const struct hwrtc* primary_rtc;
void
hwrtc_init();
struct hwrtc*
-hwrtc_choose();
+hwrtc_alloc_new(char* driver_id);
void
hwrtc_walltime(datetime_t* dt);
#ifndef __LUNAIX_HWTIMER_H
#define __LUNAIX_HWTIMER_H
+#include <lunaix/device.h>
#include <lunaix/time.h>
#include <lunaix/types.h>
typedef void (*timer_tick_cb)();
-struct hwtimer_context
+struct hwtimer
{
char* name;
void* data;
- int (*supported)(struct hwtimer_context*);
- void (*init)(struct hwtimer_context*, u32_t hertz, timer_tick_cb);
+ struct device* timer_dev;
+
+ int (*supported)(struct hwtimer*);
+ void (*init)(struct hwtimer*, u32_t hertz, timer_tick_cb);
ticks_t (*systicks)();
ticks_t base_freq;
ticks_t running_freq;
};
-extern struct hwtimer_context* current_timer;
+extern struct hwtimer* current_timer;
void
hwtimer_init(u32_t hertz, void* tick_callback);
-struct hwtimer_context*
+struct hwtimer*
hwtimer_choose();
ticks_t
+++ /dev/null
-#ifndef __LUNAIX_RND_H
-#define __LUNAIX_RND_H
-
-#include <lunaix/types.h>
-
-static inline void
-rnd_fill(void* data, size_t len)
-{
- asm volatile("1:\n"
- "rdrand %%eax\n"
- "movl %%eax, (%0)\n"
- "addl $4, %%eax\n"
- "subl $4, %1\n"
- "jnz 1b" ::"r"((ptr_t)data),
- "r"((len & ~0x3))
- : "%eax");
-}
-
-int
-rnd_is_supported();
-
-#endif /* __LUNAIX_RND_H */
#define DEVICE_NAME_SIZE 32
#include <lunaix/ds/hstr.h>
+#include <lunaix/ds/ldga.h>
#include <lunaix/ds/llist.h>
+#include <lunaix/ds/semaphore.h>
#include <lunaix/types.h>
+/**
+ * @brief Export pseudo device
+ *
+ */
+#define EXPORT_PSEUDODEV(id, init_fn) \
+ export_ldga_el(pseudo_dev, id, ptr_t, init_fn)
+
#define DEV_STRUCT_MAGIC 0x5645444c
#define DEV_MSKIF 0x00000003
#define DEV_IFVOL 0x0 // volumetric (block) device
#define DEV_IFSEQ 0x1 // sequential (character) device
#define DEV_IFCAT 0x2 // a device category (as device groupping)
+#define DEV_IFSYS 0x3 // a system device
typedef unsigned int dev_t;
struct llist_header siblings;
struct llist_header children;
struct device* parent;
+ // TODO investigate event polling
+
struct hstr name;
dev_t dev_id;
int dev_type;
char name_val[DEVICE_NAME_SIZE];
void* underlay;
- int (*read)(struct device* dev, void* buf, size_t offset, size_t len);
- int (*write)(struct device* dev, void* buf, size_t offset, size_t len);
- int (*read_page)(struct device* dev, void* buf, size_t offset);
- int (*write_page)(struct device* dev, void* buf, size_t offset);
- int (*exec_cmd)(struct device* dev, u32_t req, va_list args);
+
+ struct
+ {
+ int (*read)(struct device* dev, void* buf, size_t offset, size_t len);
+ int (*write)(struct device* dev, void* buf, size_t offset, size_t len);
+ int (*read_page)(struct device* dev, void* buf, size_t offset);
+ int (*write_page)(struct device* dev, void* buf, size_t offset);
+ int (*exec_cmd)(struct device* dev, u32_t req, va_list args);
+ } ops;
};
struct device*
u32_t type,
va_list args);
+struct device*
+device_addsys(struct device* parent, void* underlay, char* name_fmt, ...);
+
struct device*
device_addseq(struct device* parent, void* underlay, char* name_fmt, ...);
device_getbyoffset(struct device* root_dev, int pos);
void
-device_init_builtin();
+device_install_pseudo();
#endif /* __LUNAIX_DEVICE_H */
#include <lunaix/clock.h>
#include <lunaix/device.h>
+#include <lunaix/ds/ldga.h>
#include <lunaix/ds/llist.h>
#include <lunaix/ds/waitq.h>
#include <lunaix/types.h>
// vector (e.g. mice wheel scroll, mice maneuver)
#define PKT_VECTOR 0x3
+#define EXPORT_INPUT_DEV(id, init_fn) \
+ export_ldga_el(inputdev, id, ptr_t, init_fn)
+
struct input_evt_pkt
{
u32_t pkt_type; // packet type
isr_cb
isrm_get(int iv);
+ptr_t
+isrm_get_payload(int iv);
+
+void
+isrm_set_payload(int iv, ptr_t);
+
#endif /* __LUNAIX_ISRM_H */
#define PILE_NAME_MAXLEN 20
-#define PILE_CACHELINE 1
+#define PILE_ALIGN_CACHE 1
struct cake_pile;
+++ /dev/null
-#ifndef __LUNAIX_PS2KBD_H
-#define __LUNAIX_PS2KBD_H
-
-#include <lunaix/ds/mutex.h>
-#include <lunaix/keyboard.h>
-
-#define PS2_PORT_ENC_DATA 0x60
-#define PS2_PORT_ENC_CMDREG 0x60
-#define PS2_PORT_CTRL_STATUS 0x64
-#define PS2_PORT_CTRL_CMDREG 0x64
-
-#define PS2_STATUS_OFULL 0x1
-#define PS2_STATUS_IFULL 0x2
-
-#define PS2_RESULT_ACK 0xfa
-#define PS2_RESULT_NAK 0xfe // resend
-#define PS2_RESULT_ECHO 0xee
-#define PS2_RESULT_TEST_OK 0x55
-
-// PS/2 keyboard device related commands
-#define PS2_KBD_CMD_SETLED 0xed
-#define PS2_KBD_CMD_ECHO 0xee
-#define PS2_KBD_CMD_SCANCODE_SET 0xf0
-#define PS2_KBD_CMD_IDENTIFY 0xf2
-#define PS2_KBD_CMD_SCAN_ENABLE 0xf4
-#define PS2_KBD_CMD_SCAN_DISABLE 0xf5
-
-// PS/2 *controller* related commands
-#define PS2_CMD_PORT1_DISABLE 0xad
-#define PS2_CMD_PORT1_ENABLE 0xae
-#define PS2_CMD_PORT2_DISABLE 0xa7
-#define PS2_CMD_PORT2_ENABLE 0xa8
-#define PS2_CMD_SELFTEST 0xaa
-#define PS2_CMD_SELFTEST_PORT1 0xab
-
-#define PS2_CMD_READ_CFG 0x20
-#define PS2_CMD_WRITE_CFG 0x60
-
-#define PS2_CFG_P1INT 0x1
-#define PS2_CFG_P2INT 0x2
-#define PS2_CFG_TRANSLATION 0x40
-
-#define PS2_DELAY 1000
-
-#define PS2_CMD_QUEUE_SIZE 8
-
-#define PS2_NO_ARG 0xff00
-
-struct ps2_cmd
-{
- char cmd;
- char arg;
-};
-
-struct ps2_kbd_state
-{
- volatile char state;
- volatile char masked;
- volatile kbd_kstate_t key_state;
- kbd_keycode_t* translation_table;
-};
-
-struct ps2_cmd_queue
-{
- struct ps2_cmd cmd_queue[PS2_CMD_QUEUE_SIZE];
- int queue_ptr;
- int queue_len;
- mutex_t mutex;
-};
-
-/**
- * @brief 向PS/2控制器的控制端口(0x64)发送指令并等待返回代码。
- * 注意,对于没有返回代码的命令请使用`ps2_post_cmd`,否则会造成死锁。
- * 通过调用该方法向控制器发送指令,请区别 ps2_issue_dev_cmd
- *
- * @param cmd
- * @param args
- */
-static u8_t
-ps2_issue_cmd(char cmd, u16_t arg);
-
-/**
- * @brief 向PS/2控制器的编码器端口(0x60)发送指令并等待返回代码。
- * 注意,对于没有返回代码的命令请使用`ps2_post_cmd`,否则会造成死锁。
- * 通过调用该方法向PS/2设备发送指令,请区别 ps2_issue_cmd
- *
- * @param cmd
- * @param args
- */
-static u8_t
-ps2_issue_dev_cmd(char cmd, u16_t arg);
-
-/**
- * @brief 向PS/2控制器发送指令,不等待返回代码。
- *
- * @param port 端口号
- * @param cmd
- * @param args
- * @return char
- */
-static void
-ps2_post_cmd(u8_t port, char cmd, u16_t arg);
-
-void
-ps2_device_post_cmd(char cmd, char arg);
-
-void
-ps2_kbd_init();
-
-void
-ps2_process_cmd(void* arg);
-
-#endif /* __LUNAIX_PS2KBD_H */
#define TIOCCLSBUF IOREQ(2, 0)
#define TIOCFLUSH IOREQ(3, 0)
+#define RTCIO_IUNMSK IOREQ(1, 0)
+#define RTCIO_IMSK IOREQ(2, 0)
+#define RTCIO_SETFREQ IOREQ(3, 1)
+#define RTCIO_GETINFO IOREQ(4, 1)
+#define RTCIO_SETDT IOREQ(5, 1)
+
+#define TIMERIO_GETINFO IOREQ(1, 0)
+
#endif /* __LUNAIX_IOCTL_DEFS_H */
for (size_t i = 0; i < header->ents_len; i++) {
if (!(i % ENT_PER_BLK)) {
- errno = master->read(
+ errno = master->ops.read(
master, ents_parial, LBA2OFF(ent_lba++), GPT_BLKSIZE);
if (errno < 0) {
goto done;
int errno;
struct gpt_header* gpt_hdr = (struct gpt_header*)valloc(GPT_BLKSIZE);
- if ((errno = master->read(master, gpt_hdr, LBA2OFF(1), LBA2OFF(1))) < 0) {
+ if ((errno = master->ops.read(master, gpt_hdr, LBA2OFF(1), LBA2OFF(1))) <
+ 0) {
goto done;
}
struct device* dev =
device_addvol(blk_parent_dev, bdev, "sd%c", 'a' + free_slot);
- dev->write = __block_write;
- dev->write_page = __block_write_page;
- dev->read = __block_read;
- dev->read_page = __block_read_page;
+ dev->ops.write = __block_write;
+ dev->ops.write_page = __block_write_page;
+ dev->ops.read = __block_read;
+ dev->ops.read_page = __block_read_page;
bdev->dev = dev;
strcpy(bdev->bdev_id, dev->name_val);
struct device* dev =
device_addvol(NULL, pbdev, "%sp%d", bdev->bdev_id, index + 1);
- dev->write = __block_write;
- dev->write_page = __block_write_page;
- dev->read = __block_read;
- dev->read_page = __block_read_page;
+ dev->ops.write = __block_write;
+ dev->ops.write_page = __block_write_page;
+ dev->ops.read = __block_read;
+ dev->ops.read_page = __block_read_page;
pbdev->start_lba = start_lba;
pbdev->end_lba = end_lba;
+++ /dev/null
-#include <lunaix/device.h>
-
-extern void
-devbuiltin_init_rand();
-
-extern void
-devbuiltin_init_null();
-
-void
-device_init_builtin()
-{
- devbuiltin_init_null();
- devbuiltin_init_rand();
-}
\ No newline at end of file
+++ /dev/null
-#include <hal/rnd.h>
-#include <lunaix/device.h>
-#include <lunaix/mm/page.h>
-#include <lunaix/syslog.h>
-
-LOG_MODULE("rand")
-
-int
-__rand_rd_pg(struct device* dev, void* buf, size_t offset)
-{
- // rnd_fill(buf, PG_SIZE);
- return PG_SIZE;
-}
-
-int
-__rand_rd(struct device* dev, void* buf, size_t offset, size_t len)
-{
- // rnd_fill(buf, len);
- return len;
-}
-
-void
-devbuiltin_init_rand()
-{
- // TODO rnd device need better abstraction
- if (1) {
- kprintf(KWARN "not supported.\n");
- return;
- }
- struct device* devrand = device_addseq(NULL, NULL, "rand");
- devrand->read = __rand_rd;
- devrand->read_page = __rand_rd_pg;
-}
\ No newline at end of file
struct device* dev = (struct device*)inode->data;
- if (!dev->read) {
+ if (!dev->ops.read) {
return ENOTSUP;
}
- return dev->read(dev, buffer, fpos, len);
+ return dev->ops.read(dev, buffer, fpos, len);
}
int
struct device* dev = (struct device*)inode->data;
- if (!dev->write) {
+ if (!dev->ops.write) {
return ENOTSUP;
}
- return dev->write(dev, buffer, fpos, len);
+ return dev->ops.write(dev, buffer, fpos, len);
}
int
struct device* dev = (struct device*)inode->data;
- if (!dev->read_page) {
+ if (!dev->ops.read_page) {
return ENOTSUP;
}
- return dev->read_page(dev, buffer, fpos);
+ return dev->ops.read_page(dev, buffer, fpos);
}
int
struct device* dev = (struct device*)inode->data;
- if (!dev->read_page) {
+ if (!dev->ops.read_page) {
return ENOTSUP;
}
- return dev->read_page(dev, buffer, fpos);
+ return dev->ops.read_page(dev, buffer, fpos);
}
int
return dev;
}
+struct device*
+device_addsys(struct device* parent, void* underlay, char* name_fmt, ...)
+{
+ va_list args;
+ va_start(args, name_fmt);
+
+ struct device* dev =
+ device_add(parent, underlay, name_fmt, DEV_IFSEQ, args);
+
+ va_end(args);
+ return dev;
+}
+
struct device*
device_addseq(struct device* parent, void* underlay, char* name_fmt, ...)
{
goto done;
}
- if (!dev->exec_cmd) {
- errno = EINVAL;
+ if (!dev->ops.exec_cmd) {
+ errno = ENOTSUP;
goto done;
}
- errno = dev->exec_cmd(dev, req, args);
+ errno = dev->ops.exec_cmd(dev, req, args);
done:
return DO_STATUS_OR_RETURN(errno);
input_init()
{
input_devcat = device_addcat(NULL, "input");
+
+ int i;
+ ptr_t input_dev_init;
+ ldga_foreach(inputdev, ptr_t, i, input_dev_init)
+ {
+ ((void (*)())input_dev_init)();
+ }
}
void
device_add(input_devcat, idev, name_fmt, DEV_IFSEQ, args);
idev->dev_if = dev;
- dev->read = __input_dev_read;
- dev->read_page = __input_dev_read_pg;
+ dev->ops.read = __input_dev_read;
+ dev->ops.read_page = __input_dev_read_pg;
va_end(args);
#include <lunaix/device.h>
#include <lunaix/mm/page.h>
-int
+static int
__null_wr_pg(struct device* dev, void* buf, size_t offset)
{
// do nothing
return PG_SIZE;
}
-int
+static int
__null_wr(struct device* dev, void* buf, size_t offset, size_t len)
{
// do nothing
return len;
}
-int
+static int
__null_rd_pg(struct device* dev, void* buf, size_t offset)
{
// do nothing
return 0;
}
-int
+static int
__null_rd(struct device* dev, void* buf, size_t offset, size_t len)
{
// do nothing
}
void
-devbuiltin_init_null()
+pdev_nulldev_init()
{
struct device* devnull = device_addseq(NULL, NULL, "null");
- devnull->write_page = __null_wr_pg;
- devnull->write = __null_wr;
- devnull->read_page = __null_rd_pg;
- devnull->read = __null_rd;
-}
\ No newline at end of file
+ devnull->ops.write_page = __null_wr_pg;
+ devnull->ops.write = __null_wr;
+ devnull->ops.read_page = __null_rd_pg;
+ devnull->ops.read = __null_rd;
+}
+EXPORT_PSEUDODEV(nulldev, pdev_nulldev_init);
\ No newline at end of file
--- /dev/null
+#include <lunaix/device.h>
+
+extern void
+devbuiltin_init_rand();
+
+extern void
+devbuiltin_init_null();
+
+void
+device_install_pseudo()
+{
+ ptr_t pdev_init_fn;
+ int index;
+ ldga_foreach(pseudo_dev, ptr_t, index, pdev_init_fn)
+ {
+ ((void (*)())pdev_init_fn)();
+ }
+}
\ No newline at end of file
do {
if (blk_offset >= ISO9660_BLKSZ - sizeof(struct iso_drecord)) {
current_pos += ISO9660_BLKSZ;
- errno = dev->read(dev, records, blk + current_pos, ISO9660_BLKSZ);
+ errno =
+ dev->ops.read(dev, records, blk + current_pos, ISO9660_BLKSZ);
if (errno < 0) {
errno = EIO;
goto done;
int errno = 0;
while (fu_to_read) {
for (; sec < isoino->fu_size && i < len; sec++) {
- errno = bdev->read(
+ errno = bdev->ops.read(
bdev, rd_buffer, true_offset * ISO9660_BLKSZ, ISO9660_BLKSZ);
if (errno < 0) {
if (dir->xattr_len) {
struct iso_xattr* xattr = (struct iso_xattr*)valloc(ISO9660_BLKSZ);
// Only bring in single FU, as we only care about the attributes.
- errno =
- dev->read(dev, xattr, ISO9660_BLKSZ * inode->lb_addr, ISO9660_BLKSZ);
+ errno = dev->ops.read(
+ dev, xattr, ISO9660_BLKSZ * inode->lb_addr, ISO9660_BLKSZ);
if (errno < 0) {
return EIO;
}
u32_t lba = 16;
int errno = 0;
do {
- errno = dev->read(dev, vdesc, ISO9660_BLKSZ * lba, ISO9660_BLKSZ);
+ errno = dev->ops.read(dev, vdesc, ISO9660_BLKSZ * lba, ISO9660_BLKSZ);
if (errno < 0) {
errno = EIO;
goto done;
return 1;
}
+static void
+pcache_free_page(void* va)
+{
+ ptr_t pa = vmm_del_mapping(VMS_SELF, (ptr_t)va);
+ pmm_free_page(KERNEL_PID, pa);
+}
+
+static void*
+pcache_alloc_page()
+{
+ int i = 0;
+ ptr_t pp = pmm_alloc_page(KERNEL_PID, 0), va = 0;
+
+ if (!pp) {
+ return NULL;
+ }
+
+ if (!(va = (ptr_t)vmap(pp, PG_SIZE, PG_PREM_RW, 0))) {
+ pmm_free_page(KERNEL_PID, pp);
+ return NULL;
+ }
+
+ return (void*)va;
+}
+
void
pcache_init(struct pcache* pcache)
{
btrie_init(&pcache->tree, PG_SIZE_BITS);
llist_init_head(&pcache->dirty);
llist_init_head(&pcache->pages);
+
pcache_zone = lru_new_zone(__pcache_try_evict);
}
void
pcache_release_page(struct pcache* pcache, struct pcache_pg* page)
{
- vfree(page->pg);
+ pcache_free_page(page->pg);
llist_delete(&page->pg_list);
+ btrie_remove(&pcache->tree, page->fpos);
+
vfree(page);
pcache->n_pages--;
pcache_new_page(struct pcache* pcache, u32_t index)
{
struct pcache_pg* ppg = vzalloc(sizeof(struct pcache_pg));
- void* pg = valloc(PG_SIZE);
+ void* pg = pcache_alloc_page();
if (!ppg || !pg) {
lru_evict_one(pcache_zone);
return NULL;
}
- if (!pg && !(pg = valloc(PG_SIZE))) {
+ if (!pg && !(pg = pcache_alloc_page())) {
return NULL;
}
}
int
pcache_write(struct v_inode* inode, void* data, u32_t len, u32_t fpos)
{
+ int errno = 0;
u32_t pg_off, buf_off = 0;
struct pcache* pcache = inode->pg_cache;
struct pcache_pg* pg;
while (buf_off < len) {
+ u32_t wr_bytes = MIN(PG_SIZE - pg_off, len - buf_off);
+
pcache_get_page(pcache, fpos, &pg_off, &pg);
- if (!pg) {
- return ENOMEM;
- }
- u32_t wr_bytes = MIN(PG_SIZE - pg_off, len - buf_off);
- memcpy(pg->pg + pg_off, (data + buf_off), wr_bytes);
+ if (!pg) {
+ errno = inode->default_fops->write(inode, data, wr_bytes, fpos);
+ if (errno < 0) {
+ break;
+ }
+ } else {
+ memcpy(pg->pg + pg_off, (data + buf_off), wr_bytes);
+ pcache_set_dirty(pcache, pg);
- pcache_set_dirty(pcache, pg);
+ pg->len = pg_off + wr_bytes;
+ }
- pg->len = pg_off + wr_bytes;
buf_off += wr_bytes;
fpos += wr_bytes;
}
- return buf_off;
+ return errno < 0 ? errno : (int)buf_off;
}
int
struct pcache_pg* pg;
while (buf_off < len) {
- if (pcache_get_page(pcache, fpos, &pg_off, &pg)) {
-
- if (!pg) {
- return ENOMEM;
- }
-
+ int new_page = pcache_get_page(pcache, fpos, &pg_off, &pg);
+ if (new_page) {
// Filling up the page
errno =
inode->default_fops->read_page(inode, pg->pg, PG_SIZE, pg->fpos);
- if (errno >= 0 && errno < PG_SIZE) {
+
+ if (errno < 0) {
+ break;
+ }
+ if (errno < PG_SIZE) {
// EOF
len = MIN(len, buf_off + errno);
- } else if (errno < 0) {
- break;
}
+
pg->len = errno;
+ } else if (!pg) {
+ errno = inode->default_fops->read_page(
+ inode, (data + buf_off), len - buf_off, pg->fpos);
+ buf_off = len;
+ break;
}
+
u32_t rd_bytes = MIN(pg->len - pg_off, len - buf_off);
if (!rd_bytes)
llist_for_each(pos, n, &block_cat->children, siblings)
{
int errno =
- pos->read(pos, (void*)volp, ISO9660_READ_OFF, ISO9660_BLKSZ);
+ pos->ops.read(pos, (void*)volp, ISO9660_READ_OFF, ISO9660_BLKSZ);
if (errno < 0) {
kprintf(KWARN "can not probe %x:%s (%d)\n",
pos->dev_id,
/* Let's get fs online as soon as possible, as things rely on them */
vfs_init();
fsm_init();
- input_init();
/* Get intc online, this is the cornerstone when initing devices */
intc_init();
clock_init();
timer_init();
+ input_init();
block_init();
/* the bare metal are now happy, let's get software over with */
vfs_mount("/task", "taskfs", NULL, MNT_RO);
lxconsole_spawn_ttydev();
- device_init_builtin();
+ device_install_pseudo();
/* Finish up bootstrapping sequence, we are ready to spawn the root process
* and start geting into uspace
unsigned int offset = sizeof(long);
// 默认每块儿蛋糕对齐到地址总线宽度
- if ((options & PILE_CACHELINE)) {
+ if ((options & PILE_ALIGN_CACHE)) {
// 对齐到128字节缓存行大小,主要用于DMA
offset = CACHE_LINE_SIZE;
}
for (size_t i = 0; i < CLASS_LEN(piles_names_dma); i++) {
int size = 1 << (i + 7);
piles_dma[i] = cake_new_pile(
- piles_names_dma[i], size, size > 1024 ? 4 : 1, PILE_CACHELINE);
+ piles_names_dma[i], size, size > 1024 ? 4 : 1, PILE_ALIGN_CACHE);
}
}
#include <lunaix/mm/pmm.h>
#include <lunaix/mm/valloc.h>
#include <lunaix/mm/vmm.h>
-#include <lunaix/peripheral/ps2kbd.h>
#include <lunaix/peripheral/serial.h>
#include <lunaix/spike.h>
#include <lunaix/syscall.h>
serial_init();
sdbg_init();
- // FIXME ps2 kbd is a device, must not be here
- ps2_kbd_init();
-
// console
console_start_flushing();
console_flush();
void
clock_walltime(datetime_t* datetime)
{
- current_rtc->get_walltime(current_rtc, datetime);
+ primary_rtc->get_walltime(primary_rtc, datetime);
}
\ No newline at end of file
lxconsole_spawn_ttydev()
{
struct device* tty_dev = device_addseq(NULL, &lx_console, "tty");
- tty_dev->write = __tty_write;
- tty_dev->write_page = __tty_write_pg;
- tty_dev->read = __tty_read;
- tty_dev->read_page = __tty_read_pg;
- tty_dev->exec_cmd = __tty_exec_cmd;
+ tty_dev->ops.write = __tty_write;
+ tty_dev->ops.write_page = __tty_write_pg;
+ tty_dev->ops.read = __tty_read;
+ tty_dev->ops.read_page = __tty_read_pg;
+ tty_dev->ops.exec_cmd = __tty_exec_cmd;
waitq_init(&lx_reader);
input_add_listener(__lxconsole_listener);
. = ALIGN(8);
- PROVIDE(__lga_platdev_db_start = .);
+ PROVIDE(__lga_rtcdev_start = .);
- KEEP(*(.lga.platdev_db));
+ KEEP(*(.lga.rtcdev));
- PROVIDE(__lga_platdev_db_end = .);
+ PROVIDE(__lga_rtcdev_end = .);
+
+ /* ---- */
+
+ . = ALIGN(8);
+
+ PROVIDE(__lga_inputdev_start = .);
+
+ KEEP(*(.lga.inputdev));
+
+ PROVIDE(__lga_inputdev_end = .);
+
+ /* ---- */
+
+ . = ALIGN(8);
+
+ PROVIDE(__lga_pseudo_dev_start = .);
+
+ KEEP(*(.lga.pseudo_dev));
+
+ PROVIDE(__lga_pseudo_dev_end = .);
}
.bss BLOCK(4K) : AT ( ADDR(.bss) - 0xC0000000 ) {