Compare commits

...

12 Commits

Author SHA1 Message Date
feb743bb58 Added the CH340 USB to serial adapter chip's datasheet 2023-04-10 21:26:58 +02:00
8c1627b9b2 Officially added the gadget bridge parser I developed to the W800_Smart_Watch firmware 2023-04-10 21:26:25 +02:00
2b80115e47 Added some functionalities on the UI side in the code blocks simulator 2023-04-10 21:24:04 +02:00
090e1a2d61 Added the API function doc comments 2023-04-10 21:23:02 +02:00
dea34c70e8 Added a persistency setting : the Activity one, which will be used to save the step counter feature (Enabled or not) as well as other activity related parameters 2023-04-10 21:21:59 +02:00
288a64d1ce Did some cleanup by removing direct access to the watch sensor for initialization, added the gadget bridge parser I coded, and other minor stuff 2023-04-10 21:20:38 +02:00
22621219f3 Corrected a potential bug, made the date and time rollers disabled when set automatic time and date is enabled. Added the set automatic time and date feature which time and dates, if enabled, are sent by the Gadget Bridge Android Application 2023-04-10 21:19:19 +02:00
1c39e02f11 Added new line at the end of the file 2023-04-10 21:17:01 +02:00
da59200c77 Minor changes, nothing major 2023-04-10 21:16:27 +02:00
92d3279eb9 Big refactoring and cleanup by removing sensors initialization code from the gfx_task.c file and moving it to the watch_peripherals.c source file. This is way more logical IMO. This change also allows to enable or disable the wrist tilt wakeup with a function call 2023-04-10 21:15:47 +02:00
b8a11a8a79 Renamed QMC5883L_Mode_Control enumeration values to make it clear they are to be used in the magnetometer API 2023-04-10 21:13:18 +02:00
efae9a917e Added a function to the pressure sensor API to be able to know if a measurement is currently being made 2023-04-10 21:12:01 +02:00
20 changed files with 2835 additions and 555 deletions

Binary file not shown.

View File

