diff --git a/libn3ds/include/arm11/drivers/gpio.h b/libn3ds/include/arm11/drivers/gpio.h
index f0398e5..d584dd6 100644
--- a/libn3ds/include/arm11/drivers/gpio.h
+++ b/libn3ds/include/arm11/drivers/gpio.h
@@ -46,15 +46,15 @@
#define REG_GPIO3_DAT2 *(( vu16*)(GPIO_REGS_BASE + 0x28)) // WiFi.
-#define GPIO_INPUT (0u)
-#define GPIO_OUTPUT (1u)
-#define GPIO_EDGE_FALLING (0u)
-#define GPIO_EDGE_RISING (1u<<1)
-#define GPIO_IRQ_ENABLE (1u<<2)
+#define GPIO_INPUT (0u)
+#define GPIO_OUTPUT (1u)
+#define GPIO_NO_IRQ (0u)
+#define GPIO_IRQ_FALLING (1u<<2 | 0u)
+#define GPIO_IRQ_RISING (1u<<2 | 1u<<1)
// bits 3-7 pin number, bits 0-3 reg index.
-#define MAKE_GPIO(pin, reg) ((pin)<<3 | (reg))
+#define MAKE_GPIO(pin, reg) ((pin)<<3 | (reg))
typedef enum
{
diff --git a/libn3ds/include/arm11/drivers/mcu.h b/libn3ds/include/arm11/drivers/mcu.h
index 31328b4..81003e7 100644
--- a/libn3ds/include/arm11/drivers/mcu.h
+++ b/libn3ds/include/arm11/drivers/mcu.h
@@ -19,114 +19,656 @@
*/
#include "types.h"
-#include "arm11/drivers/i2c.h"
+#include "arm11/drivers/mcu_regmap.h"
-typedef enum
+#define DEFAULT_MCU_IRQ_MASK (~(MCU_IRQ_TOP_BL_ON | MCU_IRQ_TOP_BL_OFF | MCU_IRQ_BOT_BL_ON | \
+ MCU_IRQ_BOT_BL_OFF | MCU_IRQ_LCD_POWER_ON | MCU_IRQ_LCD_POWER_OFF | \
+ MCU_IRQ_VOL_SLIDER_CHANGE | MCU_IRQ_BATT_CHARGE_START | \
+ MCU_IRQ_BATT_CHARGE_STOP | MCU_IRQ_ACC_DATA_READY | MCU_IRQ_ACC_RW_DONE | \
+ MCU_IRQ_WATCHDOG | MCU_IRQ_SHELL_OPEN | MCU_IRQ_SHELL_CLOSE | \
+ MCU_IRQ_WIFI_PRESS | MCU_IRQ_HOME_RELEASE | MCU_IRQ_HOME_PRESS | \
+ MCU_IRQ_POWER_HELD | MCU_IRQ_POWER_PRESS))
+
+
+/*typedef struct
{
- MCU_REG_VERS_HIGH = 0x00u,
- MCU_REG_VERS_LOW = 0x01u,
- MCU_REG_3D_SLIDER = 0x08u,
- MCU_REG_VOL_SLIDER = 0x09u, // 0-0x3F
- MCU_REG_BATTERY = 0x0Bu,
- MCU_REG_EX_HW_STATE = 0x0Fu,
- MCU_REG_EVENTS = 0x10u,
- MCU_REG_EVENT_MASK = 0x18u,
- MCU_REG_POWER = 0x20u,
- MCU_REG_LCDs = 0x22u,
- MCU_REG_POWER_LED = 0x29u,
- MCU_REG_WIFI_LED = 0x2Au,
- MCU_REG_CAM_LED = 0x2Bu,
- MCU_REG_3D_LED = 0x2Cu,
- MCU_REG_RTC_TIME = 0x30u,
- MCU_REG_RAW_STATE = 0x7Fu
-} McuReg;
+ // TODO
+} PowerLedPattern;*/
-typedef enum
+/*typedef struct
{
- PWLED_AUTO = 0u,
- //PWLED_BLUE = 1u, // wtf is "forced default blue"?
- PWLED_SLEEP = 2u,
- PWLED_OFF = 3u,
- PWLED_RED = 4u,
- PWLED_BLUE = 5u,
- PWLED_BLINK_RED = 6u
-} PwLedState;
+ // TODO
+} InfoLedPattern;*/
+
+typedef struct
+{
+ u8 s; // Second.
+ u8 min; // Minute.
+ u8 h; // Hour.
+ u8 dow; // Unused day of week.
+ u8 d; // Day.
+ u8 mon; // Month.
+ u8 y; // Year.
+} RtcTimeDate;
+
+typedef struct
+{
+ u8 min; // Minute.
+ u8 h; // Hour.
+ u8 d; // Day.
+ u8 mon; // Month.
+ u8 y; // Year.
+} AlarmTimeDate;
+
+typedef struct
+{
+ s16 x;
+ s16 y;
+ s16 z;
+} AccData;
+
+/*typedef struct
+{
+ // 6 bytes timestamps.
+ // 336 bytes step counts.
+} PedometerHistory;*/
-u8 MCU_readReg(McuReg reg);
-
-bool MCU_writeReg(McuReg reg, u8 data);
-
-bool MCU_readRegBuf(McuReg reg, u8 *out, u32 size);
-
-bool MCU_writeRegBuf(McuReg reg, const u8 *const in, u32 size);
+// TODO: For most functions check if the return value on error makes sense.
+/**
+ * @brief Initializes the MCU driver.
+ */
void MCU_init(void);
-bool MCU_setEventMask(u32 mask);
+/**
+ * @brief Reboots the MCU.
+ *
+ * @return Returns true on success and false on failure.
+ */
+//bool MCU_reboot(void);
-u32 MCU_getEvents(u32 mask);
+/**
+ * @brief { function_description }
+ *
+ * @param[in] mask The mask
+ *
+ * @return { description_of_the_return_value }
+ */
+u32 MCU_getIrqs(u32 mask);
-u32 MCU_waitEvents(u32 mask);
+/**
+ * @brief { function_description }
+ *
+ * @param[in] mask The mask
+ *
+ * @return { description_of_the_return_value }
+ */
+u32 MCU_waitIrqs(u32 mask);
-static inline u8 MCU_getBatteryLevel(void)
-{
- u8 state;
+/**
+ * @brief Reads the MCU firmware version.
+ *
+ * @return Returns the MCU firmware version.
+ */
+u16 MCU_getFirmwareVersion(void);
- if(!MCU_readRegBuf(MCU_REG_BATTERY, &state, 1)) return 0;
-
- return state;
-}
+/**
+ * @brief Reads MCU status bits.
+ *
+ * @return Returns the MCU status bits.
+ */
+u8 MCU_getStatus(void);
-static inline u8 MCU_getExternalHwState(void)
-{
- return MCU_readReg(MCU_REG_EX_HW_STATE);
-}
+/**
+ * @brief { function_description }
+ *
+ * @param[in] status The status
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setStatus(u8 status);
-static inline void MCU_powerOffSys(void)
-{
- I2C_writeRegIntSafe(I2C_DEV_CTR_MCU, MCU_REG_POWER, 1u);
-}
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getLcdVcomTop(void);
-static inline void MCU_rebootSys(void)
-{
- I2C_writeRegIntSafe(I2C_DEV_CTR_MCU, MCU_REG_POWER, 1u<<2);
-}
+/**
+ * @brief { function_description }
+ *
+ * @param[in] vcom The vcom
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setLcdVcomTop(u8 vcom);
-static inline void MCU_controlLCDPower(u8 bits)
-{
- MCU_writeReg(MCU_REG_LCDs, bits);
-}
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getLcdVcomBot(void);
-static inline bool MCU_setPowerLedState(PwLedState state)
-{
- return MCU_writeReg(MCU_REG_POWER_LED, state);
-}
+/**
+ * @brief { function_description }
+ *
+ * @param[in] vcom The vcom
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setLcdVcomBot(u8 vcom);
-static inline bool MCU_getRTCTime(u8 rtc[7])
-{
- if(!rtc) return true;
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_get3dSliderPosition(void);
- return MCU_readRegBuf(MCU_REG_RTC_TIME, rtc, 7);
-}
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getVolumeSliderPosition(void);
-static inline u8 MCU_getSystemModel(void)
-{
- u8 buf[10];
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getBatteryTemperature(void);
- if(!MCU_readRegBuf(MCU_REG_RAW_STATE, buf, sizeof(buf))) return 0xFF;
-
- return buf[9];
-}
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+float MCU_getBatteryLevel(void);
-static inline u8 MCU_getHidHeld(void)
-{
- u8 data[19];
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+float MCU_getBatteryVoltage(void);
- if(!MCU_readRegBuf(MCU_REG_RAW_STATE, data, sizeof(data))) return 0xFF;
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u16 MCU_getExternalHardwareStatus(void);
- return data[18];
-}
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u32 MCU_getIrqMask(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] mask The mask
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setIrqMask(u32 mask);
+
+// TODO: MCU_setSystemPower()?
+
+void MCU_powerOffSys(void);
+
+void MCU_rebootSys(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] bits The bits
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setTwlIrq(u8 bits);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] bits The bits
+ */
+void MCU_setLcdPower(u8 bits);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getPoweroffDelay(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] delay The delay
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setPoweroffDelay(u8 delay);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getRegister0x25(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] data The data
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setRegister0x25(u8 data);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getRegister0x26(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] data The data
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setRegister0x26(u8 data);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getVolumeSliderPositionRaw(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] data The data
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setVolumeSliderPositionRaw(u8 data);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getLedMasterBrightness(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] brightness The brightness
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setLedMasterBrightness(u8 brightness);
+
+/**
+ * @brief { function_description }
+ *
+ * @param pattern The pattern
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_getPowerLedPattern(u8 pattern[5]); // TODO: Struct.
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] pattern The pattern
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setPowerLedPattern(const u8 pattern[5]); // TODO: Struct.
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getWifiLedState(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] state The state
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setWifiLedState(u8 state);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getCameraLedState(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] state The state
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setCameraLedState(u8 state);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_get3dLedState(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] state The state
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_set3dLedState(u8 state);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] pattern The pattern
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setInfoLedPattern(const u8 pattern[100]); // TODO: Struct.
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getInfoLedStatus(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param timeDate The time date
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_getRtcTimeDate(RtcTimeDate *timeDate);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] timeDate The time date
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setRtcTimeDate(const RtcTimeDate *timeDate);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getRtcErrorCorrection(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] correction The correction
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setRtcErrorCorrection(u8 correction);
+
+/**
+ * @brief { function_description }
+ *
+ * @param timeDate The time date
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_getAlarmTimeDate(AlarmTimeDate *timeDate);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] timeDate The time date
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setAlarmTimeDate(const AlarmTimeDate *timeDate);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u16 MCU_getRtcTick(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] data The data
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setRegister0x3F(u8 data);
+
+/**
+ * @brief { function_description }
+ *
+ * @return The acc configuration.
+ */
+AccCfg MCU_getAccelerometerConfig(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] cfg The configuration
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setAccelerometerConfig(AccCfg cfg);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] reg The register
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_readAccelerometerRegister(u8 reg);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] reg The register
+ * @param[in] data The data
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_writeAccelerometerRegister(u8 reg, u8 data);
+
+/**
+ * @brief { function_description }
+ *
+ * @param samples The samples
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_getAccelerometerSamples(AccData *samples);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] steps The steps
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setPedometerStepCount(u32 steps);
+
+// TODO: Reg 0x4E.
+
+/**
+ * @brief { function_description }
+ *
+ * @param history The history
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_getPedometerHistory(u8 history[6 + 336]); // TODO: Struct.
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getRegister0x50(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] data The data
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setRegister0x50(u8 data);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getRegister0x51(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] data The data
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setRegister0x51(u8 data);
+
+/**
+ * @brief { function_description }
+ *
+ * @param minMax The minimum maximum
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_getVolumeSliderCalibrationPoints(u8 minMax[2]);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] minMax The minimum maximum
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setVolumeSliderCalibrationPoints(const u8 minMax[2]);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] off Off
+ * @param out The out
+ * @param[in] size The size
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_getFreeRamData(u8 off, u8 *out, u8 size);
+
+/**
+ * @brief { function_description }
+ *
+ * @param[in] off Off
+ * @param[in] in { parameter_description }
+ * @param[in] size The size
+ *
+ * @return { description_of_the_return_value }
+ */
+bool MCU_setFreeRamData(u8 off, const u8 *in, u8 size);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getConsoleType(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getSystemModel(void);
+
+/**
+ * @brief { function_description }
+ *
+ * @return { description_of_the_return_value }
+ */
+u8 MCU_getEarlyButtonsHeld(void);
+
+
+/**
+ * @brief Reads a single MCU register.
+ *
+ * @param[in] reg The MCU register to read.
+ *
+ * @return The MCU register data.
+ */
+u8 MCU_readReg(McuReg reg);
+
+/**
+ * @brief Writes a single MCU register.
+ *
+ * @param[in] reg The MCU register to write.
+ * @param[in] data The data to write.
+ *
+ * @return Returns true on success and false on failure.
+ */
+bool MCU_writeReg(McuReg reg, u8 data);
+
+/**
+ * @brief Reads multiple MCU registers or buffers behind registers.
+ *
+ * @param[in] reg The MCU register(s) to read.
+ * @param out The output data pointer.
+ * @param[in] size The output buffer size.
+ *
+ * @return Returns true on success and false on failure.
+ */
+bool MCU_readRegBuf(McuReg reg, u8 *out, u32 size);
+
+/**
+ * @brief Writes multiple MCU registers or buffers behind registers.
+ *
+ * @param[in] reg The MCU register(s) to write.
+ * @param[in] in The input data pointer.
+ * @param[in] size The input data size.
+ *
+ * @return Returns true on success and false on failure.
+ */
+bool MCU_writeRegBuf(McuReg reg, const u8 *const in, u32 size);
diff --git a/libn3ds/include/arm11/drivers/mcu_regmap.h b/libn3ds/include/arm11/drivers/mcu_regmap.h
new file mode 100644
index 0000000..38fc7c3
--- /dev/null
+++ b/libn3ds/include/arm11/drivers/mcu_regmap.h
@@ -0,0 +1,145 @@
+#pragma once
+
+/*
+ * This file is part of open_agb_firm
+ * Copyright (C) 2022 derrek, profi200
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ */
+
+
+
+typedef enum
+{
+ MCU_REG_VERS_MAJOR = 0x00u, // (ro) MCU firmware major version.
+ MCU_REG_VERS_MINOR = 0x01u, // (ro) MCU firmware minor version.
+ MCU_REG_STAT = 0x02u, // (rw) Reset status and TWL MCU emulation stuff.
+ MCU_REG_LCD_VCOM_TOP = 0x03u, // (rw) Top LCD VCOM ("flicker").
+ MCU_REG_LCD_VCOM_BOT = 0x04u, // (rw) Bottom LCD VCOM ("flicker").
+ MCU_REG_FW_UPDATE = 0x05u, // (rw) 0x05-0x07 Firmware update magic "jhl" is written here. If we stop the transfer after the magic the MCU will just reset.
+ MCU_REG_3D_SLIDER = 0x08u, // (ro) Raw 3D slider position (0-0x3F?).
+ MCU_REG_VOL_SLIDER = 0x09u, // (ro) Volume slider position (0-0x3F).
+ MCU_REG_BATT_TEMP = 0x0Au, // (ro) Battery temperature in celsius.
+ MCU_REG_BATT_LEVEL = 0x0Bu, // (ro) Battery percentage (0-100).
+ MCU_REG_BATT_LEVEL_FRAC = 0x0Cu, // (ro) Battery percentage fractional part (percent/256).
+ MCU_REG_BATT_VOLT = 0x0Du, // (ro) Battery voltage in 20mV units.
+ MCU_REG_EX_HW_STAT2 = 0x0Eu, // (ro) More hardware status bits.
+ MCU_REG_EX_HW_STAT = 0x0Fu, // (ro) Hardware status bits.
+ MCU_REG_IRQ = 0x10u, // (ro) 0x10-0x13 Interrupt status (clear on read).
+ // 0x14 ro, 0x15-0x17 rw. All unused.
+ MCU_REG_IRQ_MASK = 0x18u, // (rw) 0x18-0x1B Interrupt mask (each bit 0=enabled, 1=disabled).
+ // 0x1C-0x1F rw and unused.
+ MCU_REG_SYS_POW = 0x20u, // (wo) System power/reset control.
+ MCU_REG_TWL_IRQ = 0x21u, // (wo) Various TWL MCU status change signals.
+ MCU_REG_LCD_POW = 0x22u, // (wo) LCD power control.
+ MCU_REG_RESTART = 0x23u, // (wo) Stubbed (on retail?) MCU restart register.
+ MCU_REG_PWROFF_DELAY = 0x24u, // (rw) Force power off delay.
+ MCU_REG_UNK25 = 0x25u, // (rw) Volume related? Volume value for override?
+ MCU_REG_UNK26 = 0x26u, // (rw) Volume related? Bit 0: Enable/disable MCU reporting slider state to CODEC? Bit 1: Force? Bit 2: Mode? Bit 4: Trigger volume update from slider?
+ MCU_REG_VOL_SLIDER_RAW = 0x27u, // (rw) Volume slider raw ADC data (0-0x3F?).
+ MCU_REG_LED_BRIGHTNESS = 0x28u, // (rw) Master brightness of power/Wifi/3D (and camera?) LEDs.
+ MCU_REG_POWER_LED = 0x29u, // (rw) 5 bytes power LED state + pattern.
+ MCU_REG_WIFI_LED = 0x2Au, // (rw) WiFi LED state.
+ MCU_REG_CAM_LED = 0x2Bu, // (rw) Camera LED state.
+ MCU_REG_3D_LED = 0x2Cu, // (rw) 3D LED state.
+ MCU_REG_INFO_LED = 0x2Du, // (wo) 100 bytes notification/info LED pattern.
+ MCU_REG_INFO_LED_STAT = 0x2Eu, // (ro) Info LED status.
+ // 0x2F wo with stubbed write handler.
+ MCU_REG_RTC_S = 0x30u, // (rw) RTC second.
+ MCU_REG_RTC_MIN = 0x31u, // (rw) RTC minute.
+ MCU_REG_RTC_H = 0x32u, // (rw) RTC hour.
+ MCU_REG_RTC_DOW = 0x33u, // (rw) RTC day of week (unused)?
+ MCU_REG_RTC_D = 0x34u, // (rw) RTC day.
+ MCU_REG_RTC_MON = 0x35u, // (rw) RTC month.
+ MCU_REG_RTC_Y = 0x36u, // (rw) RTC year.
+ MCU_REG_RTC_ERR_CORR = 0x37u, // (rw) RTC Watch error correction.
+ MCU_REG_ALARM_MIN = 0x38u, // (rw) Alarm minute.
+ MCU_REG_ALARM_H = 0x39u, // (rw) Alarm hour.
+ MCU_REG_ALARM_D = 0x3Au, // (rw) Alarm day.
+ MCU_REG_ALARM_MON = 0x3Bu, // (rw) Alarm month.
+ MCU_REG_ALARM_Y = 0x3Cu, // (rw) Alarm year.
+ MCU_REG_RTC_TICK_LO = 0x3Du, // (ro) RTC tick counter LSB in 32768 Hz units.
+ MCU_REG_RTC_TICK_HI = 0x3Eu, // (ro) RTC tick counter MSB.
+ MCU_REG_UNK3F = 0x3Fu, // (wo) Unknown state/control reg.
+ MCU_REG_ACC_CFG = 0x40u, // (rw) Accelerometer configuration register.
+ MCU_REG_ACC_READ_OFF = 0x41u, // (rw) Accelerometer I2C register offset for read (via MCU reg 0x44).
+ // 0x42 rw unused.
+ MCU_REG_ACC_WRITE_OFF = 0x43u, // (rw) Accelerometer I2C register offset for write (via MCU reg 0x44).
+ MCU_REG_ACC_DATA = 0x44u, // (rw) Accelerometer I2C register data.
+ MCU_REG_ACC_X_LO = 0x45u, // (ro) Accelerometer X sample data LSB.
+ MCU_REG_ACC_X_HI = 0x46u, // (ro) Accelerometer X sample data MSB.
+ MCU_REG_ACC_Y_LO = 0x47u, // (ro) Accelerometer Y sample data LSB.
+ MCU_REG_ACC_Y_HI = 0x48u, // (ro) Accelerometer Y sample data MSB.
+ MCU_REG_ACC_Z_LO = 0x49u, // (ro) Accelerometer Z sample data LSB.
+ MCU_REG_ACC_Z_HI = 0x4Au, // (ro) Accelerometer Z sample data MSB.
+ MCU_REG_PM_COUNT_LO = 0x4Bu, // (rw) Pedometer step count LSB.
+ MCU_REG_PM_COUNT_MI = 0x4Cu, // (rw) Pedometer step count middle byte.
+ MCU_REG_PM_COUNT_HI = 0x4Du, // (rw) Pedometer step count MSB.
+ MCU_REG_PM_HIST_STAT = 0x4Eu, // (rw) Pedometer history state. TODO: Better name.
+ MCU_REG_PM_HIST = 0x4Fu, // (ro) 6 + 336 bytes pedometer history data.
+ MCU_REG_UNK50 = 0x50u, // (rw)
+ MCU_REG_UNK51 = 0x51u, // (rw)
+ // 0x52-0x57 rw unknown/unused.
+ MCU_REG_VOL_SLIDER_MIN = 0x58u, // (rw) Volume slider minimum calibration point.
+ MCU_REG_VOL_SLIDER_MAX = 0x59u, // (rw) Volume slider maximum calibration point.
+ // 0x5A rw/ro depending on firmware version. Unused.
+ // 0x5B-0x5F unused.
+ MCU_REG_FREE_RAM_OFF = 0x60u, // (rw) Free RAM offset for MCU register 0x61.
+ MCU_REG_FREE_RAM_DATA = 0x61u, // (rw) Free RAM data register.
+ // 0x62-0x7E unused.
+ MCU_REG_RAW_STATE = 0x7Fu // (ro) 19 bytes of various raw state.
+ // 0x80-0xFF unused.
+} McuReg;
+
+
+// MCU_REG_IRQ and MCU_REG_IRQ_MASK.
+#define MCU_IRQ_POWER_PRESS (1u) // Power button pressed for 200 ms.
+#define MCU_IRQ_POWER_HELD (1u<<1) // Power button held for 3 seconds.
+#define MCU_IRQ_HOME_PRESS (1u<<2) // HOME button pressed for 40 ms.
+#define MCU_IRQ_HOME_RELEASE (1u<<3) // HOME button released.
+#define MCU_IRQ_WIFI_PRESS (1u<<4) // WiFi button pressed for 40 ms.
+#define MCU_IRQ_SHELL_CLOSE (1u<<5) // Shell has been closed.
+#define MCU_IRQ_SHELL_OPEN (1u<<6) // Shell has been opened.
+#define MCU_IRQ_WATCHDOG (1u<<7) // MCU has been reset by the watchdog.
+#define MCU_IRQ_CHARGER_UNPLUG (1u<<8) // Charger has been unplugged.
+#define MCU_IRQ_CHARGER_PLUG (1u<<9) // Charger has been plugged in.
+#define MCU_IRQ_RTC_ALARM (1u<<10) // RTC alarm.
+#define MCU_IRQ_ACC_RW_DONE (1u<<11) // Accelerometer I2C read/write done.
+#define MCU_IRQ_ACC_DATA_READY (1u<<12) // Accelerometer X/Y/Z sample data ready.
+#define MCU_IRQ_LOW_BATT (1u<<13) // Low battery warning IRQ triggered at 10, 5 and 0%. TODO: gbatek says 11, 6 and 1%.
+#define MCU_IRQ_BATT_CHARGE_STOP (1u<<14) // Battery charging stopped.
+#define MCU_IRQ_BATT_CHARGE_START (1u<<15) // Battery charging started.
+#define MCU_IRQ_TWL_RESET (1u<<16) // DS powerman register 0x10 bit 0 = 1 or TWL MCU register 0x11 = 1 (reset).
+#define MCU_IRQ_TWL_PWROFF (1u<<17) // DS powerman register 0x10 bit 6 = 1. Poweroff request?
+#define MCU_IRQ_TWL_BOT_BL_OFF (1u<<18) // DS powerman register 0x10 bit 2 = 0. Bottom LCD backlight off request?
+#define MCU_IRQ_TWL_BOT_BL_ON (1u<<19) // DS powerman register 0x10 bit 2 = 1. Bottom LCD backlight on request?
+#define MCU_IRQ_TWL_TOP_BL_OFF (1u<<20) // DS powerman register 0x10 bit 3 = 0. Top LCD backlight off request?
+#define MCU_IRQ_TWL_TOP_BL_ON (1u<<21) // DS powerman register 0x10 bit 3 = 1. Top LCD backlight on request?
+#define MCU_IRQ_VOL_SLIDER_CHANGE (1u<<22) // Volume slider position changed.
+#define MCU_IRQ_TWL_MCU_VER_READ (1u<<23) // TWL MCU version register (0x00) read.
+#define MCU_IRQ_LCD_POWER_OFF (1u<<24) // LCDs have been powered off.
+#define MCU_IRQ_LCD_POWER_ON (1u<<25) // LCDs have been powered on.
+#define MCU_IRQ_BOT_BL_OFF (1u<<26) // Bottom LCD backlight has been powered off.
+#define MCU_IRQ_BOT_BL_ON (1u<<27) // Bottom LCD backlight has been powered on.
+#define MCU_IRQ_TOP_BL_OFF (1u<<28) // Top LCD backlight has been powered off.
+#define MCU_IRQ_TOP_BL_ON (1u<<29) // Top LCD backlight has been powered on.
+
+// MCU_REG_ACC_CFG
+typedef enum
+{
+ ACC_CFG_ALL_OFF = 0u, // Accelerometer and pedometer off.
+ ACC_CFG_ACC_ON_PM_OFF = 1u, // Accelerometer on and pedometer off.
+ ACC_CFG_ACC_OFF_PM_ON = 2u, // Accelerometer off and pedometer on.
+ ACC_CFG_ACC_ON_PM_ON = 3u // Accelerometer on and pedometer on.
+} AccCfg;
diff --git a/libn3ds/include/arm11/drivers/spiflash.h b/libn3ds/include/arm11/drivers/spiflash.h
index ae8f886..437071f 100644
--- a/libn3ds/include/arm11/drivers/spiflash.h
+++ b/libn3ds/include/arm11/drivers/spiflash.h
@@ -21,8 +21,18 @@
#include "types.h"
-#define SPIFLASH_CMD_RDSR (0x05)
-#define SPIFLASH_CMD_READ (0x03)
+#define SPIFLASH_PP (0x02u) // Page Program (0x100 bytes).
+#define SPIFLASH_READ (0x03u) // Read.
+#define SPIFLASH_WRDI (0x04u) // Write Disable.
+#define SPIFLASH_RDSR (0x05u) // Read Status Register.
+#define SPIFLASH_WREN (0x06u) // Write Enable.
+#define SPIFLASH_PW (0x0Au) // Page Write (0x100 bytes).
+#define SPIFLASH_FAST (0x0Bu) // Fast Read.
+#define SPIFLASH_RDP (0xABu) // Release from Deep Power-down.
+#define SPIFLASH_DP (0xB9u) // Deep Power-Down.
+#define SPIFLASH_SE (0xD8u) // Sector Erase (0x10000 bytes).
+#define SPIFLASH_PE (0xDBu) // Page Erase (0x100 bytes).
+#define SPIFLASH_RDID (0x9Fu) // Read JEDEC Identification.
diff --git a/libn3ds/source/arm11/drivers/codec.c b/libn3ds/source/arm11/drivers/codec.c
index 788f6d6..f7d949c 100644
--- a/libn3ds/source/arm11/drivers/codec.c
+++ b/libn3ds/source/arm11/drivers/codec.c
@@ -431,7 +431,7 @@ static void legacyTouchscreenMode(bool enabled)
static void headsetInit(void)
{
// Headset detection stuff.
- GPIO_config(GPIO_2_HEADPH_JACK, GPIO_IRQ_ENABLE | GPIO_EDGE_RISING | GPIO_INPUT); // Headphone jack IRQ.
+ GPIO_config(GPIO_2_HEADPH_JACK, GPIO_IRQ_RISING | GPIO_INPUT); // Headphone jack IRQ.
//maskReg(CDC_REG_HEADSET_SEL, GPIO_read(GPIO_2_HEADPH_JACK)<gpuprot = GPUPROT_NO_PROT;
@@ -131,10 +136,10 @@ void GFX_init(GfxFbFmt fmtTop, GfxFbFmt fmtBot)
REG_LCD_UNK00C = 0; // Starts H-/V-sync control signals?
TIMER_sleepMs(10); // Wait for power supply (which?) to stabilize and LCD drivers to finish resetting.
LCDI2C_init(); // Initialize LCD drivers.
- MCU_controlLCDPower(2u); // Power on LCDs (MCU --> PMIC).
+ MCU_setLcdPower(2u); // Power on LCDs (MCU --> PMIC).
// Timing critical part end.
// Wait 50 us for LCD sync. The MCU event wait will cover this.
- if(MCU_waitEvents(0x3Fu<<24) != 2u<<24) panic();
+ if(MCU_waitIrqs(MCU_LCD_IRQ_MASK) != MCU_IRQ_LCD_POWER_ON) panic();
// The transfer engine is (sometimes) borked on screen init.
// Doing a dummy texture copy fixes it.
@@ -146,8 +151,8 @@ void GFX_init(GfxFbFmt fmtTop, GfxFbFmt fmtBot)
REG_LCD_ABL0_LIGHT = 1;
REG_LCD_ABL1_LIGHT_PWM = 0x1023E; // TODO: Figure out how this works.
REG_LCD_ABL1_LIGHT = 1;
- MCU_controlLCDPower(0x28u); // Power on backlights.
- if(MCU_waitEvents(0x3Fu<<24) != 0x28u<<24) panic();
+ MCU_setLcdPower(0x28u); // Power on backlights.
+ if(MCU_waitIrqs(MCU_LCD_IRQ_MASK) != (MCU_IRQ_TOP_BL_ON | MCU_IRQ_BOT_BL_ON)) panic();
// Make sure the fills finished.
GFX_waitForPSC0();
@@ -176,8 +181,8 @@ void GFX_deinit(void)
const u8 power = g_gfxState.lcdPower;
if(power & ~1u)
{
- MCU_controlLCDPower(power & ~1u);
- if(MCU_waitEvents(0x3Fu<<24) != (u32)(power & ~1u)<<24) panic();
+ MCU_setLcdPower(power & ~1u);
+ if(MCU_waitIrqs(MCU_LCD_IRQ_MASK) != (u32)(power & ~1u)<<24) panic();
}
GFX_setBrightness(0, 0);
REG_LCD_ABL0_LIGHT_PWM = 0;
@@ -197,8 +202,8 @@ void GFX_deinit(void)
// Power off LCDs if on.
if(power & 1u)
{
- MCU_controlLCDPower(1u);
- if(MCU_waitEvents(0x3Fu<<24) != 1u<<24) panic();
+ MCU_setLcdPower(1u);
+ if(MCU_waitIrqs(MCU_LCD_IRQ_MASK) != MCU_IRQ_LCD_POWER_OFF) panic();
}
// TODO: Wait until PDC is not reading any data from mem.
@@ -365,8 +370,8 @@ void GFX_powerOnBacklights(GfxBlight mask)
g_gfxState.lcdPower |= mask;
mask <<= 1;
- MCU_controlLCDPower(mask); // Power on backlights.
- if(MCU_waitEvents(0x3Fu<<24) != (u32)mask<<24) panic();
+ MCU_setLcdPower(mask); // Power on backlights.
+ if(MCU_waitIrqs(MCU_LCD_IRQ_MASK) != (u32)mask<<24) panic();
}
void GFX_powerOffBacklights(GfxBlight mask)
@@ -374,8 +379,8 @@ void GFX_powerOffBacklights(GfxBlight mask)
fb_assert((mask & ~GFX_BLIGHT_BOTH) == 0u);
g_gfxState.lcdPower &= ~mask;
- MCU_controlLCDPower(mask); // Power off backlights.
- if(MCU_waitEvents(0x3Fu<<24) != (u32)mask<<24) panic();
+ MCU_setLcdPower(mask); // Power off backlights.
+ if(MCU_waitIrqs(MCU_LCD_IRQ_MASK) != (u32)mask<<24) panic();
}
void GFX_setBrightness(u8 top, u8 bot)
diff --git a/libn3ds/source/arm11/drivers/gpio.c b/libn3ds/source/arm11/drivers/gpio.c
index 44bd254..2807225 100644
--- a/libn3ds/source/arm11/drivers/gpio.c
+++ b/libn3ds/source/arm11/drivers/gpio.c
@@ -20,6 +20,11 @@
#include "arm11/drivers/gpio.h"
+#define GPIO_EDGE_FALLING (0u)
+#define GPIO_EDGE_RISING (1u<<1)
+#define GPIO_IRQ_ENABLE (1u<<2)
+
+
static vu16 *const g_datRegs[5] = {(vu16*)®_GPIO1_DAT, (vu16*)®_GPIO2_DAT,
®_GPIO2_DAT2, ®_GPIO3_DAT, ®_GPIO3_DAT2};
diff --git a/libn3ds/source/arm11/drivers/hid.c b/libn3ds/source/arm11/drivers/hid.c
index e1c382f..cb67f3c 100644
--- a/libn3ds/source/arm11/drivers/hid.c
+++ b/libn3ds/source/arm11/drivers/hid.c
@@ -29,6 +29,12 @@
#include "arm11/drivers/codec.h"
+#define MCU_HID_IRQ_MASK (MCU_IRQ_VOL_SLIDER_CHANGE | MCU_IRQ_BATT_CHARGE_START | \
+ MCU_IRQ_BATT_CHARGE_STOP | MCU_IRQ_SHELL_OPEN | \
+ MCU_IRQ_SHELL_CLOSE | MCU_IRQ_WIFI_PRESS | \
+ MCU_IRQ_HOME_RELEASE | MCU_IRQ_HOME_PRESS | \
+ MCU_IRQ_POWER_HELD | MCU_IRQ_POWER_PRESS)
+
#define CPAD_THRESHOLD (400)
@@ -46,10 +52,10 @@ void hidInit(void)
inited = true;
MCU_init();
- u8 state = MCU_getExternalHwState();
+ u16 state = MCU_getExternalHardwareStatus();
u32 tmp = ~state<<3 & KEY_SHELL; // Current shell state. Bit is inverted.
tmp |= state<<1 & KEY_BAT_CHARGING; // Current battery charging state
- state = MCU_getHidHeld();
+ state = MCU_getEarlyButtonsHeld();
tmp |= ~state<<1 & KEY_HOME; // Current HOME button state
g_extraKeys = tmp;
@@ -58,7 +64,7 @@ void hidInit(void)
static void updateMcuHidState(void)
{
- const u32 state = MCU_getEvents(0x40C07F);
+ const u32 state = MCU_getIrqs(MCU_HID_IRQ_MASK);
if(state == 0) return;
u32 tmp = g_extraKeys;
diff --git a/libn3ds/source/arm11/drivers/lgy.c b/libn3ds/source/arm11/drivers/lgy.c
index 4c99ebf..dd4f51c 100644
--- a/libn3ds/source/arm11/drivers/lgy.c
+++ b/libn3ds/source/arm11/drivers/lgy.c
@@ -124,7 +124,7 @@ Result LGY_prepareGbaMode(bool directBoot, u16 saveType, const char *const saveP
// Setup GBA Real-Time Clock.
GbaRtc rtc;
- MCU_getRTCTime((u8*)&rtc);
+ MCU_getRtcTimeDate((u8*)&rtc);
rtc.time = __builtin_bswap32(rtc.time)>>8;
rtc.date = __builtin_bswap32(rtc.date)>>8;
calcDayOfWeek(&rtc);
diff --git a/libn3ds/source/arm11/drivers/mcu.c b/libn3ds/source/arm11/drivers/mcu.c
index ccfc5d0..f957c45 100644
--- a/libn3ds/source/arm11/drivers/mcu.c
+++ b/libn3ds/source/arm11/drivers/mcu.c
@@ -16,20 +16,522 @@
* along with this program. If not, see .
*/
+#include
#include
#include "arm11/drivers/mcu.h"
#include "arm11/drivers/i2c.h"
+#include "arm11/debug.h"
#include "arm11/drivers/interrupt.h"
#include "arm11/drivers/gpio.h"
-static bool g_mcuIrq = false;
-static u32 g_mcuEvents = 0;
+static bool g_mcuNeedsIrqRead = false;
+static u32 g_mcuIrqs = 0;
+static struct
+{
+ u16 version; // MCU firmware version ((MCU_REG_VERS_MAJOR - 0x10)<<8 | MCU_REG_VERS_MINOR).
+ // TODO: Cache IRQ mask?
+ u8 conType; // Console type (MCU_REG_RAW_STATE[0]).
+ u8 systemModel; // System model (MCU_REG_RAW_STATE[9]).
+ u8 earlyButtonsHeld; // Early button state (MCU_REG_RAW_STATE[18]);
+} g_mcuRegCache;
static void mcuIrqHandler(UNUSED u32 intSource);
+static bool updateRegisterCache(void)
+{
+ // Read major and minor version at once.
+ u16 version;
+ if(!MCU_readRegBuf(MCU_REG_VERS_MAJOR, (u8*)&version, sizeof(version))) return false;
+ g_mcuRegCache.version = __builtin_bswap16(version - 0x10);
+
+ u8 tmp[19];
+ if(!MCU_readRegBuf(MCU_REG_RAW_STATE, tmp, sizeof(tmp))) return false;
+ g_mcuRegCache.conType = tmp[0];
+ g_mcuRegCache.systemModel = tmp[9];
+ g_mcuRegCache.earlyButtonsHeld = tmp[18];
+
+ return true;
+}
+
+void MCU_init(void)
+{
+ static bool mcuDriverInitialized = false;
+ if(mcuDriverInitialized) return;
+ mcuDriverInitialized = true;
+
+ // Make sure I2C is initialized.
+ I2C_init();
+
+ // Configure GPIO for MCU IRQs.
+ GPIO_config(GPIO_3_MCU, GPIO_IRQ_FALLING | GPIO_INPUT);
+
+ // TODO: Clear alarm regs here like mcu module? Is this really needed?
+
+ // Enable MCU IRQs.
+ IRQ_registerIsr(IRQ_CTR_MCU, 14, 0, mcuIrqHandler);
+
+ // Do first MCU IRQ read to clear all bits.
+ // Discard IRQs we don't care about.
+ atomic_store_explicit(&g_mcuNeedsIrqRead, true, memory_order_relaxed);
+ (void)MCU_getIrqs(~DEFAULT_MCU_IRQ_MASK);
+
+ // Set IRQ mask so we only get IRQs we are interested in.
+ if(!MCU_setIrqMask(DEFAULT_MCU_IRQ_MASK)) panic();
+
+ // Initialize register cache.
+ if(!updateRegisterCache()) panic();
+}
+
+/*bool MCU_reboot(void)
+{
+ // TODO: GPIO bitmask 0x40000 handling.
+
+ // Enters MCU update mode but since no firmware data
+ // is incoming it will just reboot.
+ if(!MCU_writeRegBuf(MCU_REG_FW_UPDATE, (const u8*)"jhl", 3)) return false;
+
+ // We need to wait 1 second for the MCU to reboot.
+ TIMER_sleepMs(1000);
+
+ // TODO: Some state needs to be restored after a reboot.
+
+ return true;
+}*/
+
+static void mcuIrqHandler(UNUSED u32 intSource)
+{
+ atomic_store_explicit(&g_mcuNeedsIrqRead, true, memory_order_relaxed);
+}
+
+// TODO: Rewrite using events (needs timeout support).
+u32 MCU_getIrqs(u32 mask)
+{
+ u32 irqs = g_mcuIrqs;
+
+ if(atomic_load_explicit(&g_mcuNeedsIrqRead, memory_order_relaxed))
+ {
+ atomic_store_explicit(&g_mcuNeedsIrqRead, false, memory_order_relaxed);
+
+ u32 newIrqs;
+ if(!MCU_readRegBuf(MCU_REG_IRQ, (u8*)&newIrqs, sizeof(newIrqs))) return 0;
+
+ irqs |= newIrqs;
+ }
+
+ g_mcuIrqs = irqs & ~mask;
+
+ return irqs & mask;
+}
+
+// TODO: Rewrite using events (needs timeout support).
+u32 MCU_waitIrqs(u32 mask)
+{
+ u32 irqs;
+
+ while((irqs = MCU_getIrqs(mask)) == 0u)
+ {
+ __wfi();
+ }
+
+ return irqs;
+}
+
+
+u16 MCU_getFirmwareVersion(void)
+{
+ return g_mcuRegCache.version;
+}
+
+u8 MCU_getStatus(void)
+{
+ return MCU_readReg(MCU_REG_STAT);
+}
+
+bool MCU_setStatus(u8 status)
+{
+ return MCU_writeReg(MCU_REG_STAT, status);
+}
+
+u8 MCU_getLcdVcomTop(void)
+{
+ return MCU_readReg(MCU_REG_LCD_VCOM_TOP);
+}
+
+bool MCU_setLcdVcomTop(u8 vcom)
+{
+ return MCU_writeReg(MCU_REG_LCD_VCOM_TOP, vcom);
+}
+
+u8 MCU_getLcdVcomBot(void)
+{
+ return MCU_readReg(MCU_REG_LCD_VCOM_BOT);
+}
+
+bool MCU_setLcdVcomBot(u8 vcom)
+{
+ return MCU_writeReg(MCU_REG_LCD_VCOM_BOT, vcom);
+}
+
+u8 MCU_get3dSliderPosition(void)
+{
+ return MCU_readReg(MCU_REG_3D_SLIDER);
+}
+
+u8 MCU_getVolumeSliderPosition(void)
+{
+ return MCU_readReg(MCU_REG_VOL_SLIDER);
+}
+
+u8 MCU_getBatteryTemperature(void)
+{
+ return MCU_readReg(MCU_REG_BATT_TEMP);
+}
+
+float MCU_getBatteryLevel(void)
+{
+ u8 buf[2];
+
+ // Read integer and fractional bytes at once.
+ if(!MCU_readRegBuf(MCU_REG_BATT_LEVEL, buf, sizeof(buf))) return NAN;
+
+ return buf[0] + (float)buf[1] / 256u; // TODO: Verify this.
+}
+
+float MCU_getBatteryVoltage(void)
+{
+ return 0.02f * MCU_readReg(MCU_REG_BATT_VOLT);
+}
+
+u16 MCU_getExternalHardwareStatus(void)
+{
+ u16 status;
+
+ // Read both status regs at once.
+ if(!MCU_readRegBuf(MCU_REG_EX_HW_STAT2, (u8*)&status, sizeof(status))) status = 0;
+
+ return __builtin_bswap16(status);
+}
+
+u32 MCU_getIrqMask(void)
+{
+ u32 mask;
+
+ if(!MCU_readRegBuf(MCU_REG_IRQ_MASK, (u8*)&mask, sizeof(mask))) mask = 0;
+
+ return mask;
+}
+
+bool MCU_setIrqMask(u32 mask)
+{
+ return MCU_writeRegBuf(MCU_REG_IRQ_MASK, (const u8*)&mask, sizeof(mask));
+}
+
+// TODO: MCU_setSystemPower()?
+
+void MCU_powerOffSys(void)
+{
+ I2C_writeRegIntSafe(I2C_DEV_CTR_MCU, MCU_REG_SYS_POW, 1u);
+}
+
+void MCU_rebootSys(void)
+{
+ I2C_writeRegIntSafe(I2C_DEV_CTR_MCU, MCU_REG_SYS_POW, 1u<<2);
+}
+
+bool MCU_setTwlIrq(u8 bits)
+{
+ return MCU_writeReg(MCU_REG_TWL_IRQ, bits);
+}
+
+void MCU_setLcdPower(u8 bits)
+{
+ MCU_writeReg(MCU_REG_LCD_POW, bits);
+}
+
+u8 MCU_getPoweroffDelay(void)
+{
+ return MCU_readReg(MCU_REG_PWROFF_DELAY);
+}
+
+bool MCU_setPoweroffDelay(u8 delay)
+{
+ return MCU_writeReg(MCU_REG_PWROFF_DELAY, delay);
+}
+
+u8 MCU_getRegister0x25(void)
+{
+ return MCU_readReg(MCU_REG_UNK25);
+}
+
+bool MCU_setRegister0x25(u8 data)
+{
+ return MCU_writeReg(MCU_REG_UNK25, data);
+}
+
+u8 MCU_getRegister0x26(void)
+{
+ return MCU_readReg(MCU_REG_UNK26);
+}
+
+bool MCU_setRegister0x26(u8 data)
+{
+ return MCU_writeReg(MCU_REG_UNK26, data);
+}
+
+u8 MCU_getVolumeSliderPositionRaw(void)
+{
+ return MCU_readReg(MCU_REG_VOL_SLIDER_RAW);
+}
+
+bool MCU_setVolumeSliderPositionRaw(u8 data)
+{
+ return MCU_writeReg(MCU_REG_VOL_SLIDER_RAW, data);
+}
+
+u8 MCU_getLedMasterBrightness(void)
+{
+ return MCU_readReg(MCU_REG_LED_BRIGHTNESS);
+}
+
+bool MCU_setLedMasterBrightness(u8 brightness)
+{
+ return MCU_writeReg(MCU_REG_LED_BRIGHTNESS, brightness);
+}
+
+bool MCU_getPowerLedPattern(u8 pattern[5])
+{
+ return MCU_readRegBuf(MCU_REG_POWER_LED, pattern, 5);
+}
+
+bool MCU_setPowerLedPattern(const u8 pattern[5])
+{
+ return MCU_writeRegBuf(MCU_REG_POWER_LED, pattern, 5);
+}
+
+u8 MCU_getWifiLedState(void)
+{
+ return MCU_readReg(MCU_REG_WIFI_LED);
+}
+
+bool MCU_setWifiLedState(u8 state)
+{
+ return MCU_writeReg(MCU_REG_WIFI_LED, state);
+}
+
+u8 MCU_getCameraLedState(void)
+{
+ return MCU_readReg(MCU_REG_CAM_LED);
+}
+
+bool MCU_setCameraLedState(u8 state)
+{
+ return MCU_writeReg(MCU_REG_CAM_LED, state);
+}
+
+u8 MCU_get3dLedState(void)
+{
+ return MCU_readReg(MCU_REG_3D_LED);
+}
+
+bool MCU_set3dLedState(u8 state)
+{
+ return MCU_writeReg(MCU_REG_3D_LED, state);
+}
+
+bool MCU_setInfoLedPattern(const u8 pattern[100])
+{
+ return MCU_writeRegBuf(MCU_REG_INFO_LED, pattern, 100);
+}
+
+u8 MCU_getInfoLedStatus(void)
+{
+ return MCU_readReg(MCU_REG_INFO_LED_STAT);
+}
+
+bool MCU_getRtcTimeDate(RtcTimeDate *timeDate)
+{
+ // Read time and date at once.
+ return MCU_readRegBuf(MCU_REG_RTC_S, (u8*)timeDate, sizeof(RtcTimeDate));
+}
+
+bool MCU_setRtcTimeDate(const RtcTimeDate *timeDate)
+{
+ // Write time and date at once.
+ return MCU_writeRegBuf(MCU_REG_RTC_S, (const u8*)timeDate, sizeof(RtcTimeDate));
+}
+
+u8 MCU_getRtcErrorCorrection(void)
+{
+ return MCU_readReg(MCU_REG_RTC_ERR_CORR);
+}
+
+bool MCU_setRtcErrorCorrection(u8 correction)
+{
+ return MCU_writeReg(MCU_REG_RTC_ERR_CORR, correction);
+}
+
+bool MCU_getAlarmTimeDate(AlarmTimeDate *timeDate)
+{
+ // Read time and date at once.
+ return MCU_readRegBuf(MCU_REG_ALARM_MIN, (u8*)timeDate, sizeof(AlarmTimeDate));
+}
+
+bool MCU_setAlarmTimeDate(const AlarmTimeDate *timeDate)
+{
+ // Write time and date at once.
+ return MCU_writeRegBuf(MCU_REG_ALARM_MIN, (const u8*)timeDate, sizeof(AlarmTimeDate));
+}
+
+u16 MCU_getRtcTick(void)
+{
+ u16 tick;
+
+ // Read both tick bytes at once.
+ if(!MCU_readRegBuf(MCU_REG_RTC_TICK_LO, (u8*)&tick, sizeof(tick))) tick = 0;
+
+ return tick;
+}
+
+bool MCU_setRegister0x3F(u8 data)
+{
+ return MCU_writeReg(MCU_REG_UNK3F, data);
+}
+
+AccCfg MCU_getAccelerometerConfig(void)
+{
+ return MCU_readReg(MCU_REG_ACC_CFG);
+}
+
+bool MCU_setAccelerometerConfig(AccCfg cfg)
+{
+ return MCU_writeReg(MCU_REG_ACC_CFG, cfg);
+}
+
+u8 MCU_readAccelerometerRegister(u8 reg)
+{
+ if(!MCU_writeReg(MCU_REG_ACC_READ_OFF, reg)) return 0;
+ MCU_waitIrqs(MCU_IRQ_ACC_RW_DONE);
+
+ return MCU_readReg(MCU_REG_ACC_DATA);
+}
+
+bool MCU_writeAccelerometerRegister(u8 reg, u8 data)
+{
+ const u16 regData = (u16)data<<8 | reg;
+
+ // Write register and data at once.
+ if(!MCU_writeRegBuf(MCU_REG_ACC_WRITE_OFF, (const u8*)®Data, sizeof(regData))) return false;
+ MCU_waitIrqs(MCU_IRQ_ACC_RW_DONE); // TODO: Is this needed? mcu module doesn't wait for write.
+
+ return true;
+}
+
+bool MCU_getAccelerometerSamples(AccData *samples)
+{
+ // Read all X/Y/Z sample bytes at once.
+ const bool res = MCU_readRegBuf(MCU_REG_ACC_X_LO, (u8*)samples, sizeof(AccData));
+
+ // Sample data is in the upper 12 bits.
+ samples->x >>= 4;
+ samples->y >>= 4;
+ samples->z >>= 4;
+
+ return res;
+}
+
+u32 MCU_getPedometerStepCount(void)
+{
+ u32 steps;
+
+ // Read all step count bytes at once.
+ if(!MCU_readRegBuf(MCU_REG_PM_COUNT_LO, (u8*)&steps, 3)) steps = 0;
+
+ return steps & ~0xFF000000u; // Make sure byte 4 is 0.
+}
+
+bool MCU_setPedometerStepCount(u32 steps)
+{
+ // Write all step count bytes at once.
+ return MCU_writeRegBuf(MCU_REG_PM_COUNT_LO, (u8*)&steps, 3);
+}
+
+// TODO: Reg 0x4E.
+
+bool MCU_getPedometerHistory(u8 history[6 + 336])
+{
+ // Read all history bytes at once.
+ const bool res = MCU_readRegBuf(MCU_REG_PM_HIST, history, 6 + 336);
+
+ // TODO: BCD to decimal for the timestamps.
+
+ return res;
+}
+
+u8 MCU_getRegister0x50(void)
+{
+ return MCU_readReg(MCU_REG_UNK50);
+}
+
+bool MCU_setRegister0x50(u8 data)
+{
+ return MCU_writeReg(MCU_REG_UNK50, data);
+}
+
+u8 MCU_getRegister0x51(void)
+{
+ return MCU_readReg(MCU_REG_UNK51);
+}
+
+bool MCU_setRegister0x51(u8 data)
+{
+ return MCU_writeReg(MCU_REG_UNK51, data);
+}
+
+bool MCU_getVolumeSliderCalibrationPoints(u8 minMax[2])
+{
+ // Read min and max at once.
+ return MCU_readRegBuf(MCU_REG_VOL_SLIDER_MIN, minMax, 2);
+}
+
+bool MCU_setVolumeSliderCalibrationPoints(const u8 minMax[2])
+{
+ // Write min and max at once.
+ return MCU_writeRegBuf(MCU_REG_VOL_SLIDER_MIN, minMax, 2);
+}
+
+bool MCU_getFreeRamData(u8 off, u8 *out, u8 size)
+{
+ if(!MCU_writeReg(MCU_REG_FREE_RAM_OFF, off)) return false;
+
+ return MCU_readRegBuf(MCU_REG_FREE_RAM_DATA, out, size);
+}
+
+bool MCU_setFreeRamData(u8 off, const u8 *in, u8 size)
+{
+ if(!MCU_writeReg(MCU_REG_FREE_RAM_OFF, off)) return false;
+
+ return MCU_writeRegBuf(MCU_REG_FREE_RAM_DATA, in, size);
+}
+
+u8 MCU_getConsoleType(void)
+{
+ return g_mcuRegCache.conType;
+}
+
+u8 MCU_getSystemModel(void)
+{
+ return g_mcuRegCache.systemModel;
+}
+
+u8 MCU_getEarlyButtonsHeld(void)
+{
+ return g_mcuRegCache.earlyButtonsHeld;
+}
+
+
u8 MCU_readReg(McuReg reg)
{
return I2C_readReg(I2C_DEV_CTR_MCU, reg);
@@ -49,62 +551,3 @@ bool MCU_writeRegBuf(McuReg reg, const u8 *const in, u32 size)
{
return I2C_writeRegBuf(I2C_DEV_CTR_MCU, reg, in, size);
}
-
-void MCU_init(void)
-{
- static bool inited = false;
- if(inited) return;
- inited = true;
-
- I2C_init();
-
- // Configure GPIO for MCU event IRQs
- GPIO_config(GPIO_3_MCU, GPIO_INPUT | GPIO_EDGE_FALLING | GPIO_IRQ_ENABLE);
- IRQ_registerIsr(IRQ_CTR_MCU, 14, 0, mcuIrqHandler);
-
- atomic_store_explicit(&g_mcuIrq, true, memory_order_relaxed);
- (void)MCU_getEvents(0);
-
- MCU_setEventMask(0xC0BF3F80);
-}
-
-static void mcuIrqHandler(UNUSED u32 intSource)
-{
- g_mcuIrq = true;
-}
-
-bool MCU_setEventMask(u32 mask)
-{
- return MCU_writeRegBuf(MCU_REG_EVENT_MASK, (const u8*)&mask, 4);
-}
-
-u32 MCU_getEvents(u32 mask)
-{
- u32 events = g_mcuEvents;
-
- if(atomic_load_explicit(&g_mcuIrq, memory_order_relaxed))
- {
- atomic_store_explicit(&g_mcuIrq, false, memory_order_relaxed);
-
- u32 data;
- if(!MCU_readRegBuf(MCU_REG_EVENTS, (u8*)&data, 4)) return 0;
-
- events |= data;
- }
-
- g_mcuEvents = events & ~mask;
-
- return events & mask;
-}
-
-u32 MCU_waitEvents(u32 mask)
-{
- u32 events;
-
- while((events = MCU_getEvents(mask)) == 0u)
- {
- __wfi();
- }
-
- return events;
-}
diff --git a/libn3ds/source/arm11/drivers/spiflash.c b/libn3ds/source/arm11/drivers/spiflash.c
index 7df52f5..20c1c85 100644
--- a/libn3ds/source/arm11/drivers/spiflash.c
+++ b/libn3ds/source/arm11/drivers/spiflash.c
@@ -26,7 +26,7 @@ bool spiflash_get_status(void)
{
alignas(4) u8 cmd[4];
- cmd[0] = SPIFLASH_CMD_RDSR;
+ cmd[0] = SPIFLASH_RDSR;
NSPI_writeRead(NSPI_DEV_CS_HIGH | NSPI_DEV_NVRAM, (u32*)cmd, (u32*)cmd, 1, 1);
if(cmd[0] & 1) return false;
@@ -35,7 +35,7 @@ bool spiflash_get_status(void)
void spiflash_read(u32 offset, u32 size, u32 *buf)
{
- offset = __builtin_bswap32(offset & 0x00FFFFFFu) | SPIFLASH_CMD_READ;
+ offset = __builtin_bswap32(offset & 0x00FFFFFFu) | SPIFLASH_READ;
NSPI_writeRead(NSPI_DEV_CS_HIGH | NSPI_DEV_NVRAM, &offset, buf, 4, size);
}
diff --git a/libn3ds/source/arm9/drivers/lgy.c b/libn3ds/source/arm9/drivers/lgy.c
index beeb6f6..c6f6b78 100644
--- a/libn3ds/source/arm9/drivers/lgy.c
+++ b/libn3ds/source/arm9/drivers/lgy.c
@@ -47,8 +47,8 @@ typedef struct
u8 _0x10a[6];
vu32 gba_rtc_bcd_date;
vu32 gba_rtc_bcd_time;
- vu32 gba_rtc_hex_time; // Writing bit 7 completely hangs all(?) GBA hardware.
- vu32 gba_rtc_hex_date;
+ vu32 gba_rtc_toffset; // Writing bit 7 completely hangs all(?) GBA hardware.
+ vu32 gba_rtc_doffset;
vu32 gba_save_timing[4];
} Lgy;
static_assert(offsetof(Lgy, gba_save_timing) == 0x120, "Error: Member gba_save_timing of Lgy is not at offset 0x120!");
@@ -138,8 +138,8 @@ Result LGY_setGbaRtc(const GbaRtc rtc)
//while(lgy->gba_rtc_cnt & LGY_RTC_CNT_BUSY);
//lgy->gba_rtc_cnt = 0; // Legacy P9 does this. Useless?
- lgy->gba_rtc_hex_time = 1u<<15; // Time offset 0 and 24h format.
- lgy->gba_rtc_hex_date = 0; // Date offset 0.
+ lgy->gba_rtc_toffset = 1u<<15; // Time offset 0 and 24h format.
+ lgy->gba_rtc_doffset = 0; // Date offset 0.
lgy->gba_rtc_cnt = LGY_RTC_CNT_WR;
while(lgy->gba_rtc_cnt & LGY_RTC_CNT_BUSY);