@ -113,6 +113,16 @@ bool BMP280_trigger_measurement(void)
return i2c_write_reg(BMP280_I2C_ADDR, BMP280_CTRL_MEAS, data);
}
bool BMP280_is_measuring(void)
{
uint8_t data;
if(!i2c_read_reg(BMP280_I2C_ADDR, BMP280_STATUS, &data)) return false;
/* If bit 3 of the status register is 1, then a measurement is ongoing */
return (data >> 3) & 0x01;
}
float BMP280_get_temperature(void)
{
int32_t var1, var2;

View File

@ -110,6 +110,15 @@ bool BMP280_configure(BMP280_Mode_e mode, BMP280_Oversampling_e temperature_over
*/
bool BMP280_trigger_measurement(void);
/**
* @brief Checks if the sensor is currently performing a measurement or not.
* This can be useful to check if the measurement is ready after calling @ref BMP280_trigger_measurement.
*
* @return true if the sensor is currently performing a measurement.
* @return false if the sensor is not, this means that the data is ready to be read.
*/
bool BMP280_is_measuring(void);
/**
* @brief Returns the previously sampled temperature in °C.
*

View File

@ -21,8 +21,8 @@
/* Configuration enumerations */
typedef enum QMC5883L_Mode_Control
{
Standby = 0,
Continuous = 1,
QMC5883L_Mode_Control_Standby = 0,
QMC5883L_Mode_Control_Continuous = 1,
} QMC5883L_Mode_Control_e;
typedef enum QMC5883L_Output_Data_Rate

View File

@ -5,6 +5,10 @@
#include "wm_adc.h"
#include "wm_timer.h"
#include "wm_pwm.h"
#include "i2c.h"
#include "BMP280.h"
#include "FreeRTOS.h" // <---- Only needed for the pdMS_TO_TICKS macro, to be removed
#include "bma456w.h"
#define INTERRUPT_POLICY (0)
#define POLL_POLICY (1)
@ -21,6 +25,23 @@ static uint8_t _vibration_motor_timer_id = WM_TIMER_ID_INVALID;
static battery_controller_status_e _battery_fsm = BATTERY_CONTROLLER_STATUS_DISCHARGING;
static BatteryControllerStatusChangeCb_t _BatteryControllerStatusChangeCb = NULL;
/* BMA456 strcture */
struct
{
uint8_t dev_addr;
struct bma4_dev bma;
struct bma4_accel_config accel_conf;
struct bma456w_wrist_wear_wakeup_params setting;
struct bma4_int_pin_config pin_config;
bool wrist_wakeup_enable;
bool step_counter_enable;
} _bma456 =
{
.dev_addr = BMA4_I2C_ADDR_SECONDARY,
.wrist_wakeup_enable = false,
};
static void vibration_motor_timer_irq_cb(void *p)
{
(void)p;
@ -29,7 +50,7 @@ static void vibration_motor_timer_irq_cb(void *p)
tls_gpio_write(VIBRATION_MOTOR_ENABLE, 0);
}
#if BATTERY_CONTROLLER_STATUS_DETECTION_POLICY == POLL_POLICY
#if BATTERY_CONTROLLER_STATUS_DETECTION_POLICY == POLL_POLICY && HARDWARE_PLATFORM == SMART_WATCH_PCB
static uint8_t _battery_status_timer_id = WM_TIMER_ID_INVALID;
static void battery_status_timer_irq_cb(void *p)
@ -58,7 +79,7 @@ static void battery_status_timer_irq_cb(void *p)
if(_BatteryControllerStatusChangeCb) _BatteryControllerStatusChangeCb(old_battery_status, _battery_fsm);
}
}
#elif BATTERY_CONTROLLER_STATUS_DETECTION_POLICY == INTERRUPT_POLICY
#elif BATTERY_CONTROLLER_STATUS_DETECTION_POLICY == INTERRUPT_POLICY && HARDWARE_PLATFORM == SMART_WATCH_PCB
static void battery_controller_irq_cb(void *p)
{
enum tls_io_name gpio_pin = (enum tls_io_name)p;
@ -122,7 +143,7 @@ static void watch_peripherals_io_init(void)
tls_gpio_cfg(BATTERY_CONTROLLER_CHARGED_STATUS, WM_GPIO_DIR_INPUT, WM_GPIO_ATTR_FLOATING);
tls_gpio_cfg(BATTERY_CONTROLLER_CHARGING_STATUS, WM_GPIO_DIR_INPUT, WM_GPIO_ATTR_FLOATING);
#if BATTERY_CONTROLLER_STATUS_DETECTION_POLICY == INTERRUPT_POLICY
#if BATTERY_CONTROLLER_STATUS_DETECTION_POLICY == INTERRUPT_POLICY && HARDWARE_PLATFORM == SMART_WATCH_PCB
tls_gpio_isr_register(BATTERY_CONTROLLER_CHARGED_STATUS, &(battery_controller_irq_cb), (int*) BATTERY_CONTROLLER_CHARGED_STATUS);
tls_gpio_irq_enable(BATTERY_CONTROLLER_CHARGED_STATUS, WM_GPIO_IRQ_TRIG_DOUBLE_EDGE); // Enabled when level is changing edge
@ -171,7 +192,7 @@ void watch_peripherals_init(int8_t adcOffset)
if(WM_TIMER_ID_INVALID == _vibration_motor_timer_id)
APP_LOG_ERROR("Failed to create vibration motor timer");
}
#if BATTERY_CONTROLLER_STATUS_DETECTION_POLICY == POLL_POLICY
#if BATTERY_CONTROLLER_STATUS_DETECTION_POLICY == POLL_POLICY && HARDWARE_PLATFORM == SMART_WATCH_PCB
if(WM_TIMER_ID_INVALID == _battery_status_timer_id)
{
struct tls_timer_cfg battery_status_timer_cfg =
@ -190,6 +211,9 @@ void watch_peripherals_init(int8_t adcOffset)
tls_timer_start(_battery_status_timer_id);
}
#endif
/* Let's init the I2C interface */
i2c_init(I2C_SDA, I2C_SCL, I2C_CLOCK_SPEED);
}
void watch_peripherals_register_battery_controller_status_change_cb(BatteryControllerStatusChangeCb_t BatteryControllerStatusChangeCb)
@ -264,3 +288,309 @@ void watch_peripherals_set_orientation(LCDOrientation_e orientation)
extern LCDConfig_t LCDConfig;
lcd_orientation(&LCDConfig, orientation);
}
bool watch_peripherals_magnetometer_init(void)
{
/* Init the magnetometer */
if(!QMC5883L_init())
{
APP_LOG_ERROR("Failed to init QMC5883L");
return false;
}
else
APP_LOG_INFO("Inited QMC5883L");
/* Needed but UGLY */
tls_os_time_delay(2);
if(!QMC5883L_set_power_mode(QMC5883L_Mode_Control_Continuous))
{
APP_LOG_ERROR("Failed to set QMC5883L mode");
return false;
}
else
APP_LOG_INFO("QMC5883L Mode set");
/* Needed but UGLY */
tls_os_time_delay(2);
if(!QMC5883L_configure_1(ODR_10HZ, FS_2G, OSR_512))
{
APP_LOG_ERROR("Failed to configure 1 QMC5883L");
return false;
}
else
APP_LOG_INFO("QMC5883L configured");
return true;
}
void watch_peripherals_magnetometer_calibration_data_set(
int16_t x_min, int16_t x_max,
int16_t y_min, int16_t y_max,
int16_t z_min, int16_t z_max, float temperature_offset
)
{
QMC5883L_set_calibration_data(x_min, x_max, y_min, y_max, z_min, z_max, temperature_offset);
}
uint16_t watch_peripherals_magnetometer_azimuth_read(bool *is_data_available)
{
bool data_ready = QMC5883L_is_data_available();
if(is_data_available) *is_data_available = data_ready;
if(!data_ready) return 0;
QMC5883L_MData_calibrated_t MData = QMC5883L_get_MFields_calibrated();
return QMC5883L_get_azimuth(MData);
}
QMC5883L_MData_t watch_peripherals_magnetometer_raw_data_read(void)
{
return QMC5883L_get_MFields_raw();
}
bool watch_peripherals_magnetometer_power_mode_set(QMC5883L_Mode_Control_e mode_control)
{
return QMC5883L_set_power_mode(mode_control);
}
bool watch_peripherals_pressure_sensor_init(void)
{
/* Init the BMP280 */
if(!BMP280_init())
{
APP_LOG_ERROR("Failed to init BMP280");
return false;
}
else
APP_LOG_INFO("Inited BMP280");
if(!BMP280_configure(BMP280_Forced, BMP280_Oversampling_x16, BMP280_Oversampling_x16, BMP280_Filter_x16, BMP280_Standby_4000MS))
{
APP_LOG_ERROR("Failed to configure BMP280");
return false;
}
else
APP_LOG_INFO("BMP280 configured");
return true;
}
float watch_peripherals_pressure_sensor_get_pressure(float * const temperature)
{
BMP280_trigger_measurement();
while(BMP280_is_measuring());
return BMP280_get_pressure(temperature);
}
static BMA4_INTF_RET_TYPE _bma4_i2c_read(uint8_t reg_addr, uint8_t *read_data, uint32_t len, void *intf_ptr)
{
uint8_t dev_address = *(uint8_t*)intf_ptr;
return !i2c_read(dev_address, reg_addr, read_data, len);
}
static BMA4_INTF_RET_TYPE _bma4_i2c_write(uint8_t reg_addr, const uint8_t *read_data, uint32_t len, void *intf_ptr)
{
uint8_t dev_address = *(uint8_t*)intf_ptr;
return !i2c_write(dev_address, reg_addr, read_data, len);
}
// TODO: Rework the delay_us function to rather use a timer and have real µs resolution and not ms ...
static void _bma4_delay_us(uint32_t period, void *intf_ptr)
{
(void) intf_ptr;
if(period < 1000)
tls_os_time_delay(1);
else
tls_os_time_delay(pdMS_TO_TICKS(period / 1000));
}
bool watch_peripherals_accelerometer_init(void)
{
/* Init the BMA456 */
_bma456.bma.intf = BMA4_I2C_INTF;
_bma456.bma.intf_ptr = &_bma456.dev_addr;
_bma456.bma.bus_read = &(_bma4_i2c_read);
_bma456.bma.bus_write = &(_bma4_i2c_write);
_bma456.bma.variant = BMA45X_VARIANT;
_bma456.bma.delay_us = &(_bma4_delay_us);
_bma456.bma.read_write_len = 46;
_bma456.bma.perf_mode_status = BMA4_DISABLE;
if(bma456w_init(&_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 init");
else
{
APP_LOG_ERROR("Failed to init BMA456");
return false;
}
if(bma4_soft_reset(&_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 soft reset");
else
{
APP_LOG_ERROR("Failed to soft reset BMA456");
return false;
}
tls_os_time_delay(2);
if(bma456w_write_config_file(&_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 config ok");
else
{
APP_LOG_ERROR("BMA456 config failed");
return false;
}
_bma456.accel_conf.odr = BMA4_OUTPUT_DATA_RATE_100HZ;
_bma456.accel_conf.range = BMA4_ACCEL_RANGE_2G;
_bma456.accel_conf.bandwidth = BMA4_ACCEL_NORMAL_AVG4;
_bma456.accel_conf.perf_mode = BMA4_CIC_AVG_MODE;
if(bma4_set_accel_config(&_bma456.accel_conf, &_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 accel conf ok");
else
{
APP_LOG_ERROR("BMA456 accel conf failed");
return false;
}
if(bma4_set_accel_enable(1, &_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 accel en ok");
else
{
APP_LOG_ERROR("BMA456 accel en failed");
return false;
}
return true;
}
bool watch_peripherals_accelerometer_wrist_wakeup_enable(bool enable)
{
if(_bma456.wrist_wakeup_enable == enable) return true;
_bma456.wrist_wakeup_enable = enable;
if(bma456w_feature_enable(BMA456W_WRIST_WEAR_WAKEUP, enable, &_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 feature enable ok");
else
{
APP_LOG_ERROR("BMA456 feature enable failed");
return false;
}
if(bma456w_get_wrist_wear_wakeup_param_config(&_bma456.setting, &_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 get wrist param ok");
else
{
APP_LOG_ERROR("BMA456 get wrist param failed");
return false;
}
APP_LOG_DEBUG("%d %d %d %d %d %d %d %d",
_bma456.setting.min_angle_focus,
_bma456.setting.min_angle_non_focus,
_bma456.setting.angle_landscape_right,
_bma456.setting.angle_landscape_left,
_bma456.setting.angle_portrait_up,
_bma456.setting.angle_portrait_down,
_bma456.setting.min_dur_moved,
_bma456.setting.min_dur_quite);
if(bma4_get_int_pin_config(&_bma456.pin_config, BMA4_INTR1_MAP, &_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 get pin conf ok");
else
{
APP_LOG_ERROR("BMA456 get pin conf failed");
return false;
}
if(bma456w_map_interrupt(BMA4_INTR1_MAP, BMA456W_WRIST_WEAR_WAKEUP_INT, enable, &_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 map int ok");
else
{
APP_LOG_ERROR("BMA456 map int failed");
return false;
}
_bma456.pin_config.edge_ctrl = BMA4_EDGE_TRIGGER;
_bma456.pin_config.output_en = BMA4_OUTPUT_ENABLE;
_bma456.pin_config.lvl = BMA4_ACTIVE_LOW;
_bma456.pin_config.od = BMA4_PUSH_PULL;
_bma456.pin_config.input_en = BMA4_INPUT_DISABLE;
if(bma4_set_int_pin_config(&_bma456.pin_config, BMA4_INTR1_MAP, &_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 set pin conf ok");
else
{
APP_LOG_ERROR("BMA456 set pin conf failed");
return false;
}
return true;
}
bool watch_peripherals_accelerometer_wrist_wakeup_interrupt(void)
{
uint16_t bma456_int_status;
uint8_t rslt = bma456w_read_int_status(&bma456_int_status, &_bma456.bma);
if(rslt != BMA4_OK)
{
APP_LOG_ERROR("Failed to read int status");
return false;
}
if((BMA4_OK == rslt) && (bma456_int_status & BMA456W_WRIST_WEAR_WAKEUP_INT))
return true;
return false;
}
bool watch_peripherals_accelerometer_step_counter_enable(bool enable)
{
if(_bma456.step_counter_enable == enable) return true;
_bma456.step_counter_enable = enable;
if(bma456w_feature_enable(BMA456W_STEP_CNTR, BMA4_ENABLE, &_bma456.bma) == BMA4_OK)
APP_LOG_INFO("BMA456 step cnter feature enable ok");
else
{
APP_LOG_ERROR("BMA456 step cnter feature enable failed");
return false;
}
return true;
}
bool watch_peripherals_accelerometer_step_count_read(uint32_t *step_count)
{
if(!step_count) return false;
if(bma456w_step_counter_output(step_count, &_bma456.bma) != BMA4_OK)
{
APP_LOG_ERROR("Failed to read step counts");
return false;
}
return true;
}
bool watch_peripherals_accelerometer_step_count_reset(void)
{
if(bma456w_reset_step_counter(&_bma456.bma) != BMA4_OK)
{
APP_LOG_ERROR("Failed to reset step counts");
return false;
}
return true;
}

View File

@ -6,6 +6,7 @@
#define WATCH_PERIPHERALS_H
#include "lcd.h"
#include "wm_type_def.h"
#include "QMC5883L.h"
typedef enum battery_unit
{
@ -32,8 +33,8 @@ typedef void (*BatteryControllerStatusChangeCb_t)(battery_controller_status_e ol
const char *battery_controller_status_2_str(battery_controller_status_e status);
/**
* @brief Inits the watch peripherals driver.
* This must be called before using the API.
* @brief Inits the watch peripherals drivers and sets battery sensing ADC offset.
* This must be called before using the watch peripherals API.
*
* @param adcOffset an offset in mV to apply to the battery voltage reading.
*/
@ -100,4 +101,34 @@ void watch_peripherals_set_brightness(uint8_t brightness);
*/
void watch_peripherals_set_orientation(LCDOrientation_e orientation);
bool watch_peripherals_magnetometer_init(void);
void watch_peripherals_magnetometer_calibration_data_set(
int16_t x_min, int16_t x_max,
int16_t y_min, int16_t y_max,
int16_t z_min, int16_t z_max, float temperature_offset
);
uint16_t watch_peripherals_magnetometer_azimuth_read(bool *is_data_available);
QMC5883L_MData_t watch_peripherals_magnetometer_raw_data_read(void);
bool watch_peripherals_magnetometer_power_mode_set(QMC5883L_Mode_Control_e mode_control);
bool watch_peripherals_pressure_sensor_init(void);
float watch_peripherals_pressure_sensor_get_pressure(float * const temperature);
bool watch_peripherals_accelerometer_init(void);
bool watch_peripherals_accelerometer_wrist_wakeup_enable(bool enable);
bool watch_peripherals_accelerometer_wrist_wakeup_interrupt(void);
bool watch_peripherals_accelerometer_step_counter_enable(bool enable);
bool watch_peripherals_accelerometer_step_count_read(uint32_t *step_count);
bool watch_peripherals_accelerometer_step_count_reset(void);
#endif //WATCH_PERIPHERALS_H

View File

@ -95,4 +95,4 @@ bool is_ble_modem_on(void)
if(bt_adapter_state == WM_BT_STATE_OFF || bt_system_action != WM_BT_SYSTEM_ACTION_IDLE)
return false;
return true;
}
}

View File

@ -29,4 +29,4 @@ bool ble_modem_off(void);
*/
bool is_ble_modem_on(void);
#endif //BLE_MODEM_H
#endif //BLE_MODEM_H

View File

@ -123,4 +123,4 @@ bool ble_service_send_nus_data(const uint8_t *data, uint16_t length);
*/
void ble_service_register_nus_data_rx_cb(nus_data_rx_fn_t nus_data_rx_cb);
#endif //BLE_APP_H
#endif //BLE_APP_H

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,321 @@
/**
* @file gadget_bridge.h
* @author Anatole SCHRAMM-HENRY
* @brief Header file exposing the API used to communicate/interact with the GadgetBridge Android application
* over BLE.
* @version 0.1
* @date 2023-04-04
*
* @copyright MIT
*
*/
#ifndef GADGET_BRIDGE_H
#define GADGET_BRIDGE_H
#include "wm_type_def.h"
#include <time.h>
/**
* @brief GADGET_BRIDGE_PARSER_BUFFER_SIZE allows to set the size of the buffer
* which is internally used by the parser to do it's job.
*
*/
#define GADGET_BRIDGE_PARSER_BUFFER_SIZE (300)
/**
* @brief GADGET_BRIDGE_PARSER_BUFFER_THRESHOLD permits to set a size threshold used to free up
* some space in the parser's internal buffer when the threshold is reached.
* This ensures that we can keep on feeding new data and not get stuck.
*
*/
#define GADGET_BRIDGE_PARSER_BUFFER_THRESHOLD (100)
/**
* @brief GADGET_BRIDGE_PARSER_MAX_BODY_SIZE defines the max body size that will be saved in the event_data
* structure when parsing the body of a notification.
*
*/
#define GADGET_BRIDGE_PARSER_MAX_BODY_SIZE (200)
/**
* @brief GADGET_BRIDGE_PARSER_MAX_TITLE_SIZE defines the max title size that will be saved in the event_data
* structure when parsing the title of a notification.
*
*/
#define GADGET_BRIDGE_PARSER_MAX_TITLE_SIZE (100)
typedef enum gadget_bridge_toast_type
{
GADGET_BRIDGE_TOAST_TYPE_INFO = 0,
GADGET_BRIDGE_TOAST_TYPE_WARN,
GADGET_BRIDGE_TOAST_TYPE_ERROR,
} gadget_bridge_toast_type_e;
typedef enum gadget_bridge_music_control
{
GADGET_BRIDGE_MUSIC_CONTROL_PLAY = 0,
GADGET_BRIDGE_MUSIC_CONTROL_PAUSE,
GADGET_BRIDGE_MUSIC_CONTROL_PLAYPAUSE,
GADGET_BRIDGE_MUSIC_CONTROL_NEXT,
GADGET_BRIDGE_MUSIC_CONTROL_PREVIOUS,
GADGET_BRIDGE_MUSIC_CONTROL_VOLUMEUP,
GADGET_BRIDGE_MUSIC_CONTROL_VOLUMEDOWN,
GADGET_BRIDGE_MUSIC_CONTROL_FORWARD,
GADGET_BRIDGE_MUSIC_CONTROL_REWIND,
} gadget_bridge_music_control_e;
typedef enum gadget_bridge_call_action
{
GADGET_BRIDGE_CALL_ACTION_ACCEPT = 0,
GADGET_BRIDGE_CALL_ACTION_END,
GADGET_BRIDGE_CALL_ACTION_INCOMING,
GADGET_BRIDGE_CALL_ACTION_OUTGOING,
GADGET_BRIDGE_CALL_ACTION_REJECT,
GADGET_BRIDGE_CALL_ACTION_START,
GADGET_BRIDGE_CALL_ACTION_IGNORE,
GADGET_BRIDGE_CALL_ACTION_UNKNOWN,
} gadget_bridge_call_action_e;
typedef enum gadget_bridge_notification_action
{
GADGET_BRIDGE_NOTIFICATION_ACTION_DISMISS = 0,
GADGET_BRIDGE_NOTIFICATION_ACTION_DISMISS_ALL,
GADGET_BRIDGE_NOTIFICATION_ACTION_OPEN,
GADGET_BRIDGE_NOTIFICATION_ACTION_MUTE,
GADGET_BRIDGE_NOTIFICATION_ACTION_REPLY,
} gadget_bridge_notification_action_e;
typedef enum gadget_bridge_http_request_method
{
GADGET_BRIDGE_HTTP_REQUEST_GET = 0,
GADGET_BRIDGE_HTTP_REQUEST_POST,
GADGET_BRIDGE_HTTP_REQUEST_HEAD,
GADGET_BRIDGE_HTTP_REQUEST_PUT,
GADGET_BRIDGE_HTTP_REQUEST_PATCH,
GADGET_BRIDGE_HTTP_REQUEST_DELETE,
} gadget_bridge_http_request_method_e;
typedef enum gadget_bridge_parser_code
{
GADGET_BRIDGE_PARSER_CODE_OK = 0,
GADGET_BRIDGE_PARSER_CODE_PARSING,
GADGET_BRIDGE_PARSER_CODE_BUFFER_FULL,
GADGET_BRIDGE_PARSER_CODE_DATA_TOO_LONG,
} gadget_bridge_parser_code_e;
typedef struct http_header
{
const char *key;
const char *value;
} http_header_t;
typedef enum gadget_bridge_event_type
{
GADGET_BRIDGE_EVENT_TYPE_NONE = 0,
GADGET_BRIDGE_EVENT_TYPE_SET_TIME,
GADGET_BRIDGE_EVENT_TYPE_NOTIFY,
GADGET_BRIDGE_EVENT_TYPE_CALL,
GADGET_BRIDGE_EVENT_TYPE_WEATHER,
GADGET_BRIDGE_EVENT_TYPE_FIND,
GADGET_BRIDGE_EVENT_TYPE_ACT,
GADGET_BRIDGE_EVENT_TYPE_MUSIC_INFO,
GADGET_BRIDGE_EVENT_TYPE_MUSIC_STATE,
GADGET_BRIDGE_EVENT_TYPE_UNKNOWN,
} gadget_bridge_event_type_e;
typedef enum gadget_bridge_notification_type
{
GADGET_BRIDGE_NOTIFICATION_TYPE_SMS = 0,
GADGET_BRIDGE_NOTIFICATION_TYPE_EMAIL,
GADGET_BRIDGE_NOTIFICATION_TYPE_UNKNOWN,
} gadget_bridge_notification_type_e;
typedef enum
{
GADGET_BRIDGE_MUSIC_STATE_PAUSE = 0,
GADGET_BRIDGE_MUSIC_STATE_PLAY,
GADGET_BRIDGE_MUSIC_STATE_UNKNOWN,
} gadget_bridge_music_state_e;
typedef struct gadget_bridge_event_data
{
gadget_bridge_event_type_e event_type;
union
{
struct
{
struct tm gm_time;
struct tm local_time;
int8_t time_zone;
} time;
struct
{
uint32_t handle;
gadget_bridge_notification_type_e notification_type;
char *title;
char *body;
} notification;
struct
{
char *phone_number;
char *contact;
gadget_bridge_call_action_e call_action;
} call;
struct
{
float temperature_celsius;
uint8_t humidity;
char *weather_desc;
float wind_speed_kmh;
uint16_t wind_dir;
char *location;
} weather;
struct
{
bool find;
} find;
struct
{
bool heart_rate_monitor;
bool steps;
uint8_t heart_rate_interval;
} act;
struct
{
gadget_bridge_music_state_e music_state;
uint16_t position_in_seconds;
uint8_t shuffle;
uint8_t repeat;
} music_state;
struct
{
char *artist;
char *track;
uint16_t duration_in_seconds;
} music_info;
};
} gadget_bridge_event_data_t;
typedef void (*parser_event_callback_t)(const gadget_bridge_event_data_t *gadget_bridge_event_data);
/**
* @brief Sends an Android toast to GadgetBridge to be displayed on the phone.
*
* @param toast_type the type of the toast (INFO, WARN or ERROR).
* @param message a string representing the message to display.
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_toast(gadget_bridge_toast_type_e toast_type, const char *message);
/**
* @brief Sends up to two firmwares version to GadgetBridge.
* These are displayed in the display details section of the watch in GadgetBridge.
*
* @param fw1 a string representing the first firmware version.
* @param fw2 a string representing the second firmware version.
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_firmware_version(const char *fw1, const char *fw2);
/**
* @brief Sends the current battery status to GadgetBridge.
*
* @param battery_level_in_percent the current battery level from 0 to 100%.
* @param battery_level_in_V the current battery voltage in volts (3.942 for example).
* @param is_charging a boolean which indicates if the battery is currently charging or not.
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_battery_status(uint8_t battery_level_in_percent, float battery_level_in_V, bool is_charging);
/**
* @brief Sends the find phone command to GagdetBridge, this will make the phone ring and vibrate
* so that you can locate it.
*
* @param find_phone a boolean which indicates to make the phone rind and vibrate or not.
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_find_phone(bool find_phone);
/**
* @brief Sends a command to control the music playback of the phone through GadgetBridge.
*
* @param music_control an enumeration value indicating the action to perform:
* PLAY, PAUSE, NEXT, PREVIOUS, VOLUMEUP etc..
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_music_control(gadget_bridge_music_control_e music_control);
bool gadget_bridge_handle_call(gadget_bridge_call_action_e call_action);
bool gadget_bridge_handle_notification(gadget_bridge_call_action_e notification_action, uint32_t handle, const char *phone_number, const char *message);
/**
* @brief Sends the provided activity data to GadgetBridge. This will then be displayed
* on the app in the activity section.
*
* @param heart_rate_in_bpm the current heart rate in beat per minute
* @param step_count the number of new steps since the last time the count was sent.
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_activity_data(uint16_t heart_rate_in_bpm, uint32_t step_count);
/**
* @brief Tells GadgetBridge to perform an HTTP request for us.
* @note THIS DOES NOT WORK as GadgetBridge don't and will never have network permission... what a pitty !
*
* @param id an unsigned integer representing the ID of the http request
* @param url a string representing the URL to fetch
* @param http_request_method a enumeration value specifying the http verb to use : GET, POST, PATCH etc..
* @param http_body the body to include in the request (not implemented yet)
* @param http_headers various headers to include in the request (not implemented yet)
* @return true if the request has been successfully sent to GadgetBridge
* @return false otherwise
*/
bool gadget_bridge_send_http_request(uint32_t id, const char *url, gadget_bridge_http_request_method_e http_request_method, const char *http_body, const http_header_t *http_headers);
//bool gadget_bridge_send_force_calendar_sync(void);
/**
* @brief Registers a callback function used to listen for GadgetBridge events.
*
* @param parser_event_callback
*/
void gadget_bridge_parser_register_event_callback(parser_event_callback_t parser_event_callback);
/**
* @brief Feeds new data to the GadgetBridge parser.
*
* @param data the new chunk of data to parse, it will be copied to the parser's internal buffer,
* so you can free the memory containing the string after calling the function.
* @param length the length in bytes of the new chunk.
* @return gadget_bridge_parser_code_e GADGET_BRIDGE_PARSER_CODE_OK if no error occured.
*/
gadget_bridge_parser_code_e gadget_bridge_parser_feed(const char *data, uint16_t length);
/**
* @brief Call this function to run the parser.
* It should be safe to call if in a loop like : while((code = gadget_bridge_parser_run()) == GADGET_BRIDGE_PARSER_CODE_PARSING);
*
* @return gadget_bridge_parser_code_e the parser's execution status code.
*/
gadget_bridge_parser_code_e gadget_bridge_parser_run(void);
const char *gadget_bridge_parser_code_2_str(gadget_bridge_parser_code_e parser_code);
const char *gadget_bridge_event_type_2_str(gadget_bridge_event_type_e event_type);
const char *gadget_bridge_notification_type_2_str(gadget_bridge_notification_type_e notification_type);
const char *gadget_bridge_music_state_2_str(gadget_bridge_music_state_e music_state);
void gadget_bridge_parser_debug(void);
#endif //GADGET_BRIDGE_H

View File

@ -9,16 +9,13 @@
#include "menu_screen.h"
#include "compass_screen.h"
#include "settings_screen.h"
#include "i2c.h"
#include "QMC5883L.h"
#include "BMP280.h"
#include "bma456w.h"
#include "CST816D.h"
#include "watch_peripherals.h"
#include "watch_settings.h"
#include "ble_modem.h"
#include "ble_service.h"
#include "gadget_bridge.h"
static void date_time_cb(struct tm * const dateTime)
{
@ -34,16 +31,10 @@ MenuScreen_t menuScreen;
CompassScreen_t compassScreen;
SettingsScreen_t settingsScreen;
struct bma4_dev bma;
struct bma4_accel_config accel_conf;
struct bma456w_wrist_wear_wakeup_params setting;
struct bma4_int_pin_config pin_config;
static struct
{
uint16_t int_status;
bool battery_controller_status;
} _interrupts_statuses = {.int_status = 0, .battery_controller_status = false};
} _interrupts_statuses = {.battery_controller_status = false};
static struct
{
@ -60,10 +51,8 @@ static void battery_indicator_cb(uint8_t *levelInPercent, BatteryState_e *batter
static void step_count_cb(uint32_t *steps)
{
if(bma456w_step_counter_output(steps, &bma) != BMA4_OK)
if(!watch_peripherals_accelerometer_step_count_read(steps))
APP_LOG_DEBUG("Failed to read step counts");
else
watch_face_set_step_count_indicator(&watchFace, *steps);
}
static void battery_controller_status_on_change_cb(battery_controller_status_e old, battery_controller_status_e new)
@ -87,6 +76,18 @@ static void setGetBrightnessCb(uint8_t *brightness, SettingMode_e mode)
}
}
static void setAutomaticTimeCb(bool *enabled, SettingMode_e mode)
{
if(SETTING_MODE_GET == mode)
{
*enabled = persistency_get_settings()->timeAndDate.time_and_date_automatic;
}
else
{
watch_settings_time_and_date_set_automatic(*enabled);
}
}
static void setTimeCb(uint8_t *hour, uint8_t *minute, uint8_t *second, uint8_t *day, uint8_t *month, uint8_t *year, SettingMode_e mode)
{
struct tm timeToSet;
@ -190,6 +191,19 @@ static void setOrientationCb(uint8_t *orientation, SettingMode_e mode)
}
}
static void setWristTiltCb(bool *enabled, SettingMode_e mode)
{
if(SETTING_MODE_GET == mode)
{
*enabled = persistency_get_settings()->display.display_wrist_wakeup;
}
else
{
watch_peripherals_accelerometer_wrist_wakeup_enable(*enabled);
watch_settings_display_set_wrist_wakeup(*enabled);
}
}
static void setBLEEnabledCb(bool *enabled, SettingMode_e mode)
{
if(SETTING_MODE_GET == mode)
@ -277,6 +291,7 @@ static void performFactoryResetCb()
SettingsScreenAPIInterface_t settingsScreenAPIInterface =
{
.setAutomaticTimeSettingsCb = &(setAutomaticTimeCb),
.setTimeSettingsCb = &(setTimeCb),
.setTimeFormatSettingsCb = &(setTimeFormatCb),
.setBrightnessSettingsCb = &(setGetBrightnessCb),
@ -284,6 +299,7 @@ SettingsScreenAPIInterface_t settingsScreenAPIInterface =
.setDisplayVibrationDurationSettingsCb = &(setDisplayVibrationDuration),
.setDisplayVibrationStrengthSettingsCb = &(setDisplayVibrationStrength),
.setOrientationSettingsCb = &(setOrientationCb),
.setWristTiltSettingsCb = &(setWristTiltCb),
.setBLEEnabledSettingsCb = &(setBLEEnabledCb),
.setWiFiEnabledSettingsCb = &(setWiFiEnabledCb),
.setLanguageSettingsCb = &(setLanguageCb),
@ -298,39 +314,38 @@ static uint16_t angle_with_offset(uint16_t angle, uint16_t offset)
return (angle + offset) >= 360 ? angle + offset - 360 : angle + offset;
}
static BMA4_INTF_RET_TYPE bma4_i2c_read(uint8_t reg_addr, uint8_t *read_data, uint32_t len, void *intf_ptr)
static void parser_event_cb(const gadget_bridge_event_data_t *gadget_bridge_event_data)
{
uint8_t dev_address = *(uint8_t*)intf_ptr;
APP_LOG_INFO("[GB]Event of type : %s\n", gadget_bridge_event_type_2_str(gadget_bridge_event_data->event_type));
return !i2c_read(dev_address, reg_addr, read_data, len);
}
static BMA4_INTF_RET_TYPE bma4_i2c_write(uint8_t reg_addr, const uint8_t *read_data, uint32_t len, void *intf_ptr)
{
uint8_t dev_address = *(uint8_t*)intf_ptr;
return !i2c_write(dev_address, reg_addr, read_data, len);
}
static void delay_us(uint32_t period, void *intf_ptr)
{
(void) intf_ptr;
if(period < 1000)
tls_os_time_delay(1);
else
tls_os_time_delay(pdMS_TO_TICKS(period / 1000));
switch(gadget_bridge_event_data->event_type)
{
case GADGET_BRIDGE_EVENT_TYPE_SET_TIME:
if(persistency_get_settings()->timeAndDate.time_and_date_automatic)
{
// Only in this case we set the time
tls_set_rtc((struct tm *)&gadget_bridge_event_data->time.local_time);
// We force the sync of the watch face :)
watch_face_force_sync(&watchFace);
}
break;
default:
APP_LOG_INFO("Not yet handled\n");
}
}
static void ble_service_nus_data_rx_cb(const uint8_t *data, uint16_t length)
{
for (uint16_t i = 0; i < length; i++)
/*for (uint16_t i = 0; i < length; i++)
{
if (data[i] < 32)
printf("[%u]", data[i]);
else
printf("%c", data[i]);
}
}*/
gadget_bridge_parser_feed((const char *)data, length);
while(gadget_bridge_parser_run() == GADGET_BRIDGE_PARSER_CODE_PARSING);
}
static void ble_service_state_change_cb(ble_service_state_e ble_service_state)
@ -405,6 +420,14 @@ void gfx_task(void *param)
watch_peripherals_init(27);
watch_peripherals_register_battery_controller_status_change_cb(&(battery_controller_status_on_change_cb));
/* Let's init all the watch's sensors */
watch_peripherals_pressure_sensor_init();
watch_peripherals_magnetometer_init();
watch_peripherals_magnetometer_calibration_data_set(4812, 8550, -3200, 20, -2200, 3500, 0.0);
watch_peripherals_accelerometer_init();
watch_peripherals_accelerometer_wrist_wakeup_enable(persistency_get_settings()->display.display_wrist_wakeup);
watch_peripherals_accelerometer_step_counter_enable(true);
/* Make the first battery voltage reading here */
_battery_stats.battery_voltage = watch_peripherals_get_battery_voltage(battery_unit_mv);
_battery_stats.battery_percentage = battery_voltage_to_percentage(_battery_stats.battery_voltage);
@ -440,114 +463,10 @@ void gfx_task(void *param)
watch_face_create(&watchFace);
lv_scr_load(watchFace.display);
/* Let's init the I2C interface */
i2c_init(I2C_SDA, I2C_SCL, I2C_CLOCK_SPEED);
/* Init the magnetometer */
if(!QMC5883L_init())
APP_LOG_INFO("Failed to init QMC5883L");
else
APP_LOG_INFO("Inited QMC5883L");
tls_os_time_delay(2);
if(!QMC5883L_set_power_mode(Continuous))
APP_LOG_INFO("Failed to set QMC5883L mode");
else
APP_LOG_INFO("QMC5883L Mode set");
tls_os_time_delay(2);
if(!QMC5883L_configure_1(ODR_10HZ, FS_2G, OSR_512))
APP_LOG_INFO("Failed to configure 1 QMC5883L");
else
APP_LOG_INFO("QMC5883L configured");
//QMC5883L_set_calibration_data(-900, 2500, -1400, 1400, 2300, 7500, 0.0);
QMC5883L_set_calibration_data(4812, 8550, -3200, 20, -2200, 3500, 0.0);
/* Init the BMP280 */
if(!BMP280_init())
APP_LOG_INFO("Failed to init BMP280");
else
APP_LOG_INFO("Inited BMP280");
if(!BMP280_configure(BMP280_Forced, BMP280_Oversampling_x16, BMP280_Oversampling_x16, BMP280_Filter_x16, BMP280_Standby_4000MS))
APP_LOG_INFO("Failed to configure BMP280");
else
APP_LOG_INFO("BMP280 configured");
/* Init the BMA456 */
bma.intf = BMA4_I2C_INTF;
uint8_t dev_addr = BMA4_I2C_ADDR_SECONDARY;
bma.intf_ptr = &dev_addr;
bma.bus_read = &(bma4_i2c_read);
bma.bus_write = &(bma4_i2c_write);
bma.variant = BMA45X_VARIANT;
bma.delay_us = &(delay_us);
bma.read_write_len = 46;
bma.perf_mode_status = BMA4_DISABLE;
if(bma456w_init(&bma) == BMA4_OK)
APP_LOG_INFO("BMA456 init");
else
APP_LOG_INFO("Failed to init BMA456");
bma4_soft_reset(&bma);
tls_os_time_delay(2);
if(bma456w_write_config_file(&bma) == BMA4_OK)
APP_LOG_INFO("BMA456 config ok");
else
APP_LOG_INFO("BMA456 config failed");
accel_conf.odr = BMA4_OUTPUT_DATA_RATE_100HZ;
accel_conf.range = BMA4_ACCEL_RANGE_2G;
accel_conf.bandwidth = BMA4_ACCEL_NORMAL_AVG4;
accel_conf.perf_mode = BMA4_CIC_AVG_MODE;
if(bma4_set_accel_config(&accel_conf, &bma) == BMA4_OK)
APP_LOG_INFO("BMA456 accel conf ok");
else
APP_LOG_INFO("BMA456 accel conf failed");
if(bma4_set_accel_enable(1, &bma) == BMA4_OK)
APP_LOG_INFO("BMA456 accel en ok");
else
APP_LOG_INFO("BMA456 accel en failed");
bma456w_feature_enable(BMA456W_WRIST_WEAR_WAKEUP, BMA4_ENABLE, &bma);
bma456w_get_wrist_wear_wakeup_param_config(&setting, &bma);
APP_LOG_DEBUG("%d %d %d %d %d %d %d %d", setting.min_angle_focus, setting.min_angle_non_focus, setting.angle_landscape_right, setting.angle_landscape_left, setting.angle_portrait_up, setting.angle_portrait_down, setting.min_dur_moved, setting.min_dur_quite);
if(bma4_get_int_pin_config(&pin_config, BMA4_INTR1_MAP, &bma) == BMA4_OK)
APP_LOG_INFO("BMA456 get pin conf ok");
else
APP_LOG_INFO("BMA456 get pin conf failed");
if(bma456w_map_interrupt(BMA4_INTR1_MAP, BMA456W_WRIST_WEAR_WAKEUP_INT, BMA4_ENABLE, &bma) == BMA4_OK)
APP_LOG_INFO("BMA456 map int ok");
else
APP_LOG_INFO("BMA456 map int failed");
pin_config.edge_ctrl = BMA4_EDGE_TRIGGER;
pin_config.output_en = BMA4_OUTPUT_ENABLE;
pin_config.lvl = BMA4_ACTIVE_LOW;
pin_config.od = BMA4_PUSH_PULL;
pin_config.input_en = BMA4_INPUT_DISABLE;
if(bma4_set_int_pin_config(&pin_config, BMA4_INTR1_MAP, &bma) == BMA4_OK)
APP_LOG_INFO("BMA456 set pin conf ok");
else
APP_LOG_INFO("BMA456 set pin conf failed");
/* Configure BMA's step counter */
if(bma456w_feature_enable(BMA456W_STEP_CNTR, BMA4_ENABLE, &bma) == BMA4_OK)
APP_LOG_INFO("BMA456 step cnter feature enable ok");
else
APP_LOG_INFO("BMA456 step cnter feature enable failed");
gadget_bridge_parser_register_event_callback(&(parser_event_cb));
/* Configure and register BLE stack and services callbacks */
ble_service_register_nus_data_rx_cb(&(ble_service_nus_data_rx_cb));
ble_service_register_state_change_cb(&(ble_service_state_change_cb));
@ -570,34 +489,31 @@ void gfx_task(void *param)
if(compass_screen_is_in_use(&compassScreen))
{
if(QMC5883L_is_data_available())
bool is_data_available = false;
uint16_t azimuth = watch_peripherals_magnetometer_azimuth_read(&is_data_available);
if(is_data_available)
{
/*
QMC5883L_MData_t MDataRaw = QMC5883L_get_MFields_raw();
QMC5883L_MData_t MDataRaw = watch_peripherals_magnetometer_raw_data_read();
APP_LOG_TRACE("X %d Y %d Z %d", MDataRaw.MFieldX, MDataRaw.MFieldY, MDataRaw.MFieldZ);
*/
QMC5883L_MData_calibrated_t MData = QMC5883L_get_MFields_calibrated();
compass_screen_set_azimuth(&compassScreen, angle_with_offset(QMC5883L_get_azimuth(MData), 180));
compass_screen_set_azimuth(&compassScreen, angle_with_offset(azimuth, 180));
}
compass_screen_set_temperature(&compassScreen, temperature);
}
uint8_t rslt = bma456w_read_int_status(&_interrupts_statuses.int_status, &bma);
if(rslt != BMA4_OK)
APP_LOG_DEBUG("Failed to read int status");
if((BMA4_OK == rslt) && (_interrupts_statuses.int_status & BMA456W_WRIST_WEAR_WAKEUP_INT))
if(watch_peripherals_accelerometer_wrist_wakeup_interrupt())
{
APP_LOG_DEBUG("Wrist tilt");
}
if(lv_tick_elaps(update_tick) > 5000)
{
pressure = BMP280_get_pressure(&temperature);
BMP280_trigger_measurement();
pressure = watch_peripherals_pressure_sensor_get_pressure(&temperature);
_battery_stats.battery_voltage = watch_peripherals_get_battery_voltage(battery_unit_mv);
_battery_stats.battery_percentage = battery_voltage_to_percentage(_battery_stats.battery_voltage);
APP_LOG_DEBUG("GFX thread, temp : %0.2f °C, press : %0.2f hPa, battery(%s) : %u mV <-> %u %%",
@ -619,7 +535,7 @@ void gfx_task(void *param)
watch_peripherals_set_brightness(0);
//lcd_on(&LCDConfig, false);
lcd_sleep(&LCDConfig, true);
QMC5883L_set_power_mode(Standby);
watch_peripherals_magnetometer_power_mode_set(QMC5883L_Mode_Control_Standby);
if(CST816D_sleep())
APP_LOG_DEBUG("CST816D Sleep cmd ok");
else
@ -630,7 +546,7 @@ void gfx_task(void *param)
tls_os_time_delay(1);
watch_face_force_sync(&watchFace);
lv_disp_trig_activity(NULL);
QMC5883L_set_power_mode(Continuous);
watch_peripherals_magnetometer_power_mode_set(QMC5883L_Mode_Control_Continuous);
//lcd_on(&LCDConfig, true);
lcd_sleep(&LCDConfig, false);
//watch_peripherals_set_brightness(persistency_get_settings()->display.display_brightness);

View File

@ -26,6 +26,8 @@ static void update_menu_list_item_text(lv_obj_t *menu_list_item, const char *tex
static void _simulate_side_screen_item_click(SettingsScreen_t * const settingsScreen, lv_obj_t *item);
static void _set_rtc_time_to_label(SettingsScreen_t * const settingsScreen);
static void _set_battery_voltage_to_label(SettingsScreen_t * const settingsScreen);
static void _reset_switch_pointers(SettingsScreen_t * const settingsScreen);
static void _enable_time_and_date_rollers(bool enabled, SettingsScreen_t * const settingsScreen);
static void _settings_screen_update_labels_language(SettingsScreen_t * const settingsScreen)
{
@ -220,6 +222,11 @@ static void activation_switch_cb(lv_event_t *e)
{
if(settingsScreen->settingsScreenAPIInterface.setWristTiltSettingsCb)settingsScreen->settingsScreenAPIInterface.setWristTiltSettingsCb(&toggled, SETTING_MODE_SET);
}
else if(e->target == settingsScreen->auto_set_time_switch)
{
if(settingsScreen->settingsScreenAPIInterface.setAutomaticTimeSettingsCb)settingsScreen->settingsScreenAPIInterface.setAutomaticTimeSettingsCb(&toggled, SETTING_MODE_SET);
_enable_time_and_date_rollers(!toggled, settingsScreen);
}
}
static void language_dropdown_cb(lv_event_t *e)
@ -254,6 +261,7 @@ static void about_refresh_timer_cb(lv_timer_t *timer)
static void load_time_and_date_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
uint8_t hour = 0, minute = 0, second = 0, day = 0, month = 0, year = 0;
if(settingsScreen->settingsScreenAPIInterface.setTimeSettingsCb)
@ -262,16 +270,23 @@ static void load_time_and_date_side_screen(SettingsScreen_t *settingsScreen)
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Set Time & Date :");
lv_obj_t *toggle = lv_switch_create(settingsScreen->side_screen);
lv_obj_align_to(toggle, label, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 10);
label = lv_label_create(settingsScreen->side_screen);
settingsScreen->auto_set_time_switch = lv_switch_create(settingsScreen->side_screen);
lv_obj_align_to(settingsScreen->auto_set_time_switch, label, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 10);
bool auto_set_enable = false;
if(settingsScreen->settingsScreenAPIInterface.setAutomaticTimeSettingsCb)settingsScreen->settingsScreenAPIInterface.setAutomaticTimeSettingsCb(&auto_set_enable, SETTING_MODE_GET);
if(auto_set_enable)
{
lv_obj_add_state(settingsScreen->auto_set_time_switch, LV_STATE_CHECKED);
}
lv_obj_add_event_cb(settingsScreen->auto_set_time_switch, &(activation_switch_cb), LV_EVENT_VALUE_CHANGED, settingsScreen);
label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Automatic");
lv_obj_align_to(label, toggle, LV_ALIGN_OUT_RIGHT_MID, 10, 0);
lv_obj_align_to(label, settingsScreen->auto_set_time_switch, LV_ALIGN_OUT_RIGHT_MID, 10, 0);
label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Time :");
lv_obj_align_to(label, toggle, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 10);
lv_obj_align_to(label, settingsScreen->auto_set_time_switch, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 10);
settingsScreen->hour_roller = lv_roller_create(settingsScreen->side_screen);
settingsScreen->minute_roller = lv_roller_create(settingsScreen->side_screen);
@ -349,6 +364,8 @@ static void load_time_and_date_side_screen(SettingsScreen_t *settingsScreen)
lv_roller_set_visible_row_count(settingsScreen->year_roller, 2);
lv_roller_set_selected(settingsScreen->year_roller, year-22, LV_ANIM_OFF);
lv_obj_add_event_cb(settingsScreen->year_roller, &(time_roller_cb), LV_EVENT_RELEASED, settingsScreen);
// We set the state of the rollers only here, because they are not created yet earlier.
_enable_time_and_date_rollers(!auto_set_enable, settingsScreen);
label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Date Format :");
@ -362,6 +379,7 @@ static void load_time_and_date_side_screen(SettingsScreen_t *settingsScreen)
static void load_display_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Brightness :");
@ -451,6 +469,7 @@ static void load_display_side_screen(SettingsScreen_t *settingsScreen)
static void load_notifications_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Vibrate on\nnotifications :");
@ -479,6 +498,7 @@ static void load_notifications_side_screen(SettingsScreen_t *settingsScreen)
static void load_connectivity_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Connectivity :");
@ -520,6 +540,7 @@ static void load_connectivity_side_screen(SettingsScreen_t *settingsScreen)
static void load_language_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Language :");
@ -536,6 +557,7 @@ static void load_language_side_screen(SettingsScreen_t *settingsScreen)
static void load_about_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "System Info :");
@ -765,6 +787,50 @@ static void _set_battery_voltage_to_label(SettingsScreen_t * const settingsScree
lv_label_set_text_static(settingsScreen->batteryVoltage.batteryVoltageLabel, settingsScreen->batteryVoltage.batteryVoltageText);
}
static void _reset_switch_pointers(SettingsScreen_t * const settingsScreen)
{
settingsScreen->auto_set_time_switch = NULL;
settingsScreen->wrist_tilt_switch = NULL;
settingsScreen->ble_switch = NULL;
settingsScreen->wifi_switch = NULL;
}
static void _enable_time_and_date_rollers(bool enabled, SettingsScreen_t * const settingsScreen)
{
if(enabled)
{
lv_obj_clear_state(settingsScreen->hour_roller, LV_STATE_DISABLED);
lv_obj_clear_state(settingsScreen->minute_roller, LV_STATE_DISABLED);
lv_obj_clear_state(settingsScreen->second_roller, LV_STATE_DISABLED);
lv_obj_clear_state(settingsScreen->day_roller, LV_STATE_DISABLED);
lv_obj_clear_state(settingsScreen->month_roller, LV_STATE_DISABLED);
lv_obj_clear_state(settingsScreen->year_roller, LV_STATE_DISABLED);
lv_obj_set_style_bg_color(settingsScreen->hour_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->minute_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->second_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->day_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->month_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->year_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
}
else
{
lv_obj_add_state(settingsScreen->hour_roller, LV_STATE_DISABLED);
lv_obj_add_state(settingsScreen->minute_roller, LV_STATE_DISABLED);
lv_obj_add_state(settingsScreen->second_roller, LV_STATE_DISABLED);
lv_obj_add_state(settingsScreen->day_roller, LV_STATE_DISABLED);
lv_obj_add_state(settingsScreen->month_roller, LV_STATE_DISABLED);
lv_obj_add_state(settingsScreen->year_roller, LV_STATE_DISABLED);
lv_obj_set_style_bg_color(settingsScreen->hour_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->minute_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->second_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->day_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->month_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->year_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
}
}
static lv_obj_t *add_menu_list_item(lv_obj_t *list, const char *text, lv_event_cb_t event_cb, void *user_data)
{
lv_obj_t *btn = lv_list_add_btn(list, NULL, text);

View File

@ -11,6 +11,7 @@ typedef enum SettingMode
typedef struct SettingsScreenAPIInterface
{
void (*setAutomaticTimeSettingsCb)(bool *enabled, SettingMode_e mode);
void (*setTimeSettingsCb)(uint8_t *hour, uint8_t *minute, uint8_t *second, uint8_t *day, uint8_t *month, uint8_t *year, SettingMode_e mode);
void (*setTimeFormatSettingsCb)(bool *hour_24H_format, SettingMode_e mode);
void (*setBrightnessSettingsCb)(uint8_t *brightness, SettingMode_e mode);
@ -42,6 +43,7 @@ typedef struct SettingsScreen
lv_obj_t *side_screen;
/* Menu widgets */
lv_obj_t *auto_set_time_switch;
lv_obj_t *hour_roller;
lv_obj_t *minute_roller;
lv_obj_t *second_roller;

View File

@ -25,6 +25,9 @@ static const WatchSettings_t defaultWatchSettings =
.display_vibrate_on_touch_strength = 6,
.display_wrist_wakeup = true,
},
.activity = {
.activity_step_counter_en = true,
},
.notification = {
.notification_vibration_duration = 3,
.notification_vibration_strength = 6,

View File

@ -36,6 +36,15 @@ typedef struct Display
display_vibrate_on_touch_duration:3;
} Display_t;
/**
* @brief Activity settings
*
*/
typedef struct Activity
{
uint32_t activity_step_counter_en:1;
} Activity_t;
/**
* @brief Notification Settings
*
@ -81,6 +90,7 @@ typedef struct WatchSettings
Notification_t notification;
Connectivity_t connectivity;
LanguageAndUI_t languageAndUI;
Activity_t activity;
} WatchSettings_t;
/**

View File

@ -18,14 +18,32 @@
#include <time.h>
/**
* @brief Size of the internal buffer used to store incoming data
* which needs to be parsed.
* @brief GADGET_BRIDGE_PARSER_BUFFER_SIZE allows to set the size of the buffer
* which is internally used by the parser to do it's job.
*
*/
#define GADGET_BRIDGE_PARSER_BUFFER_SIZE (300)
/**
* @brief GADGET_BRIDGE_PARSER_BUFFER_THRESHOLD permits to set a size threshold used to free up
* some space in the parser's internal buffer when the threshold is reached.
* This ensures that we can keep on feeding new data and not get stuck.
*
*/
#define GADGET_BRIDGE_PARSER_BUFFER_THRESHOLD (100)
/**
* @brief GADGET_BRIDGE_PARSER_MAX_BODY_SIZE defines the max body size that will be saved in the event_data
* structure when parsing the body of a notification.
*
*/
#define GADGET_BRIDGE_PARSER_MAX_BODY_SIZE (200)
/**
* @brief GADGET_BRIDGE_PARSER_MAX_TITLE_SIZE defines the max title size that will be saved in the event_data
* structure when parsing the title of a notification.
*
*/
#define GADGET_BRIDGE_PARSER_MAX_TITLE_SIZE (100)
typedef enum gadget_bridge_toast_type
@ -183,28 +201,112 @@ typedef struct gadget_bridge_event_data
typedef void (*parser_event_callback_t)(const gadget_bridge_event_data_t *gadget_bridge_event_data);
/**
* @brief Sends an Android toast to GadgetBridge to be displayed on the phone.
*
* @param toast_type the type of the toast (INFO, WARN or ERROR).
* @param message a string representing the message to display.
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_toast(gadget_bridge_toast_type_e toast_type, const char *message);
/**
* @brief Sends up to two firmwares version to GadgetBridge.
* These are displayed in the display details section of the watch in GadgetBridge.
*
* @param fw1 a string representing the first firmware version.
* @param fw2 a string representing the second firmware version.
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_firmware_version(const char *fw1, const char *fw2);
/**
* @brief Sends the current battery status to GadgetBridge.
*
* @param battery_level_in_percent the current battery level from 0 to 100%.
* @param battery_level_in_V the current battery voltage in volts (3.942 for example).
* @param is_charging a boolean which indicates if the battery is currently charging or not.
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_battery_status(uint8_t battery_level_in_percent, float battery_level_in_V, bool is_charging);
/**
* @brief Sends the find phone command to GagdetBridge, this will make the phone ring and vibrate
* so that you can locate it.
*
* @param find_phone a boolean which indicates to make the phone rind and vibrate or not.
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_find_phone(bool find_phone);
/**
* @brief Sends a command to control the music playback of the phone through GadgetBridge.
*
* @param music_control an enumeration value indicating the action to perform:
* PLAY, PAUSE, NEXT, PREVIOUS, VOLUMEUP etc..
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_music_control(gadget_bridge_music_control_e music_control);
bool gadget_bridge_handle_call(gadget_bridge_call_action_e call_action);
bool gadget_bridge_handle_notification(gadget_bridge_call_action_e notification_action, uint32_t handle, const char *phone_number, const char *message);
/**
* @brief Sends the provided activity data to GadgetBridge. This will then be displayed
* on the app in the activity section.
*
* @param heart_rate_in_bpm the current heart rate in beat per minute
* @param step_count the number of new steps since the last time the count was sent.
* @return true if the command was successfully sent.
* @return false otherwise.
*/
bool gadget_bridge_send_activity_data(uint16_t heart_rate_in_bpm, uint32_t step_count);
/**
* @brief Tells GadgetBridge to perform an HTTP request for us.
* @note THIS DOES NOT WORK as GadgetBridge don't and will never have network permission... what a pitty !
*
* @param id an unsigned integer representing the ID of the http request
* @param url a string representing the URL to fetch
* @param http_request_method a enumeration value specifying the http verb to use : GET, POST, PATCH etc..
* @param http_body the body to include in the request (not implemented yet)
* @param http_headers various headers to include in the request (not implemented yet)
* @return true if the request has been successfully sent to GadgetBridge
* @return false otherwise
*/
bool gadget_bridge_send_http_request(uint32_t id, const char *url, gadget_bridge_http_request_method_e http_request_method, const char *http_body, const http_header_t *http_headers);
//bool gadget_bridge_send_force_calendar_sync(void);
/**
* @brief Registers a callback function used to listen for GadgetBridge events.
*
* @param parser_event_callback
*/
void gadget_bridge_parser_register_event_callback(parser_event_callback_t parser_event_callback);
/**
* @brief Feeds new data to the GadgetBridge parser.
*
* @param data the new chunk of data to parse, it will be copied to the parser's internal buffer,
* so you can free the memory containing the string after calling the function.
* @param length the length in bytes of the new chunk.
* @return gadget_bridge_parser_code_e GADGET_BRIDGE_PARSER_CODE_OK if no error occured.
*/
gadget_bridge_parser_code_e gadget_bridge_parser_feed(const char *data, uint16_t length);
/**
* @brief Call this function to run the parser.
* It should be safe to call if in a loop like : while((code = gadget_bridge_parser_run()) == GADGET_BRIDGE_PARSER_CODE_PARSING);
*
* @return gadget_bridge_parser_code_e the parser's execution status code.
*/
gadget_bridge_parser_code_e gadget_bridge_parser_run(void);
const char *gadget_bridge_parser_code_2_str(gadget_bridge_parser_code_e parser_code);

View File

@ -2,159 +2,19 @@
<CodeBlocks_layout_file>
<FileVersion major="1" minor="0" />
<ActiveTarget name="Debug" />
<File name="lvgl\src\core\lv_obj_style_gen.h" open="0" top="0" tabpos="11" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\widgets\menu\lv_menu.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="29532" topLine="612" />
</Cursor>
</File>
<File name="lvgl\src\font\lv_symbol_def.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1135" topLine="14" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_disp.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="7126" topLine="230" />
</Cursor>
</File>
<File name="lv_drivers\win_drv.h" open="0" top="0" tabpos="10" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="585" topLine="0" />
</Cursor>
</File>
<File name="lvgl\src\widgets\spinbox\lv_spinbox.h" open="0" top="0" tabpos="18" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="4262" topLine="120" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_pos.c" open="0" top="0" tabpos="12" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="10562" topLine="336" />
</Cursor>
</File>
<File name="compass_assets.c" open="0" top="0" tabpos="13" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="143" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_style.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="9059" topLine="238" />
</Cursor>
</File>
<File name="lvgl\src\widgets\list\lv_list.h" open="0" top="0" tabpos="7" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="721" topLine="16" />
</Cursor>
</File>
<File name="menu_screen.c" open="1" top="0" tabpos="5" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="3627" topLine="67" />
</Cursor>
</File>
<File name="lvgl\lvgl.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="138" />
</Cursor>
</File>
<File name="lvgl\demos\widgets\assets\img_demo_widgets_avatar.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1282774" topLine="472" />
</Cursor>
</File>
<File name="lvgl\src\widgets\label\lv_label.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1299" topLine="36" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_disp.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="615" topLine="25" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_types.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1969" topLine="47" />
</Cursor>
</File>
<File name="firmware_version.h" open="1" top="0" tabpos="9" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="160" topLine="0" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_indev_scroll.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="14405" topLine="323" />
</Cursor>
</File>
<File name="altimeter_screen.h" open="0" top="0" tabpos="7" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1028" topLine="30" />
</Cursor>
</File>
<File name="lvgl\examples\widgets\menu\lv_example_menu_5.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="7631" topLine="141" />
</Cursor>
</File>
<File name="lvgl\src\widgets\roller\lv_roller.h" open="0" top="0" tabpos="6" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="715" topLine="26" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="7842" topLine="283" />
</Cursor>
</File>
<File name="lvgl\examples\widgets\bar\lv_example_bar_6.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="181" topLine="0" />
</Cursor>
</File>
<File name="lvgl\src\draw\lv_draw_img.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="5230" topLine="191" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_timer.h" open="1" top="0" tabpos="10" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="635" topLine="36" />
<Cursor1 position="3321" topLine="109" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_event.h" open="0" top="0" tabpos="19" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="5517" topLine="93" />
<Cursor1 position="4009" topLine="56" />
</Cursor>
</File>
<File name="lvgl\src\widgets\imgbtn\lv_imgbtn.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\misc\lv_color.h" open="0" top="0" tabpos="5" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="2184" topLine="61" />
</Cursor>
</File>
<File name="lvgl\src\layouts\flex\lv_flex.c" open="0" top="0" tabpos="8" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="3097" topLine="74" />
</Cursor>
</File>
<File name="lvgl\src\widgets\imgbtn\lv_imgbtn.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="2129" topLine="53" />
</Cursor>
</File>
<File name="compass_screen.h" open="0" top="0" tabpos="5" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1253" topLine="18" />
</Cursor>
</File>
<File name="watch_face.c" open="1" top="0" tabpos="1" split="0" active="1" splitpos="702" zoom_1="-1" zoom_2="-1">
<Cursor>
<Cursor1 position="649" topLine="389" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_indev.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="3034" topLine="107" />
<Cursor1 position="23661" topLine="673" />
</Cursor>
</File>
<File name="lvgl\demos\widgets\lv_demo_widgets.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
@ -162,44 +22,38 @@
<Cursor1 position="456" topLine="6" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_tree.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\core\lv_disp.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1234" topLine="139" />
<Cursor1 position="615" topLine="25" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_color.c" open="0" top="0" tabpos="6" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\widgets\tileview\lv_tileview.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="10782" topLine="316" />
<Cursor1 position="1055" topLine="40" />
</Cursor>
<Folding>
<Collapse line="8" />
<Collapse line="995" />
</Folding>
</File>
<File name="lvgl\src\draw\lv_img_buf.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="6210" topLine="113" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_timer.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\libs\ffmpeg\lv_ffmpeg.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="5053" topLine="144" />
<Cursor1 position="5784" topLine="170" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_tree.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\core\lv_obj_pos.c" open="0" top="0" tabpos="12" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="2082" topLine="62" />
<Cursor1 position="10562" topLine="336" />
</Cursor>
</File>
<File name="lv_drivers\indev\keyboard.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="menu_screen.c" open="0" top="0" tabpos="5" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="440" topLine="14" />
</Cursor>
</File>
<File name="lvgl\src\widgets\menu\lv_menu.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="3321" topLine="109" />
</Cursor>
</File>
<File name="lv_drv_conf.h" open="0" top="0" tabpos="3" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="6602" topLine="208" />
</Cursor>
</File>
<File name="common_screen_components.c" open="1" top="0" tabpos="8" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="498" topLine="0" />
<Cursor1 position="3627" topLine="67" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_anim.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
@ -207,27 +61,52 @@
<Cursor1 position="3835" topLine="68" />
</Cursor>
</File>
<File name="settings_screen.h" open="1" top="0" tabpos="3" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\demos\widgets\assets\img_demo_widgets_avatar.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="527" topLine="0" />
<Cursor1 position="1282774" topLine="472" />
</Cursor>
</File>
<File name="lvgl\src\widgets\img\lv_img.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\widgets\list\lv_list.h" open="0" top="0" tabpos="7" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1863" topLine="59" />
<Cursor1 position="721" topLine="16" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_refr.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\hal\lv_hal_indev.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="2447" topLine="75" />
<Cursor1 position="5065" topLine="123" />
</Cursor>
</File>
<File name="lvgl\src\font\lv_font.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\misc\lv_area.h" open="0" top="0" tabpos="15" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="5535" topLine="120" />
<Cursor1 position="1789" topLine="74" />
</Cursor>
</File>
<File name="watch_casio_assets.c" open="1" top="0" tabpos="2" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="watch_face.h" open="0" top="0" tabpos="4" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="713" topLine="33" />
</Cursor>
</File>
<File name="compass_assets.c" open="0" top="0" tabpos="13" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="143" />
</Cursor>
</File>
<File name="lvgl\lvgl.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="138" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="7842" topLine="283" />
</Cursor>
</File>
<File name="lvgl\src\widgets\spinbox\lv_spinbox.h" open="0" top="0" tabpos="18" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="4262" topLine="120" />
</Cursor>
</File>
<File name="watch_casio_assets.c" open="0" top="0" tabpos="2" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="3791697" topLine="77" />
</Cursor>
@ -244,109 +123,54 @@
<Collapse line="3403" />
</Folding>
</File>
<File name="lv_conf.h" open="0" top="0" tabpos="5" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="12839" topLine="10" />
</Cursor>
</File>
<File name="lvgl\src\layouts\flex\lv_flex.h" open="0" top="0" tabpos="7" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="950" topLine="43" />
</Cursor>
</File>
<File name="lv_drivers\win32drv\win32drv.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="15" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_types.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1969" topLine="47" />
</Cursor>
</File>
<File name="lvgl\src\widgets\label\lv_label.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1299" topLine="36" />
</Cursor>
</File>
<File name="lvgl\src\font\lv_symbol_def.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1135" topLine="14" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_scroll.h" open="0" top="0" tabpos="16" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1988" topLine="67" />
</Cursor>
</File>
<File name="lvgl\demos\widgets\lv_demo_widgets.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\core\lv_obj_style_gen.h" open="0" top="0" tabpos="11" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="2825" topLine="122" />
<Cursor1 position="29532" topLine="612" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj.h" open="0" top="0" tabpos="10" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\src\layouts\flex\lv_flex.c" open="0" top="0" tabpos="8" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="8074" topLine="159" />
<Cursor1 position="3097" topLine="74" />
</Cursor>
</File>
<File name="compass_screen.c" open="0" top="0" tabpos="11" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<File name="lvgl\examples\widgets\bar\lv_example_bar_6.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="6172" topLine="154" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_area.h" open="0" top="0" tabpos="15" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1789" topLine="74" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_style.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="7273" topLine="217" />
</Cursor>
</File>
<File name="lv_drivers\display\SSD1963.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1563" topLine="27" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_class.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1857" topLine="35" />
</Cursor>
</File>
<File name="lvgl\src\hal\lv_hal_disp.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="11123" topLine="327" />
</Cursor>
</File>
<File name="menu_screen.h" open="0" top="0" tabpos="2" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="48" topLine="0" />
</Cursor>
</File>
<File name="lv_drivers\win32drv\win32drv.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="524" topLine="954" />
</Cursor>
</File>
<File name="lvgl\src\hal\lv_hal_indev.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="5065" topLine="123" />
</Cursor>
</File>
<File name="lvgl\src\libs\ffmpeg\lv_ffmpeg.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="5784" topLine="170" />
</Cursor>
</File>
<File name="lv_drivers\display\monitor.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="289" topLine="31" />
</Cursor>
</File>
<File name="altimeter_screen.c" open="0" top="0" tabpos="6" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="13638" topLine="409" />
</Cursor>
</File>
<File name="lvgl\src\lv_api_map.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="722" topLine="32" />
</Cursor>
</File>
<File name="lvgl\src\draw\lv_img_buf.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="6210" topLine="113" />
</Cursor>
</File>
<File name="common_screen_components.h" open="1" top="1" tabpos="7" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="215" topLine="0" />
</Cursor>
</File>
<File name="lvgl\src\font\lv_font_montserrat_30.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="869" topLine="0" />
</Cursor>
</File>
<File name="main.c" open="0" top="0" tabpos="1" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1457" topLine="45" />
</Cursor>
</File>
<File name="lvgl\src\widgets\menu\lv_menu.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="3706" topLine="117" />
<Cursor1 position="181" topLine="0" />
</Cursor>
</File>
<File name="lv_drivers\lv_drv_conf_template.h" open="0" top="0" tabpos="11" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
@ -354,9 +178,109 @@
<Cursor1 position="10670" topLine="390" />
</Cursor>
</File>
<File name="settings_screen.c" open="1" top="0" tabpos="4" split="0" active="1" splitpos="513" zoom_1="0" zoom_2="0">
<File name="lvgl\src\widgets\label\lv_label.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="4139" topLine="82" />
<Cursor1 position="5648" topLine="194" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_disp.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="7126" topLine="230" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_indev.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="3034" topLine="107" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_refr.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="2447" topLine="75" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_timer.h" open="0" top="0" tabpos="10" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="635" topLine="36" />
</Cursor>
</File>
<File name="common_screen_components.c" open="0" top="0" tabpos="8" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="498" topLine="0" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_log.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1509" topLine="59" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_tree.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1234" topLine="139" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_timer.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="5053" topLine="144" />
</Cursor>
</File>
<File name="lvgl\src\widgets\menu\lv_menu.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="3706" topLine="117" />
</Cursor>
</File>
<File name="compass_screen.h" open="0" top="0" tabpos="5" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1253" topLine="18" />
</Cursor>
</File>
<File name="lvgl\src\hal\lv_hal_disp.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="823" topLine="24" />
</Cursor>
</File>
<File name="lvgl\src\font\lv_font_montserrat_30.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="869" topLine="0" />
</Cursor>
</File>
<File name="lvgl\src\draw\lv_draw_rect.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="539" topLine="9" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_style.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="9059" topLine="238" />
</Cursor>
</File>
<File name="altimeter_screen.c" open="0" top="0" tabpos="6" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="13638" topLine="409" />
</Cursor>
</File>
<File name="common_screen_components.h" open="0" top="0" tabpos="7" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="682" topLine="0" />
</Cursor>
</File>
<File name="lvgl\demos\widgets\lv_demo_widgets.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="2825" topLine="122" />
</Cursor>
</File>
<File name="menu_screen.h" open="0" top="0" tabpos="2" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="48" topLine="0" />
</Cursor>
</File>
<File name="watch_face.c" open="0" top="0" tabpos="1" split="0" active="1" splitpos="702" zoom_1="-1" zoom_2="-1">
<Cursor>
<Cursor1 position="649" topLine="389" />
</Cursor>
</File>
<File name="lv_drivers\display\SSD1963.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1563" topLine="27" />
</Cursor>
</File>
<File name="lvgl\src\hal\lv_hal_indev.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
@ -369,110 +293,16 @@
<Cursor1 position="2557" topLine="68" />
</Cursor>
</File>
<File name="lvgl\src\widgets\label\lv_label.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="5648" topLine="194" />
</Cursor>
</File>
<File name="lvgl\src\layouts\flex\lv_flex.h" open="0" top="0" tabpos="7" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="950" topLine="43" />
</Cursor>
</File>
<File name="lvgl\src\font\lv_font_montserrat_12.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="22" />
</Cursor>
</File>
<File name="lvgl\src\font\lv_font_fmt_txt.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="24" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_log.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1509" topLine="59" />
</Cursor>
</File>
<File name="lv_drivers\win32drv\win32drv.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="15" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_class.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="3011" topLine="100" />
</Cursor>
</File>
<File name="lv_conf.h" open="0" top="0" tabpos="5" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="12839" topLine="10" />
</Cursor>
</File>
<File name="lvgl\src\widgets\chart\lv_chart.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="11658" topLine="336" />
</Cursor>
</File>
<File name="lvgl\src\hal\lv_hal_disp.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="823" topLine="24" />
</Cursor>
</File>
<File name="lvgl\src\widgets\img\lv_img.h" open="0" top="0" tabpos="3" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="4439" topLine="123" />
<Cursor1 position="6960" topLine="190" />
</Cursor>
</File>
<File name="lvgl\src\widgets\tileview\lv_tileview.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1055" topLine="40" />
</Cursor>
<Folding>
<Collapse line="8" />
<Collapse line="995" />
</Folding>
</File>
<File name="lvgl\src\core\lv_obj_style_gen.c" open="0" top="0" tabpos="7" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="19855" topLine="604" />
</Cursor>
</File>
<File name="watch_face.h" open="0" top="0" tabpos="4" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="713" topLine="33" />
</Cursor>
</File>
<File name="altimeter_screen_assets.c" open="0" top="0" tabpos="19" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="96342" topLine="161" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_color.h" open="0" top="0" tabpos="5" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="8562" topLine="290" />
</Cursor>
</File>
<File name="lvgl\lv_conf_template.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="56" />
</Cursor>
</File>
<File name="lvgl\src\widgets\list\lv_list.c" open="1" top="0" tabpos="6" split="0" active="1" splitpos="0" zoom_1="2" zoom_2="0">
<Cursor>
<Cursor1 position="2391" topLine="74" />
</Cursor>
</File>
<File name="lvgl\src\draw\lv_draw_rect.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="539" topLine="9" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_scroll.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="12525" topLine="363" />
</Cursor>
</File>
<File name="watch_menu_icons.c" open="0" top="0" tabpos="18" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="869291" topLine="156" />
@ -498,14 +328,184 @@
<Collapse line="1729" />
</Folding>
</File>
<File name="firmware_version.h" open="0" top="0" tabpos="9" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="160" topLine="0" />
</Cursor>
</File>
<File name="lv_drivers\indev\keyboard.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="440" topLine="14" />
</Cursor>
</File>
<File name="lvgl\src\hal\lv_hal_disp.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="11123" topLine="327" />
</Cursor>
</File>
<File name="lvgl\src\font\lv_font_montserrat_12.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="22" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj.h" open="0" top="0" tabpos="10" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="8074" topLine="159" />
</Cursor>
</File>
<File name="main.c" open="0" top="0" tabpos="1" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1457" topLine="45" />
</Cursor>
</File>
<File name="lv_drv_conf.h" open="0" top="0" tabpos="3" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="6602" topLine="208" />
</Cursor>
</File>
<File name="lv_drivers\win_drv.h" open="0" top="0" tabpos="10" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="585" topLine="0" />
</Cursor>
</File>
<File name="lvgl\src\widgets\imgbtn\lv_imgbtn.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="2129" topLine="53" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_style.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="7273" topLine="217" />
</Cursor>
</File>
<File name="lvgl\src\widgets\imgbtn\lv_imgbtn.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="2184" topLine="61" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_class.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1857" topLine="35" />
</Cursor>
</File>
<File name="altimeter_screen.h" open="0" top="0" tabpos="7" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1028" topLine="30" />
</Cursor>
</File>
<File name="lvgl\src\widgets\img\lv_img.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="1863" topLine="59" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_class.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="3011" topLine="100" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_indev_scroll.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="14405" topLine="323" />
</Cursor>
</File>
<File name="lvgl\examples\widgets\menu\lv_example_menu_5.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="7631" topLine="141" />
</Cursor>
</File>
<File name="lvgl\src\widgets\list\lv_list.c" open="0" top="0" tabpos="6" split="0" active="1" splitpos="0" zoom_1="2" zoom_2="0">
<Cursor>
<Cursor1 position="2391" topLine="74" />
</Cursor>
</File>
<File name="lvgl\src\widgets\roller\lv_roller.h" open="0" top="0" tabpos="6" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="715" topLine="26" />
</Cursor>
</File>
<File name="settings_screen.h" open="1" top="0" tabpos="1" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="820" topLine="8" />
</Cursor>
</File>
<File name="compass_screen.c" open="0" top="0" tabpos="11" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="6172" topLine="154" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_tree.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="2082" topLine="62" />
</Cursor>
</File>
<File name="lvgl\src\lv_api_map.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="722" topLine="32" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_scroll.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="12525" topLine="363" />
</Cursor>
</File>
<File name="lvgl\src\font\lv_font_fmt_txt.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="24" />
</Cursor>
</File>
<File name="lvgl\src\layouts\grid\lv_grid.h" open="0" top="0" tabpos="13" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="579" topLine="17" />
</Cursor>
</File>
<File name="lvgl\src\widgets\chart\lv_chart.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="11658" topLine="336" />
</Cursor>
</File>
<File name="lvgl\lv_conf_template.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="0" topLine="56" />
</Cursor>
</File>
<File name="lvgl\src\draw\lv_draw_img.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="5230" topLine="191" />
</Cursor>
</File>
<File name="settings_screen.c" open="1" top="1" tabpos="2" split="0" active="1" splitpos="513" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="6681" topLine="166" />
</Cursor>
</File>
<File name="lv_drivers\display\monitor.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="289" topLine="31" />
</Cursor>
</File>
<File name="lvgl\src\font\lv_font.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="5535" topLine="120" />
</Cursor>
</File>
<File name="altimeter_screen_assets.c" open="0" top="0" tabpos="19" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="96342" topLine="161" />
</Cursor>
</File>
<File name="lvgl\src\misc\lv_color.c" open="0" top="0" tabpos="6" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="6968" topLine="290" />
</Cursor>
</File>
<File name="lvgl\src\core\lv_obj_pos.h" open="0" top="0" tabpos="4" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="7730" topLine="167" />
</Cursor>
</File>
<File name="lv_drivers\win32drv\win32drv.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
<Cursor>
<Cursor1 position="524" topLine="954" />
</Cursor>
</File>
</CodeBlocks_layout_file>

View File

@ -19,6 +19,12 @@ static const char* vibration_force = "1\n2\n3\n4\n5\n6\n7\n8";
static const char* language_options = "Francais\nDeutsch\nEnglish";
static void _simulate_side_screen_item_click(SettingsScreen_t * const settingsScreen, lv_obj_t *item);
static void _enable_time_and_date_rollers(bool enabled, SettingsScreen_t * const settingsScreen);
static void _reset_switch_pointers(SettingsScreen_t * const settingsScreen)
{
settingsScreen->ble_switch = NULL;
settingsScreen->auto_set_time_switch = NULL;
}
static void gesture_event_cb(lv_event_t * e)
{
@ -95,17 +101,22 @@ static void orientation_dropdown_cb(lv_event_t * e)
SettingsScreen_t *settingsScreen = e->user_data;
}
static void ble_activation_switch_cb(lv_event_t *e)
static void activation_switch_cb(lv_event_t *e)
{
SettingsScreen_t *settingsScreen = e->user_data;
if(lv_obj_has_state(e->target, LV_STATE_CHECKED))
bool toggled = lv_obj_has_state(e->target, LV_STATE_CHECKED);
if(e->target == settingsScreen->ble_switch)
{
LV_LOG_USER("BLE is on");
if(toggled)
LV_LOG_USER("BLE is on");
else
LV_LOG_USER("BLE is off");
}
else
else if(e->target == settingsScreen->auto_set_time_switch)
{
LV_LOG_USER("BLE is off");
_enable_time_and_date_rollers(!toggled, settingsScreen);
}
}
@ -157,20 +168,22 @@ static lv_obj_t *add_menu_list_item(lv_obj_t *list, const char *text, lv_event_c
static void load_time_and_date_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Set Time & Date :");
lv_obj_t *toggle = lv_switch_create(settingsScreen->side_screen);
lv_obj_align_to(toggle, label, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 10);
label = lv_label_create(settingsScreen->side_screen);
settingsScreen->auto_set_time_switch = lv_switch_create(settingsScreen->side_screen);
lv_obj_align_to(settingsScreen->auto_set_time_switch, label, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 10);
lv_obj_add_event_cb(settingsScreen->auto_set_time_switch, &(activation_switch_cb), LV_EVENT_VALUE_CHANGED, settingsScreen);
label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Automatic");
lv_obj_align_to(label, toggle, LV_ALIGN_OUT_RIGHT_MID, 10, 0);
lv_obj_align_to(label, settingsScreen->auto_set_time_switch, LV_ALIGN_OUT_RIGHT_MID, 10, 0);
label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Time :");
lv_obj_align_to(label, toggle, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 10);
lv_obj_align_to(label, settingsScreen->auto_set_time_switch, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 10);
settingsScreen->hour_roller = lv_roller_create(settingsScreen->side_screen);
settingsScreen->minute_roller = lv_roller_create(settingsScreen->side_screen);
@ -243,6 +256,7 @@ static void load_time_and_date_side_screen(SettingsScreen_t *settingsScreen)
static void load_display_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Brightness :");
@ -311,6 +325,7 @@ static void load_display_side_screen(SettingsScreen_t *settingsScreen)
static void load_notifications_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Vibrate on\nnotifications :");
@ -339,21 +354,22 @@ static void load_notifications_side_screen(SettingsScreen_t *settingsScreen)
static void load_connectivity_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Connectivity :");
lv_obj_t *ble_switch = lv_switch_create(settingsScreen->side_screen);
lv_obj_align_to(ble_switch, label, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 10);
lv_obj_add_event_cb(ble_switch, &(ble_activation_switch_cb), LV_EVENT_VALUE_CHANGED, settingsScreen);
settingsScreen->ble_switch = lv_switch_create(settingsScreen->side_screen);
lv_obj_align_to(settingsScreen->ble_switch, label, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 10);
lv_obj_add_event_cb(settingsScreen->ble_switch, &(activation_switch_cb), LV_EVENT_VALUE_CHANGED, settingsScreen);
label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Bluetooth");
lv_obj_align_to(label, ble_switch, LV_ALIGN_OUT_RIGHT_MID, 10, 0);
lv_obj_align_to(label, settingsScreen->ble_switch, LV_ALIGN_OUT_RIGHT_MID, 10, 0);
label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Device Name :");
lv_obj_align_to(label, ble_switch, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 5);
lv_obj_align_to(label, settingsScreen->ble_switch, LV_ALIGN_OUT_BOTTOM_LEFT, 0, 5);
lv_obj_t *dev_name_label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(dev_name_label, NULL/*"W800SW"*/);
@ -372,6 +388,7 @@ static void load_connectivity_side_screen(SettingsScreen_t *settingsScreen)
static void load_language_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "Language :");
@ -385,6 +402,7 @@ static void load_language_side_screen(SettingsScreen_t *settingsScreen)
static void load_about_side_screen(SettingsScreen_t *settingsScreen)
{
lv_obj_clean(settingsScreen->side_screen);
_reset_switch_pointers(settingsScreen);
lv_obj_t *label = lv_label_create(settingsScreen->side_screen);
lv_label_set_text_static(label, "System Info :");
@ -593,3 +611,39 @@ static void _simulate_side_screen_item_click(SettingsScreen_t * const settingsSc
load_about_side_screen(settingsScreen);
}
}
static void _enable_time_and_date_rollers(bool enabled, SettingsScreen_t * const settingsScreen)
{
if(enabled)
{
lv_obj_clear_state(settingsScreen->hour_roller, LV_STATE_DISABLED);
lv_obj_clear_state(settingsScreen->minute_roller, LV_STATE_DISABLED);
lv_obj_clear_state(settingsScreen->second_roller, LV_STATE_DISABLED);
lv_obj_clear_state(settingsScreen->day_roller, LV_STATE_DISABLED);
lv_obj_clear_state(settingsScreen->month_roller, LV_STATE_DISABLED);
lv_obj_clear_state(settingsScreen->year_roller, LV_STATE_DISABLED);
lv_obj_set_style_bg_color(settingsScreen->hour_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->minute_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->second_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->day_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->month_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->year_roller, lv_palette_main(LV_PALETTE_BLUE), LV_PART_SELECTED);
}
else
{
lv_obj_add_state(settingsScreen->hour_roller, LV_STATE_DISABLED);
lv_obj_add_state(settingsScreen->minute_roller, LV_STATE_DISABLED);
lv_obj_add_state(settingsScreen->second_roller, LV_STATE_DISABLED);
lv_obj_add_state(settingsScreen->day_roller, LV_STATE_DISABLED);
lv_obj_add_state(settingsScreen->month_roller, LV_STATE_DISABLED);
lv_obj_add_state(settingsScreen->year_roller, LV_STATE_DISABLED);
lv_obj_set_style_bg_color(settingsScreen->hour_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->minute_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->second_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->day_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->month_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
lv_obj_set_style_bg_color(settingsScreen->year_roller, lv_palette_lighten(LV_PALETTE_GREY, 1), LV_PART_SELECTED);
}
}

View File

@ -22,6 +22,7 @@ typedef struct SettingsScreen
lv_obj_t *side_screen;
/* Menu widgets */
lv_obj_t *auto_set_time_switch;
lv_obj_t *hour_roller;
lv_obj_t *minute_roller;
lv_obj_t *second_roller;
@ -30,6 +31,7 @@ typedef struct SettingsScreen
lv_obj_t *day_roller;
lv_obj_t *month_roller;
lv_obj_t *year_roller;
lv_obj_t *ble_switch;
struct
{
lv_obj_t *current_time_label;