update for new CAN dbc (incomplete), add more NamedFields, allow mission select without confirmation, set default mission select state to manual

This commit is contained in:
Leonard Gies 2025-07-08 13:17:33 +02:00
parent e995c0ad66
commit 91b62c7b5e
Signed by: l.gies
GPG Key ID: 6F6FB9338EE44F71
23 changed files with 1029 additions and 1349 deletions

View File

@ -6,11 +6,11 @@ typedef enum {
MISSION_NONE = 0,
MISSION_ACCEL = 1,
MISSION_SKIDPAD = 2,
MISSION_AUTOX = 3,
MISSION_TRACKDRIVE = 4,
MISSION_EBS = 5,
MISSION_INSPECTION = 6,
MISSION_MANUAL = 7
MISSION_TRACKDRIVE = 3,
MISSION_BRAKETEST = 4,
MISSION_INSPECTION = 5,
MISSION_AUTOX = 6,
MISSION_MANUAL = 7,
} Mission;
#endif // __INC_STW_DEFINES_H

View File

@ -7,10 +7,9 @@ extern "C" {
#include "params.h"
#include "stw_defines.h"
#include <stdbool.h>
#include <stdint.h>
#define NUM_CONES 12
typedef enum {
TS_INACTIVE = 0,
TS_ACTIVE = 1,
@ -18,7 +17,7 @@ typedef enum {
TS_DISCHARGE = 3,
TS_ERROR = 4,
TS_CHARGING_CHECK = 5,
TS_CHARGING = 6
TS_CHARGING = 6,
} TSState;
typedef enum {
@ -27,41 +26,51 @@ typedef enum {
AS_READY = 2,
AS_DRIVING = 3,
AS_FINISHED = 4,
AS_EMERGENCY = 5
AS_EMERGENCY = 5,
} ASState;
typedef enum {
R2D_NONE = 0,
R2D_TSMS = 1,
R2D_SDC_CLOSED = 1,
R2D_TSACTIVE = 2,
R2D_RESETTING_NODES = 3,
R2D_RESETTING_COMMS = 4,
R2D_WAITING_INIT = 5,
R2D_INIT_STAGE1 = 6,
R2D_INIT_STAGE2 = 7,
R2D_INIT_SUCCESS = 0xF
R2D_INIT_SUCCESS = 0xF,
} R2DProgress;
typedef enum {
SDC_OFF = 0,
SDC_PDU_OK = 1, //
SDC_RES_OK = 2,
SDC_AMS_OK = 3,
SDC_IMD_OK = 4,
SDC_BOTS_OK = 5,
SDC_SDB_DB_OK = 6, // shut down button dashboard
SDC_IS_OK = 7,
SDC_BSPD_OK = 8,
SDC_SDB_L_OK = 9,
SDC_SDB_R_OK = 10,
SDC_TSMS_OK = 11,
SDC_HVD_OK = 12,
} SDCStatus;
typedef enum {
INICHK_START = 0,
INICHK_WD_CHECK = 1,
INICHK_WD_OK = 2,
INICHK_POS_CHK_1 = 3,
INICHK_ASB_CHECK_A_1 = 4,
INICHK_ASB_CHECK_A_2 = 5,
INICHK_SWITCH_B = 6,
INICHK_ASB_CHECK_B_1 = 7,
INICHK_ASB_CHECK_B_2 = 8,
INICHK_SWITCH_A = 9,
INICHK_ASB_CHECK_AB_1 = 10,
INICHK_ASB_CHECK_AB_2 = 11,
INICHK_POS_CHK_2 = 12,
INICHK_WAIT_TS = 13,
INICHK_DONE = 14,
INICHK_ERROR = 15
} IniChkState;
INICHK_ASB_CHECK_1 = 3,
INICHK_ASB_CHECK_2 = 4,
INICHK_WAIT_TS = 5,
INICHK_EBS_CHECK_A = 6,
INICHK_EBS_CHECK_B = 7,
INICHK_DONE = 8,
INICHK_ERROR = 9,
} InitialCheckupState;
const char *inichkstate_str(IniChkState state);
const char *inichkstate_str(InitialCheckupState state);
typedef enum {
AMS_ERROR_NONE = 0x00,
@ -69,7 +78,7 @@ typedef enum {
AMS_ERROR_SLAVE_PANIC = 0x02,
AMS_ERROR_SHUNT_TIMEOUT = 0x03,
AMS_ERROR_SHUNT_OVERCURRENT = 0x04,
AMS_ERROR_SHUNT_OVERTEMP = 0x05
AMS_ERROR_SHUNT_OVERTEMP = 0x05,
} AMSErrorKind;
typedef enum {
AMS_SLAVEPANIC_OVERTEMP = 0x00,
@ -77,9 +86,21 @@ typedef enum {
AMS_SLAVEPANIC_OVERVOLTAGE = 0x02,
AMS_SLAVEPANIC_UNDERVOLTAGE = 0x03,
AMS_SLAVEPANIC_TOO_FEW_TEMP = 0x04,
AMS_SLAVEPANIC_OPENWIRE = 0x05
AMS_SLAVEPANIC_OPENWIRE = 0x05,
} AMSSlavePanicKind;
typedef struct {
AMSErrorKind kind;
uint8_t arg;
} AMSError;
typedef struct {
float wss_fl; // in km/h
float wss_fr; // in km/h
float wss_rl; // in km/h
float wss_rr; // in km/h
} WheelSpeeds;
typedef struct {
float tire_fl;
float tire_fr;
@ -91,12 +112,10 @@ typedef struct {
float brake_rl;
float brake_rr;
float inv_l;
float inv_r;
float mot_l;
float mot_r;
float bat_l;
float bat_r;
float inv_1;
float inv_2;
float mot_1;
float mot_2;
} Temperatures;
typedef struct {
@ -105,82 +124,96 @@ typedef struct {
} ConePosition;
typedef struct {
TSState ts_state;
ASState as_state;
Mission active_mission;
int sdc_closed;
int pdu_sdc_active;
int imd_ok;
int sdcl_state[3];
R2DProgress r2d_progress;
struct {
int invl_ready : 1;
int invr_ready : 1;
int sdc_bfl : 1;
int sdc_brl : 1;
int sdc_acc : 1;
int sdc_hvb : 1;
int err_sdc : 1;
int err_ams : 1;
int err_pdu : 1;
int err_ini_chk : 1;
int err_con_mon : 1;
int err_scs : 1;
int err_sbspd : 1;
int err_appsp : 1;
int err_as : 1;
int err_ros : 1;
int err_res : 1;
int err_invl : 1;
int err_invr : 1;
} errors;
struct {
AMSErrorKind kind;
uint8_t arg;
} last_ams_error;
// AMS / TS system
struct {
uint8_t id;
AMSSlavePanicKind kind;
uint32_t arg;
} last_ams_slave_panic;
IniChkState ini_chk_state;
TSState ts_state;
bool sdc_closed;
uint8_t soc_ts;
float min_cell_volt; // in V
float max_cell_temp; // in °C
bool imd_ok; // latest IMD measurement
bool tsal_green;
bool imd_error; // latched imd error
bool ams_error; // latched ams error
unsigned lap_count;
float lap_last;
float lap_best;
AMSError last_ams_error;
// dcdc temp not in temps because temps only contains temperatures with multiple instances
float dcdc_temp; // in °C
float dcdc_current; // in A
float ts_current; // in A
float ts_voltage_bat; // in V
float ts_voltage_veh; // in V
float shunt_temperature; // in °C
Temperatures temps;
float min_cell_volt;
float max_cell_temp;
int soc_ts;
float lap_time_best; // in s
float lap_time_last; // in s
float sector_time_best; // in s
float sector_time_last; // in s
float lv_bat_voltage;
int soc_lv;
WheelSpeeds wheel_speeds; // all in km/h
uint16_t distance_session; // in m
float ts_current;
float ts_voltage_bat;
float ts_voltage_veh;
float tank_pressure_1;
float tank_pressure_2;
float speed;
uint8_t apps_percent;
float brake_pressure_f;
float brake_pressure_r;
int8_t steering_angle;
float speed; // in m/s
uint8_t lap_count;
uint8_t sector_count;
float brake_press_f;
float brake_press_r;
float hyd_press_a;
float hyd_press_b;
R2DProgress r2d_progress;
struct {
bool err_pdu : 1;
bool err_res : 1;
bool err_as : 1;
bool err_apps_plausible : 1;
bool err_soft_bspd : 1;
bool err_scs : 1; // system critical signals
bool err_con_mon : 1; // continuous monitoring of autonomous system
bool err_initial_checkup : 1; // initial checkup
bool err_inv_1 : 1;
bool err_inv_2 : 1;
bool err_ams : 1;
bool err_sdc : 1; // sdc err = not closed
} errors;
SDCStatus sdc_status;
bool inv_1_ready;
bool inv_2_ready;
float energy_per_lap;
InitialCheckupState initial_checkup_state;
float distance_total;
// autonomous system
Mission active_mission;
ASState as_state;
uint32_t last_jetson_msg;
uint32_t last_epsc_msg;
int as_ok;
float desired_angle;
float measured_angle;
float desired_speed;
float inv_velocity_1;
float inv_velocity_2;
ConePosition cone_pos[NUM_CONES];
int16_t inv_torque_demanded_1;
int16_t inv_torque_demanded_2;
int16_t inv_torque_desired_1;
int16_t inv_torque_desired_2;
uint16_t inv_control_word_1;
uint16_t inv_control_word_2;
int16_t inv_torque_actual_1;
int16_t inv_torque_actual_2;
uint16_t inv_errors_1;
uint16_t inv_errors_2;
uint16_t inv_warnings_1;
uint16_t inv_warnings_2;
ParamType last_param_confirmed;

View File

@ -10,72 +10,102 @@
#include "tx_api.h"
#include "ui.h"
#include "vehicle_state.h"
#include <stdbool.h>
#define CAN_ID_AMS_SLAVE_PANIC 0x9
#define CAN_ID_AMS_STATUS 0xA
#define CAN_ID_AMS_ERROR 0xC
#define CAN_ID_SDCL_TX 0x10
#define CAN_ID_PDU_RESPONSE 0xC9
#define CAN_ID_JETSON_TX 0xE1
#define CAN_ID_ABX_DRIVER 0x101
#define CAN_ID_ABX_TIMINGS 0x102
#define CAN_ID_ABX_BRAKE_T 0x105
#define CAN_ID_CS_INTERNAL 0x108
#define CAN_ID_ABX_MISC 0x109
#define CAN_ID_ABX_HYDRAULICS 0x110
#define CAN_ID_EPSC_OUT 0x321
#define CAN_ID_MISSION_SELECTED 0x400
#define CAN_ID_STW_BUTTONS 0x401
#define CAN_ID_STW_PARAM_SET 0x402
// CAN filter constants
#define CAN_ID_AMS_SLAVE_PANIC 0x009
#define CAN_ID_AMS_STATUS 0x00A
#define CAN_ID_AMS_ERROR 0x00C
#define CAN_ID_AMS_DCDC 0x313
#define CAN_ID_PWM_DUTYCYLE 0x0DC
#define CAN_ID_PWM_CONFIG 0x0DD
#define CAN_ID_FTCU_TIMINGS 0x102
#define CAN_ID_FTCU_DAMPER 0x103
#define CAN_ID_FTCU_WHEELSPEED 0x104
#define CAN_ID_FTCU_BRAKE_T 0x105
#define CAN_ID_FTCU_COOLING 0x107
#define CAN_ID_FTCU_PNEUMATIK 0x110
#define CAN_ID_FTCU_DRIVER 0x111
#define CAN_ID_AS_MISSION_FB 0x410
#define CAN_ID_STW_STATUS 0x412
#define CAN_ID_ABX_PARAM_CONFIRMED 0x413
#define CAN_ID_STW_CONES_BASE 0x414
#define CAN_ID_STW_CONES_MASK 0x7FC
#define CAN_ID_FTCU_PARAM_CONFIRMED 0x413
#define CAN_ID_FTCU_TELEMETRIE1 0x719
#define CAN_ID_FTCU_TELEMETRIE2 0x720
#define CAN_ID_PDU_RESPONSE 0x0C9
#define CAN_ID_PDU_CURRENT1 0x0CA
#define CAN_ID_PDU_CURRENT2 0x0CB
#define CAN_ID_PDU_CURRENT3 0x0CC
#define CAN_ID_PDU_CURRENT4 0x0CD
#define CAN_ID_DASHBOARD 0x420
#define CAN_ID_SSU 0x500
#define CAN_ID_SHUNT_CURRENT 0x521
#define CAN_ID_SHUNT_VOLTAGE1 0x522
#define CAN_ID_SHUNT_VOLTAGE2 0x523
#define CAN_AMS_STATUS_VOLTAGE_FACTOR 1e-4
#define CAN_AMS_STATUS_TEMP_FACTOR 0.0625
#define CAN_SDCL_STATE_1_MASK (1 << 1)
#define CAN_SDCL_STATE_2_MASK (1 << 2)
#define CAN_SDCL_STATE_3_MASK (1 << 3)
#define CAN_PDU_RESPONSE_SDC_TX_MASK (1 << 4)
#define CAN_JETSON_TX_AS_OK_MASK (1 << 1)
#define CAN_JETSON_TX_ANGLE_FACTOR 0.00784314f
#define CAN_JETSON_TX_SPEED_FACTOR (0.2 * 3.6)
#define CAN_ABX_DRIVER_SPEED_FACTOR (0.2 * 3.6)
#define CAN_ABX_DRIVER_PRESS_FACTOR 0.1f
#define CAN_CS_INTERNAL_TEMP_FACTOR 0.01
#define CAN_ABX_MISC_DISTANCE_TOTAL_FACTOR 0.01
#define CAN_ABX_MISC_LV_BAT_VOLTAGE_FACTOR (15.0f / 255)
#define CAN_EPSC_OUT_ANGLE_FACTOR 7.20721e-05f
#define CAN_ID_SHUNT_TEMPERATURE 0x525
#define CAN_ID_TTS_FL 0x701
#define CAN_ID_TTS_FR 0x702
#define CAN_ID_TTS_RL 0x703
#define CAN_ID_TTS_RR 0x704
#define CAN_ID_INVERTER_VELOCITY 0x776
#define CAN_ID_INVERTER_TORQUE_WANTED 0x777
#define CAN_ID_INVERTER_TEMPERATURE 0x778
#define CAN_ID_INVERTER_TORQUE_ACTUAL 0x779
#define CAN_ID_INVERTER_ERRORS_WARNINGS 0x780
// CAN sending constants
#define CAN_ID_MISSION_SELECTED 0x400
#define CAN_ID_STW_BUTTONS 0x401
#define CAN_ID_STW_PARAM_SET 0x402
void vehicle_thread_entry(ULONG hfdcan_addr) {
memset(&vehicle_state, 0, sizeof(vehicle_state));
memset(&vehicle_state.cone_pos, 0xFF, sizeof(vehicle_state.cone_pos));
ftcan_init((void *)hfdcan_addr);
ftcan_add_filter(CAN_ID_AMS_SLAVE_PANIC, 0x7FF);
ftcan_add_filter(CAN_ID_AMS_STATUS, 0x7FF);
ftcan_add_filter(CAN_ID_AMS_ERROR, 0x7FF);
ftcan_add_filter(CAN_ID_SDCL_TX, 0x7FF);
ftcan_add_filter(CAN_ID_PDU_RESPONSE, 0x7FF);
ftcan_add_filter(CAN_ID_JETSON_TX, 0x7FF);
ftcan_add_filter(CAN_ID_ABX_DRIVER, 0x7FF);
ftcan_add_filter(CAN_ID_ABX_TIMINGS, 0x7FF);
ftcan_add_filter(CAN_ID_ABX_BRAKE_T, 0x7FF);
ftcan_add_filter(CAN_ID_CS_INTERNAL, 0x7FF);
ftcan_add_filter(CAN_ID_ABX_MISC, 0x7FF);
ftcan_add_filter(CAN_ID_ABX_HYDRAULICS, 0x7FF);
ftcan_add_filter(CAN_ID_EPSC_OUT, 0x7FF);
ftcan_add_filter(CAN_ID_AMS_DCDC, 0x7FF);
ftcan_add_filter(CAN_ID_PWM_DUTYCYLE, 0x7FF);
ftcan_add_filter(CAN_ID_PWM_CONFIG, 0x7FF);
ftcan_add_filter(CAN_ID_FTCU_TIMINGS, 0x7FF);
ftcan_add_filter(CAN_ID_FTCU_DAMPER, 0x7FF);
ftcan_add_filter(CAN_ID_FTCU_WHEELSPEED, 0x7FF);
ftcan_add_filter(CAN_ID_FTCU_BRAKE_T, 0x7FF);
ftcan_add_filter(CAN_ID_FTCU_COOLING, 0x7FF);
ftcan_add_filter(CAN_ID_FTCU_PNEUMATIK, 0x7FF);
ftcan_add_filter(CAN_ID_FTCU_DRIVER, 0x7FF);
ftcan_add_filter(CAN_ID_AS_MISSION_FB, 0x7FF);
ftcan_add_filter(CAN_ID_STW_STATUS, 0x7FF);
ftcan_add_filter(CAN_ID_ABX_PARAM_CONFIRMED, 0x7FF);
ftcan_add_filter(CAN_ID_STW_CONES_BASE, CAN_ID_STW_CONES_MASK);
ftcan_add_filter(CAN_ID_FTCU_PARAM_CONFIRMED, 0x7FF);
ftcan_add_filter(CAN_ID_FTCU_TELEMETRIE1, 0x7FF);
ftcan_add_filter(CAN_ID_FTCU_TELEMETRIE2, 0x7FF);
ftcan_add_filter(CAN_ID_PDU_RESPONSE, 0x7FF);
ftcan_add_filter(CAN_ID_PDU_CURRENT1, 0x7FF);
ftcan_add_filter(CAN_ID_PDU_CURRENT2, 0x7FF);
ftcan_add_filter(CAN_ID_PDU_CURRENT3, 0x7FF);
ftcan_add_filter(CAN_ID_PDU_CURRENT4, 0x7FF);
ftcan_add_filter(CAN_ID_DASHBOARD, 0x7FF);
ftcan_add_filter(CAN_ID_SSU, 0x7FF);
ftcan_add_filter(CAN_ID_SHUNT_CURRENT, 0x7FF);
ftcan_add_filter(CAN_ID_SHUNT_VOLTAGE1, 0x7FF);
ftcan_add_filter(CAN_ID_SHUNT_VOLTAGE2, 0x7FF);
ftcan_add_filter(CAN_ID_SHUNT_TEMPERATURE, 0x7FF);
ftcan_add_filter(CAN_ID_TTS_FL, 0x7FF);
ftcan_add_filter(CAN_ID_TTS_FR, 0x7FF);
ftcan_add_filter(CAN_ID_TTS_RL, 0x7FF);
ftcan_add_filter(CAN_ID_TTS_RL, 0x7FF);
ftcan_add_filter(CAN_ID_INVERTER_VELOCITY, 0x7FF);
ftcan_add_filter(CAN_ID_INVERTER_TORQUE_WANTED, 0x7FF);
ftcan_add_filter(CAN_ID_INVERTER_TEMPERATURE, 0x7FF);
ftcan_add_filter(CAN_ID_INVERTER_TORQUE_ACTUAL, 0x7FF);
ftcan_add_filter(CAN_ID_INVERTER_ERRORS_WARNINGS, 0x7FF);
while (1) {
tx_thread_sleep(10);
@ -83,8 +113,7 @@ void vehicle_thread_entry(ULONG hfdcan_addr) {
#ifdef DEMO_MODE
double tick = HAL_GetTick();
vehicle_state.speed =
(sin(tick * 0.001) * 8 + 10 + cos(tick * 0.003) * 8) * 4;
vehicle_state.speed = (sin(tick * 0.001) * 8 + 10 + cos(tick * 0.003) * 8) * 4;
if (vehicle_state.speed <= 0) {
vehicle_state.speed = 0;
}
@ -107,160 +136,199 @@ void vehicle_broadcast_param(ParamType param, int32_t value) {
}
void vehicle_broadcast_buttons(GPIO_PinState *button_states) {
uint8_t data = (button_states[DRS_BUTTON_IDX] << 0) |
(button_states[6] << 1) | (button_states[7] << 2);
uint8_t data = (button_states[DRS_BUTTON_IDX] << 0) | (button_states[6] << 1) | (button_states[7] << 2);
ftcan_transmit(CAN_ID_STW_BUTTONS, &data, 1);
}
void ftcan_msg_received_cb(uint16_t id, size_t datalen, const uint8_t *data) {
const uint8_t *ptr;
if ((id & CAN_ID_STW_CONES_MASK) == CAN_ID_STW_CONES_BASE) {
size_t msg_num = id - CAN_ID_STW_CONES_BASE;
for (size_t i = 0; i < 4; i++) {
vehicle_state.cone_pos[msg_num * 4 + i].x = data[i * 2];
vehicle_state.cone_pos[msg_num * 4 + i].y = data[i * 2 + 1];
}
} else {
switch (id) {
case CAN_ID_AMS_SLAVE_PANIC:
vehicle_state.last_ams_slave_panic.id = data[0];
vehicle_state.last_ams_slave_panic.kind = data[1];
ptr = &data[2];
vehicle_state.last_ams_slave_panic.arg =
ftcan_unmarshal_unsigned(&ptr, 4);
break;
case CAN_ID_AMS_STATUS:
vehicle_state.ts_state = data[0] & 0x7F;
vehicle_state.sdc_closed = (data[0] & 0x80) >> 7;
vehicle_state.soc_ts = data[1];
ptr = &data[2];
vehicle_state.min_cell_volt =
ftcan_unmarshal_unsigned(&ptr, 2) * CAN_AMS_STATUS_VOLTAGE_FACTOR;
vehicle_state.max_cell_temp =
ftcan_unmarshal_signed(&ptr, 2) * CAN_AMS_STATUS_TEMP_FACTOR;
vehicle_state.imd_ok = (data[6] >> 7);
// TODO: Separate temperatures for left and right side of battery
vehicle_state.temps.bat_l = vehicle_state.max_cell_temp;
vehicle_state.temps.bat_r = vehicle_state.max_cell_temp;
break;
case CAN_ID_SDCL_TX:
vehicle_state.sdcl_state[0] = data[0] & CAN_SDCL_STATE_1_MASK;
vehicle_state.sdcl_state[1] = data[0] & CAN_SDCL_STATE_2_MASK;
vehicle_state.sdcl_state[2] = data[0] & CAN_SDCL_STATE_3_MASK;
break;
case CAN_ID_PDU_RESPONSE:
vehicle_state.pdu_sdc_active = data[0] & CAN_PDU_RESPONSE_SDC_TX_MASK;
break;
case CAN_ID_AMS_ERROR:
vehicle_state.last_ams_error.kind = data[0];
vehicle_state.last_ams_error.arg = data[1];
break;
case CAN_ID_JETSON_TX:
vehicle_state.last_jetson_msg = HAL_GetTick();
vehicle_state.as_ok = data[0] & CAN_JETSON_TX_AS_OK_MASK;
vehicle_state.desired_speed =
((int8_t)data[1]) * CAN_JETSON_TX_SPEED_FACTOR;
vehicle_state.desired_angle =
((int8_t)data[2]) * CAN_JETSON_TX_ANGLE_FACTOR;
break;
case CAN_ID_ABX_DRIVER:
vehicle_state.brake_press_f =
(data[1] | ((data[2] & 0x0F) << 8)) * CAN_ABX_DRIVER_PRESS_FACTOR;
vehicle_state.brake_press_r =
((data[2] >> 4) | (data[3] << 4)) * CAN_ABX_DRIVER_PRESS_FACTOR;
vehicle_state.speed = data[5] * CAN_ABX_DRIVER_SPEED_FACTOR;
break;
case CAN_ID_ABX_HYDRAULICS:
vehicle_state.hyd_press_a =
(data[0] | ((data[1] & 0x0F) << 8)) * CAN_ABX_DRIVER_PRESS_FACTOR;
vehicle_state.hyd_press_b =
((data[1] >> 4) | (data[2] << 4)) * CAN_ABX_DRIVER_PRESS_FACTOR;
break;
case CAN_ID_ABX_TIMINGS:
vehicle_state.lap_best = (data[0] | (data[1] << 8)) * 0.01f;
vehicle_state.lap_last = (data[2] | (data[3] << 8)) * 0.01f;
break;
case CAN_ID_ABX_BRAKE_T:
vehicle_state.temps.brake_fl = (data[0] | (data[1] << 8)) * 0.01f;
vehicle_state.temps.brake_fr = (data[2] | (data[3] << 8)) * 0.01f;
vehicle_state.temps.brake_rl = (data[4] | (data[5] << 8)) * 0.01f;
vehicle_state.temps.brake_rr = (data[6] | (data[7] << 8)) * 0.01f;
break;
case CAN_ID_CS_INTERNAL:
vehicle_state.temps.inv_l =
(data[0] | (data[1] << 8)) * CAN_CS_INTERNAL_TEMP_FACTOR;
vehicle_state.temps.inv_r =
(data[2] | (data[3] << 8)) * CAN_CS_INTERNAL_TEMP_FACTOR;
vehicle_state.temps.mot_l =
(data[4] | (data[5] << 8)) * CAN_CS_INTERNAL_TEMP_FACTOR;
vehicle_state.temps.mot_r =
(data[6] | (data[7] << 8)) * CAN_CS_INTERNAL_TEMP_FACTOR;
break;
case CAN_ID_ABX_MISC:
vehicle_state.distance_total =
(data[3] | (data[4] << 8)) * CAN_ABX_MISC_DISTANCE_TOTAL_FACTOR;
vehicle_state.soc_lv = data[5];
vehicle_state.lv_bat_voltage =
data[6] * CAN_ABX_MISC_LV_BAT_VOLTAGE_FACTOR;
break;
case CAN_ID_EPSC_OUT:
vehicle_state.last_epsc_msg = HAL_GetTick();
vehicle_state.measured_angle =
((int16_t)((data[0] << 8) | (data[1]))) * CAN_EPSC_OUT_ANGLE_FACTOR;
break;
case CAN_ID_AS_MISSION_FB:
vehicle_state.active_mission = data[0] & 0b111;
break;
case CAN_ID_STW_STATUS:
vehicle_state.as_state = data[0] & 0b111;
vehicle_state.r2d_progress = data[0] >> 4;
vehicle_state.errors.invl_ready = (data[1] >> 0) & 1;
vehicle_state.errors.invr_ready = (data[1] >> 1) & 1;
vehicle_state.errors.sdc_bfl = (data[1] >> 2) & 1;
vehicle_state.errors.sdc_brl = (data[1] >> 3) & 1;
vehicle_state.errors.sdc_acc = (data[1] >> 4) & 1;
vehicle_state.errors.sdc_hvb = (data[1] >> 5) & 1;
vehicle_state.lap_count = data[2] & 0b111111;
vehicle_state.ini_chk_state = data[3];
vehicle_state.errors.err_sdc = (data[4] >> 0) & 1;
vehicle_state.errors.err_ams = (data[4] >> 1) & 1;
vehicle_state.errors.err_pdu = (data[4] >> 2) & 1;
vehicle_state.errors.err_ini_chk = (data[4] >> 3) & 1;
vehicle_state.errors.err_con_mon = (data[4] >> 4) & 1;
vehicle_state.errors.err_scs = (data[4] >> 5) & 1;
vehicle_state.errors.err_sbspd = (data[4] >> 6) & 1;
vehicle_state.errors.err_appsp = (data[4] >> 7) & 1;
vehicle_state.errors.err_as = (data[5] >> 0) & 1;
vehicle_state.errors.err_ros = (data[5] >> 1) & 1;
vehicle_state.errors.err_res = (data[5] >> 2) & 1;
vehicle_state.errors.err_invl = (data[5] >> 3) & 1;
vehicle_state.errors.err_invr = (data[5] >> 4) & 1;
break;
case CAN_ID_ABX_PARAM_CONFIRMED:
vehicle_state.last_param_confirmed = data[0];
tx_event_flags_set(&gui_update_events, GUI_UPDATE_PARAM_CONFIRMED,
TX_OR);
break;
case CAN_ID_SHUNT_CURRENT: {
// The first two bytes of shunt result messages are metadata
const uint8_t *result_ptr = &data[2];
vehicle_state.ts_current =
ftcan_unmarshal_signed(&result_ptr, 4) * 1e-3;
break;
}
case CAN_ID_SHUNT_VOLTAGE1: {
const uint8_t *result_ptr = &data[2];
vehicle_state.ts_voltage_bat =
ftcan_unmarshal_signed(&result_ptr, 4) * 1e-3;
break;
}
case CAN_ID_SHUNT_VOLTAGE2: {
const uint8_t *result_ptr = &data[2];
vehicle_state.ts_voltage_veh =
ftcan_unmarshal_signed(&result_ptr, 4) * 1e-3;
break;
}
}
switch (id) {
case CAN_ID_AMS_SLAVE_PANIC:
vehicle_state.last_ams_slave_panic.id = data[0];
vehicle_state.last_ams_slave_panic.kind = data[1];
ptr = &data[2];
vehicle_state.last_ams_slave_panic.arg = ftcan_unmarshal_unsigned(&ptr, 4);
break;
case CAN_ID_AMS_STATUS:
vehicle_state.ts_state = data[0] & 0x7F;
vehicle_state.sdc_closed = (data[0] & 0x80) >> 7;
vehicle_state.soc_ts = data[1];
ptr = &data[2];
vehicle_state.min_cell_volt = ftcan_unmarshal_unsigned(&ptr, 2) * 1e-3;
vehicle_state.max_cell_temp = ftcan_unmarshal_signed(&ptr, 2) * 1e-2;
// vehicle_state.imd_state = data[6] & 0x7F; // does not provide useful
// data
vehicle_state.imd_ok = (data[6] & 0x80) >> 7;
vehicle_state.tsal_green = data[7] & 0x01;
vehicle_state.imd_error = (data[7] & 0x02) >> 1;
vehicle_state.ams_error = (data[7] & 0x04) >> 2;
break;
case CAN_ID_AMS_ERROR:
vehicle_state.last_ams_error.kind = data[0];
vehicle_state.last_ams_error.arg = data[1];
break;
case CAN_ID_AMS_DCDC:
ptr = &data[0];
vehicle_state.dcdc_temp = ftcan_unmarshal_signed(&ptr, 2) * 0.01f;
vehicle_state.dcdc_current = ftcan_unmarshal_signed(&ptr, 2) * 0.001f;
break;
case CAN_ID_PWM_DUTYCYLE:
// TODO
break;
case CAN_ID_PWM_CONFIG:
// TODO
break;
case CAN_ID_FTCU_TIMINGS:
vehicle_state.lap_time_best = (data[0] | (data[1] << 8)) * 0.01f;
vehicle_state.lap_time_last = (data[2] | (data[3] << 8)) * 0.01f;
vehicle_state.sector_time_best = (data[4] | (data[5] << 8)) * 0.01f;
vehicle_state.sector_time_last = (data[6] | (data[7] << 8)) * 0.01f;
break;
case CAN_ID_FTCU_DAMPER:
// TODO
break;
case CAN_ID_FTCU_WHEELSPEED:
vehicle_state.wheel_speeds.wss_fl = data[0] | ((data[1] & 0x0F) << 8);
vehicle_state.wheel_speeds.wss_fr = ((data[1] >> 4) & 0x0F) | (data[2] << 4);
vehicle_state.wheel_speeds.wss_rl = data[3] | ((data[4] & 0x0F) << 8);
vehicle_state.wheel_speeds.wss_rr = ((data[4] >> 4) & 0x0F) | (data[5] << 4);
vehicle_state.distance_session = data[6] | (data[7] << 8);
break;
case CAN_ID_FTCU_BRAKE_T:
vehicle_state.temps.brake_fl = (data[0] | (data[1] << 8)) * 0.01f;
vehicle_state.temps.brake_fr = (data[2] | (data[3] << 8)) * 0.01f;
vehicle_state.temps.brake_rl = (data[4] | (data[5] << 8)) * 0.01f;
vehicle_state.temps.brake_rr = (data[6] | (data[7] << 8)) * 0.01f;
break;
case CAN_ID_FTCU_COOLING:
// TODO
break;
case CAN_ID_FTCU_PNEUMATIK:
vehicle_state.tank_pressure_1 = data[0] | ((data[1] & 0x0F) << 8);
vehicle_state.tank_pressure_2 = data[2] | ((data[3] & 0x0F) << 8);
break;
case CAN_ID_FTCU_DRIVER:
vehicle_state.apps_percent = data[0];
vehicle_state.brake_pressure_f = (data[1] | ((data[2] & 0x0F) << 8)) * 0.1f;
vehicle_state.brake_pressure_r = (((data[2] >> 4) & 0x0F) | (data[3] << 4)) * 0.1f;
vehicle_state.steering_angle = data[4];
vehicle_state.speed = data[5] * 0.2f;
vehicle_state.lap_count = data[6];
vehicle_state.sector_count = data[7];
break;
case CAN_ID_AS_MISSION_FB:
vehicle_state.active_mission = data[0] & 0b111;
break;
case CAN_ID_STW_STATUS:
// vehicle_state.lap_count = data[0] & 0b111111;
vehicle_state.errors.err_pdu = (data[0] >> 6) & 0b1;
vehicle_state.errors.err_res = (data[0] >> 7) & 0b1;
vehicle_state.r2d_progress = (data[1] >> 0) & 0b1111;
vehicle_state.as_state = (data[1] >> 4) & 0b111;
vehicle_state.errors.err_as = (data[1] >> 7) & 0b1;
vehicle_state.errors.err_apps_plausible = (data[2] >> 0) & 0b1;
vehicle_state.errors.err_soft_bspd = (data[2] >> 1) & 0b1;
vehicle_state.errors.err_scs = (data[2] >> 2) & 0b1;
vehicle_state.errors.err_con_mon = (data[2] >> 3) & 0b1;
vehicle_state.errors.err_initial_checkup = (data[2] >> 4) & 0b1;
vehicle_state.errors.err_inv_2 = (data[2] >> 5) & 0b1;
vehicle_state.errors.err_inv_1 = (data[2] >> 6) & 0b1;
vehicle_state.errors.err_ams = (data[2] >> 7) & 0b1;
vehicle_state.errors.err_sdc = (data[3] >> 0) & 0b1;
vehicle_state.sdc_status = (data[3] >> 1) & 0b1111;
vehicle_state.inv_2_ready = (data[3] >> 5) & 0b1;
vehicle_state.inv_1_ready = (data[3] >> 6) & 0b1;
vehicle_state.energy_per_lap = data[4] | (data[5] << 8);
vehicle_state.initial_checkup_state = data[6];
break;
case CAN_ID_FTCU_PARAM_CONFIRMED:
vehicle_state.last_param_confirmed = data[0];
tx_event_flags_set(&gui_update_events, GUI_UPDATE_PARAM_CONFIRMED, TX_OR);
break;
case CAN_ID_FTCU_TELEMETRIE1:
// TODO
break;
case CAN_ID_FTCU_TELEMETRIE2:
// TODO
break;
case CAN_ID_PDU_RESPONSE:
// TODO
break;
case CAN_ID_PDU_CURRENT1:
// TODO
break;
case CAN_ID_PDU_CURRENT2:
// TODO
break;
case CAN_ID_PDU_CURRENT3:
// TODO
break;
case CAN_ID_PDU_CURRENT4:
// TODO
break;
case CAN_ID_DASHBOARD:
// TODO
break;
case CAN_ID_SSU:
// TODO
break;
case CAN_ID_SHUNT_CURRENT:
// The first two bytes of shunt result messages are metadata
ptr = &data[2];
vehicle_state.ts_current = ftcan_unmarshal_signed(&ptr, 4) * 0.001f;
break;
case CAN_ID_SHUNT_VOLTAGE1:
ptr = &data[2];
vehicle_state.ts_voltage_bat = ftcan_unmarshal_signed(&ptr, 4) * -0.001f;
break;
case CAN_ID_SHUNT_VOLTAGE2:
ptr = &data[2];
vehicle_state.ts_voltage_veh = vehicle_state.ts_voltage_bat - (ftcan_unmarshal_signed(&ptr, 4) * -0.001f);
break;
case CAN_ID_SHUNT_TEMPERATURE:
ptr = &data[2];
vehicle_state.shunt_temperature = ftcan_unmarshal_signed(&ptr, 4) * 0.1f;
break;
case CAN_ID_TTS_FL:
// TODO
break;
case CAN_ID_TTS_FR:
// TODO
break;
case CAN_ID_TTS_RL:
// TODO
break;
case CAN_ID_TTS_RR:
// TODO
break;
case CAN_ID_INVERTER_VELOCITY:
vehicle_state.inv_velocity_1 = (data[0] | (data[1] << 8) | (data[2] << 16) | (data[3] << 24)) * 0.001f;
vehicle_state.inv_velocity_2 = (data[4] | (data[5] << 8) | (data[6] << 16) | (data[7] << 24)) * 0.001f;
break;
case CAN_ID_INVERTER_TORQUE_WANTED:
vehicle_state.inv_torque_demanded_1 = data[0] | (data[1] << 8);
vehicle_state.inv_torque_demanded_2 = data[2] | (data[3] << 8);
vehicle_state.inv_torque_desired_1 = data[4] | (data[5] << 8);
vehicle_state.inv_torque_desired_2 = data[6] | (data[7] << 8);
break;
case CAN_ID_INVERTER_TEMPERATURE:
vehicle_state.temps.inv_1 = data[0] | (data[1] << 8);
vehicle_state.temps.mot_1 = data[2] | (data[3] << 8);
vehicle_state.temps.inv_2 = data[4] | (data[5] << 8);
vehicle_state.temps.mot_2 = data[6] | (data[7] << 8);
break;
case CAN_ID_INVERTER_TORQUE_ACTUAL:
vehicle_state.inv_control_word_1 = data[0] | (data[1] << 8);
vehicle_state.inv_torque_actual_1 = data[2] | (data[3] << 8);
vehicle_state.inv_control_word_2 = data[4] | (data[5] << 8);
vehicle_state.inv_torque_actual_2 = data[6] | (data[7] << 8);
break;
case CAN_ID_INVERTER_ERRORS_WARNINGS:
vehicle_state.inv_errors_1 = data[0] | (data[1] << 8);
vehicle_state.inv_warnings_1 = data[2] | (data[3] << 8);
vehicle_state.inv_errors_2 = data[4] | (data[5] << 8);
vehicle_state.inv_warnings_2 = data[6] | (data[7] << 8);
break;
}
tx_event_flags_set(&gui_update_events, GUI_UPDATE_VEHICLE_STATE, TX_OR);
}

View File

@ -2,40 +2,28 @@
VehicleState vehicle_state;
const char *inichkstate_str(IniChkState state) {
switch (vehicle_state.ini_chk_state) {
case INICHK_START:
return "START";
case INICHK_WD_CHECK:
return "WD CHK";
case INICHK_WD_OK:
return "WD OK";
case INICHK_POS_CHK_1:
return "POS CHK 1";
case INICHK_ASB_CHECK_A_1:
return "ASB CHK A1";
case INICHK_ASB_CHECK_A_2:
return "ASB CHK A2";
case INICHK_SWITCH_B:
return "SWITCH B";
case INICHK_ASB_CHECK_B_1:
return "ASB CHK B1";
case INICHK_ASB_CHECK_B_2:
return "ASB CHK B2";
case INICHK_SWITCH_A:
return "SWITCH A";
case INICHK_ASB_CHECK_AB_1:
return "ASB CHK AB1";
case INICHK_ASB_CHECK_AB_2:
return "ASB CHK AB2";
case INICHK_POS_CHK_2:
return "POS CHK 2";
case INICHK_WAIT_TS:
return "WAIT TS";
case INICHK_DONE:
return "DONE";
case INICHK_ERROR:
return "ERROR";
const char *inichkstate_str(InitialCheckupState state) {
switch (vehicle_state.initial_checkup_state) {
case INICHK_START:
return "START";
case INICHK_WD_CHECK:
return "WD CHK";
case INICHK_WD_OK:
return "WD OK";
case INICHK_ASB_CHECK_1:
return "ABC CHK 1";
case INICHK_ASB_CHECK_2:
return "ASB CHK 2";
case INICHK_WAIT_TS:
return "WAIT TS";
case INICHK_EBS_CHECK_A:
return "EBS CHK A";
case INICHK_EBS_CHECK_B:
return "EBS CHK B";
case INICHK_DONE:
return "DONE";
case INICHK_ERROR:
return "ERROR";
}
return "UNKNOWN";
}

View File

@ -8,13 +8,13 @@
"section": "ExtFlashSection",
"extra_section": "ExtFlashSection",
"images": {
"Fasttube_Logo_small_white.png": {
"logo_dv_small_white.png": {
"layout_rotation": "90"
},
"logo_dv_small.png": {
"layout_rotation": "90"
},
"logo_dv_small_white.png": {
"Fasttube_Logo_small_white.png": {
"layout_rotation": "90"
}
},

View File

@ -223,10 +223,10 @@
<Translation Language="GB">&lt;value&gt;</Translation>
</Text>
<Text Id="__SingleUse_OOU3" Alignment="Left" TypographyId="Chinat_Small">
<Translation Language="GB">Pressure Acc B:</Translation>
<Translation Language="GB">Pressure Acc 2:</Translation>
</Text>
<Text Id="__SingleUse_2FPP" Alignment="Left" TypographyId="Chinat_Small">
<Translation Language="GB">Pressure Acc A:</Translation>
<Translation Language="GB">Pressure Acc 1:</Translation>
</Text>
<Text Id="__SingleUse_2S21" Alignment="Right" TypographyId="Numbers_Small">
<Translation Language="GB">&lt;value&gt;</Translation>

View File

@ -12,8 +12,6 @@
#include <touchgfx/widgets/TextArea.hpp>
#include <touchgfx/containers/Container.hpp>
#include <touchgfx/widgets/TextAreaWithWildcard.hpp>
#include <touchgfx/widgets/canvas/Shape.hpp>
#include <touchgfx/widgets/canvas/PainterRGB565.hpp>
#include <touchgfx/containers/progress_indicators/BoxProgress.hpp>
class AMIViewBase : public touchgfx::View<AMIPresenter>
@ -43,37 +41,14 @@ protected:
touchgfx::TextAreaWithOneWildcard desiredSpeed;
touchgfx::TextArea textArea4;
touchgfx::TextArea textArea3;
touchgfx::Container map;
touchgfx::Shape<3> cone0;
touchgfx::PainterRGB565 cone0Painter;
touchgfx::Shape<3> cone1;
touchgfx::PainterRGB565 cone1Painter;
touchgfx::Shape<3> cone2;
touchgfx::PainterRGB565 cone2Painter;
touchgfx::Shape<3> cone3;
touchgfx::PainterRGB565 cone3Painter;
touchgfx::Shape<3> cone4;
touchgfx::PainterRGB565 cone4Painter;
touchgfx::Shape<3> cone5;
touchgfx::PainterRGB565 cone5Painter;
touchgfx::Shape<3> cone6;
touchgfx::PainterRGB565 cone6Painter;
touchgfx::Shape<3> cone7;
touchgfx::PainterRGB565 cone7Painter;
touchgfx::Shape<3> cone8;
touchgfx::PainterRGB565 cone8Painter;
touchgfx::Shape<3> cone9;
touchgfx::PainterRGB565 cone9Painter;
touchgfx::Shape<3> ft;
touchgfx::PainterRGB565 ftPainter;
touchgfx::Container init;
touchgfx::TextAreaWithOneWildcard asOK;
touchgfx::TextArea textArea8;
touchgfx::TextArea textArea7;
touchgfx::TextAreaWithOneWildcard pressRear;
touchgfx::TextAreaWithOneWildcard pressFront;
touchgfx::TextAreaWithOneWildcard pressB;
touchgfx::TextAreaWithOneWildcard pressA;
touchgfx::TextAreaWithOneWildcard press2;
touchgfx::TextAreaWithOneWildcard press1;
touchgfx::TextArea textArea6;
touchgfx::TextArea textArea5;
touchgfx::BoxProgress progressBar;
@ -82,12 +57,6 @@ protected:
private:
/*
* Canvas Buffer Size
*/
static const uint32_t CANVAS_BUFFER_SIZE = 7200;
uint8_t canvasBuffer[CANVAS_BUFFER_SIZE];
};
#endif // AMIVIEWBASE_HPP

View File

@ -52,10 +52,10 @@ protected:
touchgfx::ListLayout missionList;
MissionSelectElement accel;
MissionSelectElement skidpad;
MissionSelectElement autox;
MissionSelectElement trackdrive;
MissionSelectElement ebs;
MissionSelectElement inspection;
MissionSelectElement autox;
MissionSelectElement manual;
touchgfx::Line lastLine;
touchgfx::PainterRGB565 lastLinePainter;

View File

@ -2,15 +2,12 @@
/********** THIS FILE IS GENERATED BY TOUCHGFX DESIGNER, DO NOT MODIFY ***********/
/*********************************************************************************/
#include <gui_generated/ami_screen/AMIViewBase.hpp>
#include <touchgfx/canvas_widget_renderer/CanvasWidgetRenderer.hpp>
#include <touchgfx/Color.hpp>
#include <images/BitmapDatabase.hpp>
#include <texts/TextKeysAndLanguages.hpp>
AMIViewBase::AMIViewBase()
{
touchgfx::CanvasWidgetRenderer::setupBuffer(canvasBuffer, CANVAS_BUFFER_SIZE);
__background.setPosition(0, 0, 480, 320);
__background.setColor(touchgfx::Color::getColorFromRGB(0, 0, 0));
add(__background);
@ -76,129 +73,6 @@ AMIViewBase::AMIViewBase()
textArea3.setTypedText(touchgfx::TypedText(T___SINGLEUSE_Z78U));
driving.add(textArea3);
map.setPosition(15, 103, 255, 202);
cone0.setPosition(0, 0, 10, 10);
cone0.setOrigin(0.0f, 0.0f);
cone0.setScale(1.0f, 1.0f);
cone0.setAngle(0.0f);
cone0Painter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 0));
cone0.setPainter(cone0Painter);
const touchgfx::AbstractShape::ShapePoint<float> cone0Points[3] = { { 0.0f, 0.0f }, { 10.0f, 5.0f }, { 0.0f, 10.0f } };
cone0.setShape(cone0Points);
cone0.setVisible(false);
map.add(cone0);
cone1.setPosition(0, 0, 10, 10);
cone1.setOrigin(0.0f, 0.0f);
cone1.setScale(1.0f, 1.0f);
cone1.setAngle(0.0f);
cone1Painter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 0));
cone1.setPainter(cone1Painter);
const touchgfx::AbstractShape::ShapePoint<float> cone1Points[3] = { { 0.0f, 0.0f }, { 10.0f, 5.0f }, { 0.0f, 10.0f } };
cone1.setShape(cone1Points);
cone1.setVisible(false);
map.add(cone1);
cone2.setPosition(0, 0, 10, 10);
cone2.setOrigin(0.0f, 0.0f);
cone2.setScale(1.0f, 1.0f);
cone2.setAngle(0.0f);
cone2Painter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 0));
cone2.setPainter(cone2Painter);
const touchgfx::AbstractShape::ShapePoint<float> cone2Points[3] = { { 0.0f, 0.0f }, { 10.0f, 5.0f }, { 0.0f, 10.0f } };
cone2.setShape(cone2Points);
cone2.setVisible(false);
map.add(cone2);
cone3.setPosition(0, 0, 10, 10);
cone3.setOrigin(0.0f, 0.0f);
cone3.setScale(1.0f, 1.0f);
cone3.setAngle(0.0f);
cone3Painter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 0));
cone3.setPainter(cone3Painter);
const touchgfx::AbstractShape::ShapePoint<float> cone3Points[3] = { { 0.0f, 0.0f }, { 10.0f, 5.0f }, { 0.0f, 10.0f } };
cone3.setShape(cone3Points);
cone3.setVisible(false);
map.add(cone3);
cone4.setPosition(0, 0, 10, 10);
cone4.setOrigin(0.0f, 0.0f);
cone4.setScale(1.0f, 1.0f);
cone4.setAngle(0.0f);
cone4Painter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 0));
cone4.setPainter(cone4Painter);
const touchgfx::AbstractShape::ShapePoint<float> cone4Points[3] = { { 0.0f, 0.0f }, { 10.0f, 5.0f }, { 0.0f, 10.0f } };
cone4.setShape(cone4Points);
cone4.setVisible(false);
map.add(cone4);
cone5.setPosition(0, 0, 10, 10);
cone5.setOrigin(0.0f, 0.0f);
cone5.setScale(1.0f, 1.0f);
cone5.setAngle(0.0f);
cone5Painter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 0));
cone5.setPainter(cone5Painter);
const touchgfx::AbstractShape::ShapePoint<float> cone5Points[3] = { { 0.0f, 0.0f }, { 10.0f, 5.0f }, { 0.0f, 10.0f } };
cone5.setShape(cone5Points);
cone5.setVisible(false);
map.add(cone5);
cone6.setPosition(0, 0, 10, 10);
cone6.setOrigin(0.0f, 0.0f);
cone6.setScale(1.0f, 1.0f);
cone6.setAngle(0.0f);
cone6Painter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 0));
cone6.setPainter(cone6Painter);
const touchgfx::AbstractShape::ShapePoint<float> cone6Points[3] = { { 0.0f, 0.0f }, { 10.0f, 5.0f }, { 0.0f, 10.0f } };
cone6.setShape(cone6Points);
cone6.setVisible(false);
map.add(cone6);
cone7.setPosition(0, 0, 10, 10);
cone7.setOrigin(0.0f, 0.0f);
cone7.setScale(1.0f, 1.0f);
cone7.setAngle(0.0f);
cone7Painter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 0));
cone7.setPainter(cone7Painter);
const touchgfx::AbstractShape::ShapePoint<float> cone7Points[3] = { { 0.0f, 0.0f }, { 10.0f, 5.0f }, { 0.0f, 10.0f } };
cone7.setShape(cone7Points);
cone7.setVisible(false);
map.add(cone7);
cone8.setPosition(0, 0, 10, 10);
cone8.setOrigin(0.0f, 0.0f);
cone8.setScale(1.0f, 1.0f);
cone8.setAngle(0.0f);
cone8Painter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 0));
cone8.setPainter(cone8Painter);
const touchgfx::AbstractShape::ShapePoint<float> cone8Points[3] = { { 0.0f, 0.0f }, { 10.0f, 5.0f }, { 0.0f, 10.0f } };
cone8.setShape(cone8Points);
cone8.setVisible(false);
map.add(cone8);
cone9.setPosition(0, 0, 10, 10);
cone9.setOrigin(0.0f, 0.0f);
cone9.setScale(1.0f, 1.0f);
cone9.setAngle(0.0f);
cone9Painter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 0));
cone9.setPainter(cone9Painter);
const touchgfx::AbstractShape::ShapePoint<float> cone9Points[3] = { { 0.0f, 0.0f }, { 10.0f, 5.0f }, { 0.0f, 10.0f } };
cone9.setShape(cone9Points);
cone9.setVisible(false);
map.add(cone9);
ft.setPosition(0, 91, 20, 20);
ft.setOrigin(0.0f, 0.0f);
ft.setScale(1.0f, 1.0f);
ft.setAngle(0.0f);
ftPainter.setColor(touchgfx::Color::getColorFromRGB(255, 255, 255));
ft.setPainter(ftPainter);
const touchgfx::AbstractShape::ShapePoint<float> ftPoints[3] = { { 0.0f, 0.0f }, { 20.0f, 10.0f }, { 0.0f, 20.0f } };
ft.setShape(ftPoints);
map.add(ft);
driving.add(map);
add(driving);
init.setPosition(0, 0, 480, 320);
@ -232,17 +106,17 @@ AMIViewBase::AMIViewBase()
pressFront.setTypedText(touchgfx::TypedText(T___SINGLEUSE_CO7A));
init.add(pressFront);
pressB.setPosition(352, 185, 60, 23);
pressB.setColor(touchgfx::Color::getColorFromRGB(255, 255, 255));
pressB.setLinespacing(0);
pressB.setTypedText(touchgfx::TypedText(T___SINGLEUSE_A0LF));
init.add(pressB);
press2.setPosition(352, 185, 60, 23);
press2.setColor(touchgfx::Color::getColorFromRGB(255, 255, 255));
press2.setLinespacing(0);
press2.setTypedText(touchgfx::TypedText(T___SINGLEUSE_A0LF));
init.add(press2);
pressA.setPosition(352, 153, 60, 23);
pressA.setColor(touchgfx::Color::getColorFromRGB(255, 255, 255));
pressA.setLinespacing(0);
pressA.setTypedText(touchgfx::TypedText(T___SINGLEUSE_166C));
init.add(pressA);
press1.setPosition(352, 153, 60, 23);
press1.setColor(touchgfx::Color::getColorFromRGB(255, 255, 255));
press1.setLinespacing(0);
press1.setTypedText(touchgfx::TypedText(T___SINGLEUSE_166C));
init.add(press1);
textArea6.setXY(68, 184);
textArea6.setColor(touchgfx::Color::getColorFromRGB(255, 255, 255));
@ -282,7 +156,7 @@ AMIViewBase::AMIViewBase()
AMIViewBase::~AMIViewBase()
{
touchgfx::CanvasWidgetRenderer::resetBuffer();
}
void AMIViewBase::setupScreen()

View File

@ -28,14 +28,14 @@ MissionSelectViewBase::MissionSelectViewBase()
missionList.add(skidpad);
missionList.add(autox);
missionList.add(trackdrive);
missionList.add(ebs);
missionList.add(inspection);
missionList.add(autox);
missionList.add(manual);
lastLine.setWidth(480);
@ -64,10 +64,10 @@ void MissionSelectViewBase::setupScreen()
{
accel.initialize();
skidpad.initialize();
autox.initialize();
trackdrive.initialize();
ebs.initialize();
inspection.initialize();
autox.initialize();
manual.initialize();
}

View File

@ -1 +1 @@
{"remap":"yes","languages":["Gb"],"characters":[68,65,83,72,10,66,79,84,83,10,73,78,69,82,84,73,65,0,67,104,111,111,115,101,32,97,32,109,105,115,115,105,111,110,0,73,110,118,97,108,105,100,32,77,105,115,115,105,111,110,33,0,73,110,118,97,108,105,100,32,77,105,115,115,105,111,110,0,80,114,101,115,115,117,114,101,32,65,99,99,32,65,58,0,80,114,101,115,115,117,114,101,32,65,99,99,32,66,58,0,80,114,101,115,115,117,114,101,32,70,114,111,110,116,58,0,77,97,110,117,97,108,32,68,114,105,118,105,110,103,0,80,114,101,115,115,117,114,101,32,82,101,97,114,58,0,65,99,99,101,108,101,114,97,116,105,111,110,0,83,68,66,10,82,69,83,10,83,68,67,76,0,65,83,32,2,0,73,110,115,112,101,99,116,105,111,110,0,80,65,82,65,77,69,84,69,82,83,0,84,114,97,99,107,100,114,105,118,101,0,65,77,83,32,69,114,114,79,114,0,65,117,116,111,99,114,111,115,115,0,80,82,69,67,72,65,82,71,69,0,2,37,0,66,83,80,68,10,72,86,68,0,69,66,83,32,84,101,115,116,0,65,83,83,84,65,84,69,0,68,83,80,69,69,68,58,0,73,67,83,84,65,84,69,0,73,78,86,76,82,68,89,0,73,78,86,82,82,68,89,0,77,73,83,83,73,79,78,0,77,83,80,69,69,68,58,0,82,50,68,80,82,79,71,0,83,107,105,100,112,97,100,0,84,83,83,84,65,84,69,0,66,82,65,75,69,83,0,84,83,86,66,65,84,0,84,83,86,86,69,72,0,10,10,65,77,83,0,10,10,73,77,68,0,10,10,80,68,85,0,68,65,78,71,58,0,69,82,82,79,82,0,76,86,83,79,67,0,77,65,78,71,58,0,83,80,69,69,68,0,84,83,83,79,67,0,66,66,65,76,0,73,78,73,84,0,76,65,80,83,0,84,77,65,88,0,84,83,77,83,0,84,84,70,76,0,84,84,70,82,0,84,84,82,76,0,84,84,82,82,0,86,77,73,78,0,65,67,67,0,73,78,86,0,73,84,83,0,82,50,68,0,83,67,83,0,83,68,67,0,76,86,0],"copy_translations_to_ram":"no"}
{"remap":"yes","languages":["Gb"],"characters":[68,65,83,72,10,66,79,84,83,10,73,78,69,82,84,73,65,0,67,104,111,111,115,101,32,97,32,109,105,115,115,105,111,110,0,73,110,118,97,108,105,100,32,77,105,115,115,105,111,110,33,0,73,110,118,97,108,105,100,32,77,105,115,115,105,111,110,0,80,114,101,115,115,117,114,101,32,65,99,99,32,49,58,0,80,114,101,115,115,117,114,101,32,65,99,99,32,50,58,0,80,114,101,115,115,117,114,101,32,70,114,111,110,116,58,0,77,97,110,117,97,108,32,68,114,105,118,105,110,103,0,80,114,101,115,115,117,114,101,32,82,101,97,114,58,0,65,99,99,101,108,101,114,97,116,105,111,110,0,83,68,66,10,82,69,83,10,83,68,67,76,0,65,83,32,2,0,73,110,115,112,101,99,116,105,111,110,0,80,65,82,65,77,69,84,69,82,83,0,84,114,97,99,107,100,114,105,118,101,0,65,77,83,32,69,114,114,79,114,0,65,117,116,111,99,114,111,115,115,0,80,82,69,67,72,65,82,71,69,0,2,37,0,66,83,80,68,10,72,86,68,0,69,66,83,32,84,101,115,116,0,65,83,83,84,65,84,69,0,68,83,80,69,69,68,58,0,73,67,83,84,65,84,69,0,73,78,86,76,82,68,89,0,73,78,86,82,82,68,89,0,77,73,83,83,73,79,78,0,77,83,80,69,69,68,58,0,82,50,68,80,82,79,71,0,83,107,105,100,112,97,100,0,84,83,83,84,65,84,69,0,66,82,65,75,69,83,0,84,83,86,66,65,84,0,84,83,86,86,69,72,0,10,10,65,77,83,0,10,10,73,77,68,0,10,10,80,68,85,0,68,65,78,71,58,0,69,82,82,79,82,0,76,86,83,79,67,0,77,65,78,71,58,0,83,80,69,69,68,0,84,83,83,79,67,0,66,66,65,76,0,73,78,73,84,0,76,65,80,83,0,84,77,65,88,0,84,83,77,83,0,84,84,70,76,0,84,84,70,82,0,84,84,82,76,0,84,84,82,82,0,86,77,73,78,0,65,67,67,0,73,78,86,0,73,84,83,0,82,50,68,0,83,67,83,0,83,68,67,0,76,86,0],"copy_translations_to_ram":"no"}

View File

@ -64,8 +64,8 @@ KEEP extern const touchgfx::Unicode::UnicodeChar texts_all_languages[] TEXT_LOCA
0x43, 0x68, 0x6f, 0x6f, 0x73, 0x65, 0x20, 0x61, 0x20, 0x6d, 0x69, 0x73, 0x73, 0x69, 0x6f, 0x6e, 0x0, // @18 "Choose a mission"
0x49, 0x6e, 0x76, 0x61, 0x6c, 0x69, 0x64, 0x20, 0x4d, 0x69, 0x73, 0x73, 0x69, 0x6f, 0x6e, 0x21, 0x0, // @35 "Invalid Mission!"
0x49, 0x6e, 0x76, 0x61, 0x6c, 0x69, 0x64, 0x20, 0x4d, 0x69, 0x73, 0x73, 0x69, 0x6f, 0x6e, 0x0, // @52 "Invalid Mission"
0x50, 0x72, 0x65, 0x73, 0x73, 0x75, 0x72, 0x65, 0x20, 0x41, 0x63, 0x63, 0x20, 0x41, 0x3a, 0x0, // @68 "Pressure Acc A:"
0x50, 0x72, 0x65, 0x73, 0x73, 0x75, 0x72, 0x65, 0x20, 0x41, 0x63, 0x63, 0x20, 0x42, 0x3a, 0x0, // @84 "Pressure Acc B:"
0x50, 0x72, 0x65, 0x73, 0x73, 0x75, 0x72, 0x65, 0x20, 0x41, 0x63, 0x63, 0x20, 0x31, 0x3a, 0x0, // @68 "Pressure Acc 1:"
0x50, 0x72, 0x65, 0x73, 0x73, 0x75, 0x72, 0x65, 0x20, 0x41, 0x63, 0x63, 0x20, 0x32, 0x3a, 0x0, // @84 "Pressure Acc 2:"
0x50, 0x72, 0x65, 0x73, 0x73, 0x75, 0x72, 0x65, 0x20, 0x46, 0x72, 0x6f, 0x6e, 0x74, 0x3a, 0x0, // @100 "Pressure Front:"
0x4d, 0x61, 0x6e, 0x75, 0x61, 0x6c, 0x20, 0x44, 0x72, 0x69, 0x76, 0x69, 0x6e, 0x67, 0x0, // @116 "Manual Driving"
0x50, 0x72, 0x65, 0x73, 0x73, 0x75, 0x72, 0x65, 0x20, 0x52, 0x65, 0x61, 0x72, 0x3a, 0x0, // @131 "Pressure Rear:"

View File

@ -31,7 +31,7 @@ public:
void setMission(Mission mission);
void setASState(ASState state);
void setIniChkState(IniChkState state);
void setIniChkState(InitialCheckupState state);
void updateDataFields();
void setJetsonTimeout(bool timeout);
@ -52,8 +52,6 @@ protected:
touchgfx::Unicode::UnicodeChar progressBuffer[16];
touchgfx::Unicode::UnicodeChar asOKBuffer[16];
touchgfx::Shape<3> cones[NUM_CONES] = {cone0, cone1, cone2, cone3, cone4,
cone5, cone6, cone7, cone8, cone9};
};
#endif // AMIVIEW_HPP

View File

@ -9,17 +9,86 @@
#include "util.h"
CountedEnum(DataFieldType, size_t, DF_TSState, DF_ASState, DF_ActiveMission,
DF_R2DProgress, DF_INVLReady, DF_INVRReady, DF_SDC, DF_ERR,
DF_IniChkState, DF_LapCount, DF_TireTempFL, DF_TireTempFR,
DF_TireTempRL, DF_TireTempRR, DF_MinCellVolt, DF_MaxCellTemp,
DF_TSSoC, DF_LVSoC, DF_TSCurrent, DF_TSVoltageBat, DF_TSVoltageVeh,
DF_Speed, DF_BBal, DF_BPF, DF_BPR, DF_DistanceTotal, DF_TempMotL,
DF_TempMotR, DF_TempInvL, DF_TempInvR, DF_TempBrakeFL,
DF_TempBrakeFR, DF_TempBrakeRL, DF_TempBrakeRR, DF_LapBest,
DF_LapLast, DF_LVBatVoltage, DF_GitBuildHash);
// clang-format off
CountedEnum(DataFieldType, size_t,
DF_SlavePanicID,
DF_SlavePanicKind,
DF_SlavePanicArg,
DF_TSState,
DF_SDCClosed,
DF_TSSoC,
DF_MinCellVolt,
DF_MaxCellTemp,
DF_IMDok,
DF_TSALgreen,
DF_IMDerr,
DF_AMSerr,
DF_AMSLastErrorKind,
DF_AMSLastErrorArg,
DF_DCDCTemp,
DF_DCDCCurrent,
DF_TSCurrent,
DF_TSVoltageBat,
DF_TSVoltageVeh,
DF_ShuntTemp,
DF_TireTempFL,
DF_TireTempFR,
DF_TireTempRL,
DF_TireTempRR,
DF_BrakeTempFL,
DF_BrakeTempFR,
DF_BrakeTempRL,
DF_BrakeTempRR,
DF_Inv1Temp,
DF_Inv2Temp,
DF_Mot1Temp,
DF_Mot2Temp,
DF_LapBest,
DF_LapLast,
DF_SectorBest,
DF_SectorLast,
DF_WSSFL,
DF_WSSFR,
DF_WSSRL,
DF_WSSRR,
DF_DistanceSession,
DF_TankPressure1,
DF_TankPressure2,
DF_APPSPercent,
DF_BPF,
DF_BPR,
DF_SteeringAngle,
DF_Speed,
DF_LapCount,
DF_SectorCount,
DF_R2DProgress,
DF_ERR,
DF_SDCStatus,
DF_INV1Ready,
DF_INV2Ready,
DF_EnergyPerLap,
DF_IniChkState,
DF_ActiveMission,
DF_ASState,
DF_Inv1Velocity,
DF_Inv2Velocity,
DF_Inv1TorqueDemanded,
DF_Inv2TorqueDemanded,
DF_Inv1TorqueDesired,
DF_Inv2TorqueDesired,
DF_Inv1ControlWord,
DF_Inv2ControlWord,
DF_Inv1TorqueActual,
DF_Inv2TorqueActual,
DF_Inv1Errors,
DF_Inv2Errors,
DF_Inv1Warnings,
DF_Inv2Warnings,
DF_GitBuildHash,
);
// clang-format on
enum class NamedFieldKind { Float, Bool, Text, Int };
enum class NamedFieldKind { Float, Bool, Text, Int, Hex };
struct NamedFieldDescription {
NamedFieldKind kind;
@ -72,6 +141,7 @@ private:
void setFloatValue(float floatValue);
void setBoolValue(int boolValue);
void setIntValue(int intValue);
void setHexValue(int hexValue);
void setStrValue(const char *strValue);
void updateValueBuffer();

View File

@ -16,26 +16,16 @@ void AMIPresenter::deactivate() {}
void AMIPresenter::vehicleStateUpdated() {
view.setMission(vehicle_state.active_mission);
view.setASState(vehicle_state.as_state);
view.setIniChkState(vehicle_state.ini_chk_state);
view.setIniChkState(vehicle_state.initial_checkup_state);
view.updateDataFields();
#ifndef SIMULATOR
view.setJetsonTimeout(HAL_GetTick() - vehicle_state.last_jetson_msg > 500);
view.setEPSCTimeout(HAL_GetTick() - vehicle_state.last_epsc_msg > 500);
// TODO
// view.setJetsonTimeout(HAL_GetTick() - vehicle_state.last_jetson_msg > 500);
// view.setEPSCTimeout(HAL_GetTick() - vehicle_state.last_epsc_msg > 500);
#endif
size_t cone_count = 0;
for (; cone_count < NUM_CONES; cone_count++) {
// A cone position of 0xFF/0xFF indicates that there are no more cones
if (vehicle_state.cone_pos[cone_count].x == 0xFF &&
vehicle_state.cone_pos[cone_count].y == 0xFF) {
break;
}
}
view.setConePositions(vehicle_state.cone_pos, cone_count);
}
void AMIPresenter::nextScreen() {
FrontendApplication *app =
static_cast<FrontendApplication *>(FrontendApplication::getInstance());
FrontendApplication *app = static_cast<FrontendApplication *>(FrontendApplication::getInstance());
app->gotoSDCScreenNoTransition();
}

View File

@ -10,9 +10,7 @@
#include "touchgfx/widgets/TextAreaWithWildcard.hpp"
#include "vehicle_state.h"
AMIDataField::AMIDataField(touchgfx::TextAreaWithOneWildcard &textArea,
const char *fmt)
: fmt(fmt), textArea(textArea) {}
AMIDataField::AMIDataField(touchgfx::TextAreaWithOneWildcard &textArea, const char *fmt) : fmt(fmt), textArea(textArea) {}
void AMIDataField::setValue(float value) {
Unicode::snprintfFloat(buffer, sizeof(buffer) / sizeof(*buffer), fmt, value);
@ -21,12 +19,9 @@ void AMIDataField::setValue(float value) {
}
AMIView::AMIView()
: AMIViewBase(), paField(pressA, "%5.1f"), pbField(pressB, "%5.1f"),
pfField(pressFront, "%5.1f"), prField(pressRear, "%5.1f"),
desiredAngleField(desiredAngle, "%5.2f"),
measuredAngleField(measuredAngle, "%5.2f"),
desiredSpeedField(desiredSpeed, "%5.1f"),
measuredSpeedField(measuredSpeed, "%5.1f") {}
: AMIViewBase(), paField(press1, "%5.1f"), pbField(press1, "%5.1f"), pfField(pressFront, "%5.1f"),
prField(pressRear, "%5.1f"), desiredAngleField(desiredAngle, "%5.2f"), measuredAngleField(measuredAngle, "%5.2f"),
desiredSpeedField(desiredSpeed, "%5.1f"), measuredSpeedField(measuredSpeed, "%5.1f") {}
void AMIView::setupScreen() { AMIViewBase::setupScreen(); }
@ -34,29 +29,29 @@ void AMIView::tearDownScreen() { AMIViewBase::tearDownScreen(); }
void AMIView::setMission(Mission mission) {
switch (mission) {
case MISSION_ACCEL:
currentMission.setTypedText(TypedText(T_ACCEL_HUGE));
break;
case MISSION_SKIDPAD:
currentMission.setTypedText(TypedText(T_SKIDPAD_HUGE));
break;
case MISSION_AUTOX:
currentMission.setTypedText(TypedText(T_AUTOX_HUGE));
break;
case MISSION_TRACKDRIVE:
currentMission.setTypedText(TypedText(T_TRACKDRIVE_HUGE));
break;
case MISSION_EBS:
currentMission.setTypedText(TypedText(T_EBS_HUGE));
break;
case MISSION_INSPECTION:
currentMission.setTypedText(TypedText(T_INSPECTION_HUGE));
break;
case MISSION_MANUAL:
case MISSION_NONE:
default:
currentMission.setTypedText(TypedText(T_INVALID_HUGE));
break;
case MISSION_ACCEL:
currentMission.setTypedText(TypedText(T_ACCEL_HUGE));
break;
case MISSION_SKIDPAD:
currentMission.setTypedText(TypedText(T_SKIDPAD_HUGE));
break;
case MISSION_AUTOX:
currentMission.setTypedText(TypedText(T_AUTOX_HUGE));
break;
case MISSION_TRACKDRIVE:
currentMission.setTypedText(TypedText(T_TRACKDRIVE_HUGE));
break;
case MISSION_BRAKETEST:
currentMission.setTypedText(TypedText(T_EBS_HUGE));
break;
case MISSION_INSPECTION:
currentMission.setTypedText(TypedText(T_INSPECTION_HUGE));
break;
case MISSION_MANUAL:
case MISSION_NONE:
default:
currentMission.setTypedText(TypedText(T_INVALID_HUGE));
break;
}
currentMission.invalidate();
}
@ -73,7 +68,7 @@ void AMIView::setASState(ASState state) {
driving.invalidate();
}
void AMIView::setIniChkState(IniChkState state) {
void AMIView::setIniChkState(InitialCheckupState state) {
if (state == INICHK_ERROR) {
progressBar.setColor(DriverViewStatusItem::COLOR_ERROR);
progressBar.setValue(100);
@ -83,36 +78,35 @@ void AMIView::setIniChkState(IniChkState state) {
progressBar.setValue(100);
} else {
progressBar.setColor(DriverViewStatusItem::COLOR_OK);
float prog = ((float)vehicle_state.ini_chk_state) / INICHK_DONE;
float prog = ((float)vehicle_state.initial_checkup_state) / INICHK_DONE;
progressBar.setValue(prog * 100);
}
}
progressBar.invalidate();
const char *label = inichkstate_str(state);
touchgfx::Unicode::strncpy(progressBuffer, label,
sizeof(progressBuffer) / sizeof(*progressBuffer));
touchgfx::Unicode::strncpy(progressBuffer, label, sizeof(progressBuffer) / sizeof(*progressBuffer));
progressLabel.setWildcard(progressBuffer);
progressLabel.invalidate();
}
void AMIView::updateDataFields() {
paField.setValue(vehicle_state.hyd_press_a);
pbField.setValue(vehicle_state.hyd_press_b);
pfField.setValue(vehicle_state.brake_press_f);
prField.setValue(vehicle_state.brake_press_r);
paField.setValue(vehicle_state.tank_pressure_1);
pbField.setValue(vehicle_state.tank_pressure_2);
pfField.setValue(vehicle_state.brake_pressure_f);
prField.setValue(vehicle_state.brake_pressure_r);
desiredAngleField.setValue(vehicle_state.desired_angle);
measuredAngleField.setValue(vehicle_state.measured_angle);
desiredSpeedField.setValue(vehicle_state.desired_speed);
measuredSpeedField.setValue(vehicle_state.speed);
// TODO
// desiredAngleField.setValue(vehicle_state.desired_angle);
// measuredAngleField.setValue(vehicle_state.measured_angle);
// desiredSpeedField.setValue(vehicle_state.desired_speed);
// measuredSpeedField.setValue(vehicle_state.speed);
}
void AMIView::setJetsonTimeout(bool timeout) {
if (timeout) {
desiredAngle.setColor(touchgfx::Color::getColorFromRGB(0xFF, 0, 0));
touchgfx::Unicode::fromUTF8((const uint8_t *)"TIMEOUT", asOKBuffer,
sizeof(asOKBuffer) / sizeof(*asOKBuffer));
touchgfx::Unicode::fromUTF8((const uint8_t *)"TIMEOUT", asOKBuffer, sizeof(asOKBuffer) / sizeof(*asOKBuffer));
asOK.setWildcard(asOKBuffer);
} else {
desiredAngle.setColor(touchgfx::Color::getColorFromRGB(0xFF, 0xFF, 0xFF));
@ -126,16 +120,3 @@ void AMIView::setEPSCTimeout(bool timeout) {
measuredAngle.setColor(touchgfx::Color::getColorFromRGB(0xFF, 0xFF, 0xFF));
}
}
void AMIView::setConePositions(ConePosition *cone_positions, size_t count) {
for (size_t i = 0; i < count; i++) {
cones[i].setX(cone_positions[i].x);
cones[i].setY(cone_positions[i].y);
cones[i].setVisible(true);
cones[i].invalidate();
}
for (size_t i = count; i < NUM_CONES; i++) {
cones[i].setVisible(false);
cones[i].invalidate();
}
}

View File

@ -15,321 +15,331 @@
#ifndef COMPILER_GIT_BUILD_HASH
#define COMPILER_GIT_BUILD_HASH "git id not found"
#endif
static const char* git_hash = STRINGIZE(COMPILER_GIT_BUILD_HASH);
static const char *git_hash = STRINGIZE(COMPILER_GIT_BUILD_HASH);
#define VEH_FIELD(FIELD) []() { return (void *)&vehicle_state.FIELD; }
#define VEH_BIT_FIELD(FIELD) \
[]() { \
static int x; \
x = vehicle_state.FIELD; \
return (void *)&x; \
#define VEH_BIT_FIELD(FIELD) \
[]() { \
static int x; \
x = vehicle_state.FIELD; \
return (void *)&x; \
}
void *get_tsstate_text()
{
void *get_slave_panic_kind_text() {
const char *text;
switch (vehicle_state.ts_state)
{
case TS_INACTIVE:
text = "INACT";
break;
case TS_ACTIVE:
text = "ACT";
break;
case TS_PRECHARGE:
text = "PRECH";
break;
case TS_DISCHARGE:
text = "DISCH";
break;
case TS_ERROR:
text = "ERROR";
break;
case TS_CHARGING_CHECK:
text = "CH_CHK";
break;
case TS_CHARGING:
text = "CH";
break;
default:
text = "UNKNOWN";
switch (vehicle_state.last_ams_slave_panic.kind) {
case AMS_SLAVEPANIC_OVERTEMP:
text = "OV_TEMP";
break;
case AMS_SLAVEPANIC_UNDERTEMP:
text = "UN_TEMP";
break;
case AMS_SLAVEPANIC_OVERVOLTAGE:
text = "OV_VOLT";
break;
case AMS_SLAVEPANIC_UNDERVOLTAGE:
text = "UN_VOLT";
break;
case AMS_SLAVEPANIC_TOO_FEW_TEMP:
text = "FEWTEMP";
break;
case AMS_SLAVEPANIC_OPENWIRE:
text = "O_WIRE";
break;
default:
text = "UNKNOWN";
}
return (void *)text;
}
void *get_asstate_text()
{
void *get_ams_error_kind_text() {
const char *text;
switch (vehicle_state.as_state)
{
case AS_OFF:
text = "OFF";
break;
case AS_MANUAL:
text = "MAN";
break;
case AS_READY:
text = "RDY";
break;
case AS_DRIVING:
text = "DRIVE";
break;
case AS_FINISHED:
text = "FIN";
break;
case AS_EMERGENCY:
text = "EMERG";
break;
default:
text = "UNKNOWN";
switch (vehicle_state.last_ams_slave_panic.kind) {
case AMS_ERROR_NONE:
text = "NONE";
break;
case AMS_ERROR_SLAVE_TIMEOUT:
text = "SlTout";
break;
case AMS_ERROR_SHUNT_TIMEOUT:
text = "ShTout";
break;
case AMS_ERROR_SHUNT_OVERCURRENT:
text = "ShOCurr";
break;
case AMS_ERROR_SHUNT_OVERTEMP:
text = "ShOTp";
break;
default:
text = "UNKNOWN";
}
return (void *)text;
}
void *get_mission_text()
{
void *get_tsstate_text() {
const char *text;
switch (vehicle_state.active_mission)
{
case MISSION_NONE:
text = "NONE";
break;
case MISSION_ACCEL:
text = "ACCEL";
break;
case MISSION_SKIDPAD:
text = "SKIDPAD";
break;
case MISSION_AUTOX:
text = "AUTOX";
break;
case MISSION_TRACKDRIVE:
text = "TRACK";
break;
case MISSION_EBS:
text = "EBS";
break;
case MISSION_INSPECTION:
text = "INSPECT";
break;
case MISSION_MANUAL:
text = "MAN";
break;
default:
text = "UNKNOWN";
switch (vehicle_state.ts_state) {
case TS_INACTIVE:
text = "INACT";
break;
case TS_ACTIVE:
text = "ACT";
break;
case TS_PRECHARGE:
text = "PRECH";
break;
case TS_DISCHARGE:
text = "DISCH";
break;
case TS_ERROR:
text = "ERROR";
break;
case TS_CHARGING_CHECK:
text = "CH_CHK";
break;
case TS_CHARGING:
text = "CH";
break;
default:
text = "UNKNOWN";
}
return (void *)text;
}
void *get_r2dprog_text()
{
void *get_asstate_text() {
const char *text;
switch (vehicle_state.r2d_progress)
{
case R2D_NONE:
text = "NONE";
break;
case R2D_TSMS:
text = "TSMS";
break;
case R2D_TSACTIVE:
text = "TSACT";
break;
case R2D_RESETTING_NODES:
text = "RST NODE";
break;
case R2D_RESETTING_COMMS:
text = "RST COM";
break;
case R2D_WAITING_INIT:
text = "WAIT INIT";
break;
case R2D_INIT_STAGE1:
text = "INIT S1";
break;
case R2D_INIT_STAGE2:
text = "INIT S2";
break;
case R2D_INIT_SUCCESS:
text = "INIT SUCC";
break;
default:
text = "UNKNOWN";
switch (vehicle_state.as_state) {
case AS_OFF:
text = "OFF";
break;
case AS_MANUAL:
text = "MAN";
break;
case AS_READY:
text = "RDY";
break;
case AS_DRIVING:
text = "DRIVE";
break;
case AS_FINISHED:
text = "FIN";
break;
case AS_EMERGENCY:
text = "EMERG";
break;
default:
text = "UNKNOWN";
}
return (void *)text;
}
void *get_inichk_text()
{
return (void *)inichkstate_str(vehicle_state.ini_chk_state);
}
void *get_sdc_text()
{
void *get_mission_text() {
const char *text;
if (vehicle_state.errors.sdc_bfl)
{
text = "BFL";
}
else if (vehicle_state.errors.sdc_brl)
{
text = "BRL";
}
else if (vehicle_state.errors.sdc_acc)
{
text = "ACC";
}
else if (vehicle_state.errors.sdc_hvb)
{
text = "HVB";
}
else
{
text = "CLOSED";
switch (vehicle_state.active_mission) {
case MISSION_NONE:
text = "NONE";
break;
case MISSION_ACCEL:
text = "ACCEL";
break;
case MISSION_SKIDPAD:
text = "SKIDPAD";
break;
case MISSION_AUTOX:
text = "AUTOX";
break;
case MISSION_TRACKDRIVE:
text = "TRACK";
break;
case MISSION_BRAKETEST:
text = "EBS";
break;
case MISSION_INSPECTION:
text = "INSPECT";
break;
case MISSION_MANUAL:
text = "MAN";
break;
default:
text = "UNKNOWN";
}
return (void *)text;
}
void *get_err_text()
{
void *get_r2dprog_text() {
const char *text;
if (vehicle_state.errors.err_sdc)
{
text = "SDC";
switch (vehicle_state.r2d_progress) {
case R2D_NONE:
text = "NONE";
break;
case R2D_SDC_CLOSED:
text = "SDC CL";
break;
case R2D_TSACTIVE:
text = "TSACT";
break;
case R2D_RESETTING_NODES:
text = "RST NODE";
break;
case R2D_RESETTING_COMMS:
text = "RST COM";
break;
case R2D_WAITING_INIT:
text = "WAIT INIT";
break;
case R2D_INIT_STAGE1:
text = "INIT S1";
break;
case R2D_INIT_STAGE2:
text = "INIT S2";
break;
case R2D_INIT_SUCCESS:
text = "INIT SUCC";
break;
default:
text = "UNKNOWN";
}
else if (vehicle_state.errors.err_ams)
{
text = "AMS";
}
else if (vehicle_state.errors.err_pdu)
{
return (void *)text;
}
void *get_inichk_text() { return (void *)inichkstate_str(vehicle_state.initial_checkup_state); }
void *get_sdc_text() {
const char *text;
// if (vehicle_state.errors.sdc_bfl) {
// text = "BFL";
// } else if (vehicle_state.errors.sdc_brl) {
// text = "BRL";
// } else if (vehicle_state.errors.sdc_acc) {
// text = "ACC";
// } else if (vehicle_state.errors.sdc_hvb) {
// text = "HVB";
// } else {
// text = "CLOSED";
// }
// TODO
text = "NA";
return (void *)text;
}
void *get_err_text() {
const char *text;
if (vehicle_state.errors.err_pdu) {
text = "PDU";
}
else if (vehicle_state.errors.err_ini_chk)
{
text = "IniChk";
}
else if (vehicle_state.errors.err_con_mon)
{
text = "ConMon";
}
else if (vehicle_state.errors.err_scs)
{
text = "SCS";
}
else if (vehicle_state.errors.err_sbspd)
{
text = "sBSPD";
}
else if (vehicle_state.errors.err_appsp)
{
text = "APPSp";
}
else if (vehicle_state.errors.err_as)
{
text = "AS";
}
else if (vehicle_state.errors.err_ros)
{
text = "ROS";
}
else if (vehicle_state.errors.err_res)
{
} else if (vehicle_state.errors.err_res) {
text = "RES";
}
else if (vehicle_state.errors.err_invl)
{
text = "INVL";
}
else if (vehicle_state.errors.err_invr)
{
text = "INVR";
}
else
{
} else if (vehicle_state.errors.err_as) {
text = "AS";
} else if (vehicle_state.errors.err_apps_plausible) {
text = "APPSp";
} else if (vehicle_state.errors.err_soft_bspd) {
text = "sBSPD";
} else if (vehicle_state.errors.err_scs) {
text = "SCS";
} else if (vehicle_state.errors.err_con_mon) {
text = "ConMon";
} else if (vehicle_state.errors.err_initial_checkup) {
text = "IniChk";
} else if (vehicle_state.errors.err_inv_1) {
text = "INV1";
} else if (vehicle_state.errors.err_inv_2) {
text = "INV2";
} else if (vehicle_state.errors.err_ams) {
text = "AMS";
} else if (vehicle_state.errors.err_sdc) {
text = "SDC";
} else {
text = "NONE";
}
return (void *)text;
}
void *get_compiler_build_hash()
{
return (void *)git_hash;
}
void *get_compiler_build_hash() { return (void *)git_hash; }
void *get_zero()
{
void *get_zero() {
static float zero = 0.0f;
return &zero;
}
// max title length: 7 characters (limited by width of field select dropdown)
NamedFieldDescription dataFieldDescs[] = {
[DF_SlavePanicID] = {NamedFieldKind::Int, "TSSPID", 2, 0, VEH_FIELD(last_ams_slave_panic.id)},
[DF_SlavePanicKind] = {NamedFieldKind::Text, "TSSPKIN", 1, 0, get_slave_panic_kind_text},
[DF_SlavePanicArg] = {NamedFieldKind::Hex, "TSSPARG", 1, 0, VEH_FIELD(last_ams_slave_panic.arg)},
[DF_TSState] = {NamedFieldKind::Text, "TSSTATE", 1, 0, get_tsstate_text},
[DF_ASState] = {NamedFieldKind::Text, "ASSTATE", 1, 0, get_asstate_text},
[DF_ActiveMission] = {NamedFieldKind::Text, "MISSION", 1, 0,
get_mission_text},
[DF_R2DProgress] = {NamedFieldKind::Text, "R2DPROG", 1, 0,
get_r2dprog_text},
[DF_INVLReady] = {NamedFieldKind::Bool, "INVLRDY", 0, 0,
VEH_BIT_FIELD(errors.invl_ready)},
[DF_INVRReady] = {NamedFieldKind::Bool, "INVRRDY", 0, 0,
VEH_BIT_FIELD(errors.invr_ready)},
[DF_SDC] = {NamedFieldKind::Text, "SDC", 0, 0, get_sdc_text},
[DF_ERR] = {NamedFieldKind::Text, "ERROR", 0, 0, get_err_text},
[DF_IniChkState] = {NamedFieldKind::Text, "ICSTATE", 1, 0, get_inichk_text},
[DF_LapCount] = {NamedFieldKind::Int, "LAPS", 3, 0, VEH_FIELD(lap_count)},
[DF_TireTempFL] = {NamedFieldKind::Float, "TTFL", 2, 1,
VEH_FIELD(temps.tire_fl)},
[DF_TireTempFR] = {NamedFieldKind::Float, "TTFR", 2, 1,
VEH_FIELD(temps.tire_fr)},
[DF_TireTempRL] = {NamedFieldKind::Float, "TTRL", 2, 1,
VEH_FIELD(temps.tire_rl)},
[DF_TireTempRR] = {NamedFieldKind::Float, "TTRR", 2, 1,
VEH_FIELD(temps.tire_rr)},
[DF_MinCellVolt] = {NamedFieldKind::Float, "VMIN", 1, 2,
VEH_FIELD(min_cell_volt)},
[DF_MaxCellTemp] = {NamedFieldKind::Float, "TBAT", 2, 1,
VEH_FIELD(max_cell_temp)},
[DF_TSSoC] = {NamedFieldKind::Int, "TSSOC", 3, 0, VEH_FIELD(soc_ts)},
[DF_LVSoC] = {NamedFieldKind::Int, "LVSOC", 3, 0, VEH_FIELD(soc_lv)},
[DF_TSCurrent] = {NamedFieldKind::Float, "ITS", 3, 0,
VEH_FIELD(ts_current)},
[DF_TSVoltageBat] = {NamedFieldKind::Float, "TSVBAT", 3, 1,
VEH_FIELD(ts_voltage_bat)},
[DF_TSVoltageVeh] = {NamedFieldKind::Float, "TSVVEH", 3, 1,
VEH_FIELD(ts_voltage_veh)},
[DF_SDCClosed] = {NamedFieldKind::Bool, "SDCCLOS", 0, 0, VEH_FIELD(sdc_closed)},
[DF_TSSoC] = {NamedFieldKind::Int, "TS SoC", 3, 0, VEH_FIELD(soc_ts)},
[DF_MinCellVolt] = {NamedFieldKind::Float, "VMIN", 1, 2, VEH_FIELD(min_cell_volt)},
[DF_MaxCellTemp] = {NamedFieldKind::Float, "TBAT", 2, 1, VEH_FIELD(max_cell_temp)},
[DF_IMDok] = {NamedFieldKind::Bool, "IMD ok", 0, 0, VEH_FIELD(imd_ok)},
[DF_TSALgreen] = {NamedFieldKind::Bool, "TSAL gr", 0, 0, VEH_FIELD(tsal_green)},
[DF_IMDerr] = {NamedFieldKind::Bool, "IMD err", 0, 0, VEH_FIELD(imd_error)},
[DF_AMSerr] = {NamedFieldKind::Bool, "AMS err", 0, 0, VEH_FIELD(ams_error)},
[DF_AMSLastErrorKind] = {NamedFieldKind::Text, "AMSeKIN", 1, 0, get_ams_error_kind_text},
[DF_AMSLastErrorArg] = {NamedFieldKind::Hex, "AMSeARG", 1, 0, VEH_FIELD(last_ams_error.arg)},
[DF_DCDCTemp] = {NamedFieldKind::Float, "TDCDC", 2, 2, VEH_FIELD(dcdc_temp)},
[DF_DCDCCurrent] = {NamedFieldKind::Float, "DCDCCur", 2, 2, VEH_FIELD(dcdc_current)},
[DF_TSCurrent] = {NamedFieldKind::Float, "I_TS", 3, 0, VEH_FIELD(ts_current)},
[DF_TSVoltageBat] = {NamedFieldKind::Float, "TSVBAT", 3, 1, VEH_FIELD(ts_voltage_bat)},
[DF_TSVoltageVeh] = {NamedFieldKind::Float, "TSVVEH", 3, 1, VEH_FIELD(ts_voltage_veh)},
[DF_ShuntTemp] = {NamedFieldKind::Float, "TShunt", 3, 1, VEH_FIELD(shunt_temperature)},
[DF_TireTempFL] = {NamedFieldKind::Float, "TTFL", 2, 1, VEH_FIELD(temps.tire_fl)},
[DF_TireTempFR] = {NamedFieldKind::Float, "TTFR", 2, 1, VEH_FIELD(temps.tire_fr)},
[DF_TireTempRL] = {NamedFieldKind::Float, "TTRL", 2, 1, VEH_FIELD(temps.tire_rl)},
[DF_TireTempRR] = {NamedFieldKind::Float, "TTRR", 2, 1, VEH_FIELD(temps.tire_rr)},
[DF_BrakeTempFL] = {NamedFieldKind::Float, "TBFL", 3, 0, VEH_FIELD(temps.brake_fl)},
[DF_BrakeTempFR] = {NamedFieldKind::Float, "TBFR", 3, 0, VEH_FIELD(temps.brake_fr)},
[DF_BrakeTempRL] = {NamedFieldKind::Float, "TBRL", 3, 0, VEH_FIELD(temps.brake_rl)},
[DF_BrakeTempRR] = {NamedFieldKind::Float, "TBRR", 3, 0, VEH_FIELD(temps.brake_rr)},
[DF_Inv1Temp] = {NamedFieldKind::Float, "TINV1", 2, 1, VEH_FIELD(temps.inv_1)},
[DF_Inv2Temp] = {NamedFieldKind::Float, "TINV2", 2, 1, VEH_FIELD(temps.inv_2)},
[DF_Mot1Temp] = {NamedFieldKind::Float, "TMOT1", 2, 1, VEH_FIELD(temps.mot_1)},
[DF_Mot2Temp] = {NamedFieldKind::Float, "TMOT2", 2, 1, VEH_FIELD(temps.mot_2)},
[DF_LapBest] = {NamedFieldKind::Float, "LAPBEST", 3, 1, VEH_FIELD(lap_time_best)},
[DF_LapLast] = {NamedFieldKind::Float, "LAPLAST", 3, 1, VEH_FIELD(lap_time_last)},
[DF_SectorBest] = {NamedFieldKind::Float, "SECBEST", 3, 1, VEH_FIELD(sector_time_best)},
[DF_SectorLast] = {NamedFieldKind::Float, "SECLAST", 3, 1, VEH_FIELD(sector_time_last)},
[DF_WSSFL] = {NamedFieldKind::Float, "WSSFL", 3, 1, VEH_FIELD(wheel_speeds.wss_fl)},
[DF_WSSFR] = {NamedFieldKind::Float, "WSSFR", 3, 1, VEH_FIELD(wheel_speeds.wss_fr)},
[DF_WSSRL] = {NamedFieldKind::Float, "WSSRL", 3, 1, VEH_FIELD(wheel_speeds.wss_rl)},
[DF_WSSRR] = {NamedFieldKind::Float, "WSSRR", 3, 1, VEH_FIELD(wheel_speeds.wss_rr)},
[DF_DistanceSession] = {NamedFieldKind::Float, "DIST", 3, 1, VEH_FIELD(distance_session)},
[DF_TankPressure1] = {NamedFieldKind::Float, "TnkPrs1", 3, 1, VEH_FIELD(tank_pressure_1)},
[DF_TankPressure2] = {NamedFieldKind::Float, "TnkPrs2", 3, 1, VEH_FIELD(tank_pressure_2)},
[DF_APPSPercent] = {NamedFieldKind::Int, "APPS", 3, 0, VEH_FIELD(apps_percent)},
[DF_BPF] = {NamedFieldKind::Float, "BPF", 3, 1, VEH_FIELD(brake_pressure_f)},
[DF_BPR] = {NamedFieldKind::Float, "BPR", 3, 1, VEH_FIELD(brake_pressure_r)},
[DF_SteeringAngle] = {NamedFieldKind::Int, "SAS", 3, 0, VEH_FIELD(steering_angle)},
[DF_Speed] = {NamedFieldKind::Float, "SPEED", 3, 0, VEH_FIELD(speed)},
[DF_BBal] = {NamedFieldKind::Float, "BBAL", 3, 1, get_zero},
[DF_BPF] = {NamedFieldKind::Float, "BPF", 3, 1, VEH_FIELD(brake_press_f)},
[DF_BPR] = {NamedFieldKind::Float, "BPR", 3, 1, VEH_FIELD(brake_press_r)},
[DF_DistanceTotal] = {NamedFieldKind::Float, "DIST", 3, 1,
VEH_FIELD(distance_total)},
[DF_TempMotL] = {NamedFieldKind::Float, "TMOTL", 2, 1,
VEH_FIELD(temps.mot_l)},
[DF_TempMotR] = {NamedFieldKind::Float, "TMOTR", 2, 1,
VEH_FIELD(temps.mot_r)},
[DF_TempInvL] = {NamedFieldKind::Float, "TINVL", 2, 1,
VEH_FIELD(temps.inv_l)},
[DF_TempInvR] = {NamedFieldKind::Float, "TINVR", 2, 1,
VEH_FIELD(temps.inv_r)},
[DF_TempBrakeFL] = {NamedFieldKind::Float, "TBFL", 3, 0,
VEH_FIELD(temps.brake_fl)},
[DF_TempBrakeFR] = {NamedFieldKind::Float, "TBFR", 3, 0,
VEH_FIELD(temps.brake_fr)},
[DF_TempBrakeRL] = {NamedFieldKind::Float, "TBRL", 3, 0,
VEH_FIELD(temps.brake_rl)},
[DF_TempBrakeRR] = {NamedFieldKind::Float, "TBRR", 3, 0,
VEH_FIELD(temps.brake_rr)},
[DF_LapBest] = {NamedFieldKind::Float, "LAPBEST", 3, 1,
VEH_FIELD(lap_best)},
[DF_LapLast] = {NamedFieldKind::Float, "LAPLAST", 3, 1,
VEH_FIELD(lap_last)},
[DF_LVBatVoltage] = {NamedFieldKind::Float, "LVVBAT", 2, 2,
VEH_FIELD(lv_bat_voltage)},
[DF_GitBuildHash] = {NamedFieldKind::Text, "BLDHASH", 1, 0, get_compiler_build_hash}};
[DF_LapCount] = {NamedFieldKind::Int, "LAPS", 3, 0, VEH_FIELD(lap_count)},
[DF_SectorCount] = {NamedFieldKind::Int, "SECS", 3, 0, VEH_FIELD(sector_count)},
[DF_R2DProgress] = {NamedFieldKind::Text, "R2DPROG", 1, 0, get_r2dprog_text},
[DF_ERR] = {NamedFieldKind::Text, "ERROR", 0, 0, get_err_text},
[DF_SDCStatus] = {NamedFieldKind::Text, "SDC", 0, 0, get_sdc_text},
[DF_INV1Ready] = {NamedFieldKind::Bool, "INV1RDY", 0, 0, VEH_FIELD(inv_1_ready)},
[DF_INV2Ready] = {NamedFieldKind::Bool, "INV2RDY", 0, 0, VEH_FIELD(inv_2_ready)},
[DF_EnergyPerLap] = {NamedFieldKind::Float, "ENGYpLP", 3, 0, VEH_FIELD(energy_per_lap)},
[DF_IniChkState] = {NamedFieldKind::Text, "ICSTATE", 1, 0, get_inichk_text},
[DF_ActiveMission] = {NamedFieldKind::Text, "MISSION", 1, 0, get_mission_text},
[DF_ASState] = {NamedFieldKind::Text, "ASSTATE", 1, 0, get_asstate_text},
[DF_Inv1Velocity] = {NamedFieldKind::Int, "INV1Vel", 3, 0, VEH_FIELD(inv_velocity_1)},
[DF_Inv2Velocity] = {NamedFieldKind::Int, "INV2Vel", 3, 0, VEH_FIELD(inv_velocity_2)},
[DF_Inv1TorqueDemanded] = {NamedFieldKind::Int, "INV1TDe", 3, 0, VEH_FIELD(inv_torque_desired_1)},
[DF_Inv2TorqueDemanded] = {NamedFieldKind::Int, "INV2TDe", 3, 0, VEH_FIELD(inv_torque_desired_2)},
[DF_Inv1TorqueDesired] = {NamedFieldKind::Int, "INV1TDs", 3, 0, VEH_FIELD(inv_torque_demanded_1)},
[DF_Inv2TorqueDesired] = {NamedFieldKind::Int, "INV2TDs", 3, 0, VEH_FIELD(inv_torque_demanded_2)},
[DF_Inv1ControlWord] = {NamedFieldKind::Hex, "INV1CW", 3, 0, VEH_FIELD(inv_control_word_1)},
[DF_Inv2ControlWord] = {NamedFieldKind::Hex, "INV2CW", 3, 0, VEH_FIELD(inv_control_word_2)},
[DF_Inv1TorqueActual] = {NamedFieldKind::Int, "INV1TAc", 3, 0, VEH_FIELD(inv_torque_actual_1)},
[DF_Inv2TorqueActual] = {NamedFieldKind::Int, "INV2TAc", 3, 0, VEH_FIELD(inv_torque_actual_2)},
[DF_Inv1Errors] = {NamedFieldKind::Hex, "INV1Err", 3, 0, VEH_FIELD(inv_errors_1)},
[DF_Inv2Errors] = {NamedFieldKind::Hex, "INV2Err", 3, 0, VEH_FIELD(inv_errors_2)},
[DF_Inv1Warnings] = {NamedFieldKind::Hex, "INV1War", 3, 0, VEH_FIELD(inv_warnings_1)},
[DF_Inv2Warnings] = {NamedFieldKind::Hex, "INV2War", 3, 0, VEH_FIELD(inv_warnings_2)},
[DF_GitBuildHash] = {NamedFieldKind::Text, "BLDHASH", 1, 0, get_compiler_build_hash},
};
static_assert(sizeof(dataFieldDescs) / sizeof(dataFieldDescs[0]) ==
DataFieldType_COUNT,
static_assert(sizeof(dataFieldDescs) / sizeof(dataFieldDescs[0]) == DataFieldType_COUNT,
"Incorrect number of data field descriptions");
#define PARAM_FIELD(FIELD) []() { return (void *)&params.FIELD; }
@ -343,8 +353,7 @@ NamedFieldDescription paramFieldDescs[] = {
[PF_REKU] = {NamedFieldKind::Int, "REKU", 2, 0, PARAM_FIELD(reku)},
};
static_assert(sizeof(paramFieldDescs) / sizeof(paramFieldDescs[0]) ==
ParamType_COUNT,
static_assert(sizeof(paramFieldDescs) / sizeof(paramFieldDescs[0]) == ParamType_COUNT,
"Incorrect number of param field descriptions");
DataFieldType dataFieldByAlphaIndex[DataFieldType_COUNT];
@ -352,148 +361,116 @@ size_t dataFieldAlphaIndexByField[DataFieldType_COUNT];
ParamType paramByAlphaIndex[ParamType_COUNT];
size_t paramAlphaIndexByParam[ParamType_COUNT];
template <class T>
struct NFAlphabeticComp
{
NFAlphabeticComp(const NamedFieldDescription *fieldDescs)
: fieldDescs{fieldDescs} {}
template <class T> struct NFAlphabeticComp {
NFAlphabeticComp(const NamedFieldDescription *fieldDescs) : fieldDescs{fieldDescs} {}
const NamedFieldDescription *fieldDescs;
bool operator()(const T &a, const T &b) const
{
return strcmp(fieldDescs[a].title, fieldDescs[b].title) < 0;
}
bool operator()(const T &a, const T &b) const { return strcmp(fieldDescs[a].title, fieldDescs[b].title) < 0; }
};
template <class T>
void namedFieldSort(const NamedFieldDescription *fieldDescs, T *fieldByAlpha,
size_t *alphaIndexByField, size_t numFields)
{
for (size_t i = 0; i < numFields; i++)
{
void namedFieldSort(const NamedFieldDescription *fieldDescs, T *fieldByAlpha, size_t *alphaIndexByField, size_t numFields) {
for (size_t i = 0; i < numFields; i++) {
fieldByAlpha[i] = static_cast<T>(i);
}
std::sort(fieldByAlpha, fieldByAlpha + numFields,
NFAlphabeticComp<T>(fieldDescs));
for (size_t i = 0; i < numFields; i++)
{
std::sort(fieldByAlpha, fieldByAlpha + numFields, NFAlphabeticComp<T>(fieldDescs));
for (size_t i = 0; i < numFields; i++) {
alphaIndexByField[fieldByAlpha[i]] = i;
}
}
void namedFieldSort()
{
namedFieldSort(dataFieldDescs, dataFieldByAlphaIndex,
dataFieldAlphaIndexByField, DataFieldType_COUNT);
namedFieldSort(paramFieldDescs, paramByAlphaIndex, paramAlphaIndexByParam,
ParamType_COUNT);
void namedFieldSort() {
namedFieldSort(dataFieldDescs, dataFieldByAlphaIndex, dataFieldAlphaIndexByField, DataFieldType_COUNT);
namedFieldSort(paramFieldDescs, paramByAlphaIndex, paramAlphaIndexByParam, ParamType_COUNT);
}
template <class T>
NamedField<T>::NamedField(const NamedFieldDescription *fieldDescs)
: fieldDescs{fieldDescs} {}
template <class T> NamedField<T>::NamedField(const NamedFieldDescription *fieldDescs) : fieldDescs{fieldDescs} {}
template <class T>
void NamedField<T>::setType(T type)
{
template <class T> void NamedField<T>::setType(T type) {
this->type = type;
desc = &fieldDescs[type];
touchgfx::Unicode::strncpy(titleBuffer, desc->title,
sizeof(titleBuffer) / sizeof(*titleBuffer));
touchgfx::Unicode::strncpy(titleBuffer, desc->title, sizeof(titleBuffer) / sizeof(*titleBuffer));
titleBufferUpdated();
typeUpdated();
updateValue();
}
template <class T>
const T &NamedField<T>::getType() { return type; }
template <class T> const T &NamedField<T>::getType() { return type; }
template <class T>
void NamedField<T>::updateValue()
{
template <class T> void NamedField<T>::updateValue() {
void *val = desc->getValue();
switch (desc->kind)
{
case NamedFieldKind::Float:
setFloatValue(*static_cast<float *>(val));
break;
case NamedFieldKind::Bool:
setBoolValue(*static_cast<int *>(val));
break;
case NamedFieldKind::Text:
setStrValue(static_cast<const char *>(val));
break;
case NamedFieldKind::Int:
setIntValue(*static_cast<int *>(val));
break;
switch (desc->kind) {
case NamedFieldKind::Float:
setFloatValue(*static_cast<float *>(val));
break;
case NamedFieldKind::Bool:
setBoolValue(*static_cast<int *>(val));
break;
case NamedFieldKind::Text:
setStrValue(static_cast<const char *>(val));
break;
case NamedFieldKind::Int:
setIntValue(*static_cast<int *>(val));
break;
case NamedFieldKind::Hex:
setHexValue(*static_cast<int *>(val));
break;
}
}
template <class T>
void NamedField<T>::setFloatValue(float floatValue)
{
template <class T> void NamedField<T>::setFloatValue(float floatValue) {
fieldValue.f = floatValue;
updateValueBuffer();
}
template <class T>
void NamedField<T>::setBoolValue(int boolValue)
{
template <class T> void NamedField<T>::setBoolValue(int boolValue) {
fieldValue.b = boolValue;
updateValueBuffer();
}
template <class T>
void NamedField<T>::setIntValue(int intValue)
{
template <class T> void NamedField<T>::setIntValue(int intValue) {
fieldValue.i = intValue;
updateValueBuffer();
}
template <class T>
void NamedField<T>::setStrValue(const char *strValue)
{
touchgfx::Unicode::strncpy(valueBuffer, strValue,
sizeof(valueBuffer) / sizeof(*valueBuffer));
template <class T> void NamedField<T>::setHexValue(int hexValue) {
fieldValue.i = hexValue;
updateValueBuffer();
}
template <class T>
void NamedField<T>::updateValueBuffer()
{
switch (desc->kind)
{
case NamedFieldKind::Float:
{
size_t width = desc->int_digits;
if (desc->decimal_digits != 0)
{
width += desc->decimal_digits + 1; // 1 digit for the decimal point
template <class T> void NamedField<T>::setStrValue(const char *strValue) {
touchgfx::Unicode::strncpy(valueBuffer, strValue, sizeof(valueBuffer) / sizeof(*valueBuffer));
updateValueBuffer();
}
template <class T> void NamedField<T>::updateValueBuffer() {
switch (desc->kind) {
case NamedFieldKind::Float: {
size_t width = desc->int_digits;
if (desc->decimal_digits != 0) {
width += desc->decimal_digits + 1; // 1 digit for the decimal point
}
float params[3] = {(float)width, (float)desc->decimal_digits, fieldValue.f};
touchgfx::Unicode::snprintfFloats(valueBuffer, sizeof(valueBuffer) / sizeof(*valueBuffer), "%*.*f", params);
break;
}
float params[3] = {(float)width, (float)desc->decimal_digits, fieldValue.f};
touchgfx::Unicode::snprintfFloats(
valueBuffer, sizeof(valueBuffer) / sizeof(*valueBuffer), "%*.*f",
params);
break;
}
case NamedFieldKind::Bool:
{
const char *str = fieldValue.b ? "YES" : "NO";
touchgfx::Unicode::strncpy(valueBuffer, str,
sizeof(valueBuffer) / sizeof(*valueBuffer));
break;
}
case NamedFieldKind::Text:
// This is handled by the child class in setValue()
break;
case NamedFieldKind::Int:
touchgfx::Unicode::snprintf(valueBuffer,
sizeof(valueBuffer) / sizeof(*valueBuffer),
"%*d", desc->int_digits, fieldValue.i);
break;
case NamedFieldKind::Bool: {
const char *str = fieldValue.b ? "YES" : "NO";
touchgfx::Unicode::strncpy(valueBuffer, str, sizeof(valueBuffer) / sizeof(*valueBuffer));
break;
}
case NamedFieldKind::Text:
// This is handled by the child class in setValue()
break;
case NamedFieldKind::Int:
touchgfx::Unicode::snprintf(valueBuffer, sizeof(valueBuffer) / sizeof(*valueBuffer), "%*d", desc->int_digits, fieldValue.i);
break;
case NamedFieldKind::Hex:
touchgfx::Unicode::snprintf(valueBuffer, sizeof(valueBuffer) / sizeof(*valueBuffer), "%X", desc->int_digits, fieldValue.i);
break;
}
valueBufferUpdated();
}

View File

@ -23,14 +23,15 @@ void ConfigItem::setDirty(bool dirty) {
void ConfigItem::typeUpdated() {
switch (desc->kind) {
case NamedFieldKind::Float:
case NamedFieldKind::Int:
value.setTypedText(T_NUMBERWILDCARD);
break;
case NamedFieldKind::Bool:
case NamedFieldKind::Text:
value.setTypedText(T_DEFAULTWILDCARD_CENTERED);
break;
case NamedFieldKind::Float:
case NamedFieldKind::Int:
value.setTypedText(T_NUMBERWILDCARD);
break;
case NamedFieldKind::Hex:
case NamedFieldKind::Bool:
case NamedFieldKind::Text:
value.setTypedText(T_DEFAULTWILDCARD_CENTERED);
break;
}
value.invalidate();
}

View File

@ -17,14 +17,15 @@ void DriverViewField::setSelected(int selected) {
void DriverViewField::typeUpdated() {
switch (desc->kind) {
case NamedFieldKind::Float:
case NamedFieldKind::Int:
value.setTypedText(T_NUMBERWILDCARD);
break;
case NamedFieldKind::Bool:
case NamedFieldKind::Text:
value.setTypedText(T_DEFAULTWILDCARD_CENTERED);
break;
case NamedFieldKind::Float:
case NamedFieldKind::Int:
value.setTypedText(T_NUMBERWILDCARD);
break;
case NamedFieldKind::Hex:
case NamedFieldKind::Bool:
case NamedFieldKind::Text:
value.setTypedText(T_DEFAULTWILDCARD_CENTERED);
break;
}
value.invalidate();
}

View File

@ -6,68 +6,65 @@
DriverViewStatusItem::DriverViewStatusItem() {}
void DriverViewStatusItem::initialize() {
DriverViewStatusItemBase::initialize();
}
void DriverViewStatusItem::initialize() { DriverViewStatusItemBase::initialize(); }
void DriverViewStatusItem::setType(DriverViewStatusType type) {
this->type = type;
}
void DriverViewStatusItem::setType(DriverViewStatusType type) { this->type = type; }
void DriverViewStatusItem::update() {
switch (type) {
case DriverViewStatusType::TS_R2D:
if (vehicle_state.ts_state == TS_ERROR) {
text.setTypedText(T_TS);
bg.setColor(COLOR_ERROR);
} else if (vehicle_state.ts_state == TS_INACTIVE) {
text.setTypedText(T_TS);
bg.setColor(COLOR_OFF);
} else if (vehicle_state.r2d_progress == R2D_INIT_SUCCESS) {
text.setTypedText(T_R2D);
case DriverViewStatusType::TS_R2D:
if (vehicle_state.ts_state == TS_ERROR) {
text.setTypedText(T_TS);
bg.setColor(COLOR_ERROR);
} else if (vehicle_state.ts_state == TS_INACTIVE) {
text.setTypedText(T_TS);
bg.setColor(COLOR_OFF);
} else if (vehicle_state.r2d_progress == R2D_INIT_SUCCESS) {
text.setTypedText(T_R2D);
bg.setColor(COLOR_OK);
} else {
text.setTypedText(T_TS);
bg.setColor(COLOR_TS);
}
break;
case DriverViewStatusType::AMS:
text.setTypedText(T_AMS);
bg.setColor(vehicle_state.ts_state == TS_ERROR ? COLOR_ERROR : COLOR_OK);
break;
case DriverViewStatusType::SDC:
text.setTypedText(T_SDC);
bg.setColor(vehicle_state.sdc_closed ? COLOR_OK : COLOR_WARNING);
break;
case DriverViewStatusType::SCS:
text.setTypedText(T_SCS);
bg.setColor(vehicle_state.errors.err_scs ? COLOR_ERROR : COLOR_OK);
break;
case DriverViewStatusType::PDU:
text.setTypedText(T_PDU);
bg.setColor(vehicle_state.errors.err_pdu ? COLOR_ERROR : COLOR_OK);
break;
case DriverViewStatusType::INV:
text.setTypedText(T_INV);
if (vehicle_state.errors.err_inv_1 || vehicle_state.errors.err_inv_2) {
bg.setColor(COLOR_ERROR);
} else if (vehicle_state.inv_1_ready && vehicle_state.inv_2_ready) {
bg.setColor(COLOR_OK);
} else {
bg.setColor(COLOR_OFF);
}
break;
case DriverViewStatusType::LV:
text.setTypedText(T_LV);
// if (vehicle_state.soc_lv < 10) {
// bg.setColor(COLOR_ERROR);
// } else if (vehicle_state.soc_lv < 30) {
// bg.setColor(COLOR_WARNING);
// } else {
// bg.setColor(COLOR_OK);
// }
// TODO
bg.setColor(COLOR_OK);
} else {
text.setTypedText(T_TS);
bg.setColor(COLOR_TS);
}
break;
case DriverViewStatusType::AMS:
text.setTypedText(T_AMS);
bg.setColor(vehicle_state.ts_state == TS_ERROR ? COLOR_ERROR : COLOR_OK);
break;
case DriverViewStatusType::SDC:
text.setTypedText(T_SDC);
bg.setColor(vehicle_state.sdc_closed ? COLOR_OK : COLOR_WARNING);
break;
case DriverViewStatusType::SCS:
text.setTypedText(T_SCS);
bg.setColor(vehicle_state.errors.err_scs ? COLOR_ERROR : COLOR_OK);
break;
case DriverViewStatusType::PDU:
text.setTypedText(T_PDU);
bg.setColor(vehicle_state.errors.err_pdu ? COLOR_ERROR : COLOR_OK);
break;
case DriverViewStatusType::INV:
text.setTypedText(T_INV);
if (vehicle_state.errors.err_invl || vehicle_state.errors.err_invr) {
bg.setColor(COLOR_ERROR);
} else if (vehicle_state.errors.invl_ready &&
vehicle_state.errors.invr_ready) {
bg.setColor(COLOR_OK);
} else {
bg.setColor(COLOR_OFF);
}
break;
case DriverViewStatusType::LV:
text.setTypedText(T_LV);
if (vehicle_state.soc_lv < 10) {
bg.setColor(COLOR_ERROR);
} else if (vehicle_state.soc_lv < 30) {
bg.setColor(COLOR_WARNING);
} else {
bg.setColor(COLOR_OK);
}
break;
break;
}
text.invalidate();
bg.invalidate();

View File

@ -7,23 +7,21 @@
#include "vehicle.h"
#include "vehicle_state.h"
MissionSelectView::MissionSelectView()
: selected{nullptr}, selectedMission{MISSION_NONE} {}
MissionSelectView::MissionSelectView() : selected{nullptr}, selectedMission{MISSION_NONE} {}
void MissionSelectView::setupScreen() {
MissionSelectViewBase::setupScreen();
accel.setUp(0, T_ACCEL);
skidpad.setUp(1, T_SKIDPAD);
autox.setUp(2, T_AUTOX);
trackdrive.setUp(3, T_TRACKDRIVE);
ebs.setUp(4, T_EBS);
inspection.setUp(5, T_INSPECTION);
trackdrive.setUp(2, T_TRACKDRIVE);
ebs.setUp(3, T_EBS);
inspection.setUp(4, T_INSPECTION);
autox.setUp(5, T_AUTOX);
manual.setUp(6, T_MANUAL);
decMission();
}
void MissionSelectView::tearDownScreen() {
MissionSelectViewBase::tearDownScreen();
}
void MissionSelectView::tearDownScreen() { MissionSelectViewBase::tearDownScreen(); }
void MissionSelectView::incMission() {
int mission_int = static_cast<int>(selectedMission);
@ -56,14 +54,14 @@ void MissionSelectView::confirmMission() {
}
vehicle_select_mission(selectedMission);
#ifdef DEMO_MODE
// #ifdef DEMO_MODE
vehicle_state.active_mission = selectedMission;
presenter->vehicleStateUpdated();
#endif
// #endif
#ifdef SIMULATOR
#ifdef SIMULATOR
vehicle_state.active_mission = selectedMission;
#endif
#endif
}
void MissionSelectView::setSelectedMission(Mission mission) {
@ -72,29 +70,29 @@ void MissionSelectView::setSelectedMission(Mission mission) {
}
switch (mission) {
case MISSION_NONE:
break;
case MISSION_ACCEL:
selected = &accel;
break;
case MISSION_SKIDPAD:
selected = &skidpad;
break;
case MISSION_AUTOX:
selected = &autox;
break;
case MISSION_TRACKDRIVE:
selected = &trackdrive;
break;
case MISSION_EBS:
selected = &ebs;
break;
case MISSION_INSPECTION:
selected = &inspection;
break;
case MISSION_MANUAL:
selected = &manual;
break;
case MISSION_NONE:
break;
case MISSION_ACCEL:
selected = &accel;
break;
case MISSION_SKIDPAD:
selected = &skidpad;
break;
case MISSION_AUTOX:
selected = &autox;
break;
case MISSION_TRACKDRIVE:
selected = &trackdrive;
break;
case MISSION_BRAKETEST:
selected = &ebs;
break;
case MISSION_INSPECTION:
selected = &inspection;
break;
case MISSION_MANUAL:
selected = &manual;
break;
}
selected->setSelected(true);
selectedMission = mission;

View File

@ -10,18 +10,18 @@ void SDCPresenter::activate() { vehicleStateUpdated(); }
void SDCPresenter::deactivate() {}
void SDCPresenter::vehicleStateUpdated() {
view.setPDUClosed(vehicle_state.pdu_sdc_active);
view.setInertiaClosed(vehicle_state.sdcl_state[1]);
// TODO
view.setPDUClosed(true);
view.setInertiaClosed(true);
view.setIMDClosed(vehicle_state.imd_ok);
view.setAMSClosed(vehicle_state.ts_state != TS_ERROR);
view.setSDCLClosed(vehicle_state.sdcl_state[0]);
view.setHVBClosed(vehicle_state.sdcl_state[2]);
view.setSDCLClosed(true);
view.setHVBClosed(true);
view.setTSMSClosed(true);
view.setAccClosed(vehicle_state.sdc_closed);
}
void SDCPresenter::nextScreen() {
FrontendApplication *app =
static_cast<FrontendApplication *>(FrontendApplication::getInstance());
FrontendApplication *app = static_cast<FrontendApplication *>(FrontendApplication::getInstance());
app->gotoDebugViewScreenNoTransition();
}

View File

@ -46,7 +46,7 @@
},
{
"Type": "CustomContainerInstance",
"Name": "autox",
"Name": "trackdrive",
"Y": 60,
"Width": 480,
"Height": 30,
@ -54,7 +54,7 @@
},
{
"Type": "CustomContainerInstance",
"Name": "trackdrive",
"Name": "ebs",
"Y": 90,
"Width": 480,
"Height": 30,
@ -62,7 +62,7 @@
},
{
"Type": "CustomContainerInstance",
"Name": "ebs",
"Name": "inspection",
"Y": 120,
"Width": 480,
"Height": 30,
@ -70,7 +70,7 @@
},
{
"Type": "CustomContainerInstance",
"Name": "inspection",
"Name": "autox",
"Y": 150,
"Width": 480,
"Height": 30,
@ -209,7 +209,6 @@
},
{
"Name": "AMI",
"CanvasBufferSize": 7200,
"Components": [
{
"Type": "Image",
@ -369,270 +368,6 @@
"Blue": 255
},
"AutoSize": true
},
{
"Type": "Container",
"Name": "map",
"X": 15,
"Y": 103,
"Width": 255,
"Height": 202,
"Components": [
{
"Type": "Shape",
"Name": "cone0",
"Width": 10,
"Height": 10,
"Visible": false,
"Color": {
"Red": 255,
"Green": 255
},
"Points": [
{},
{
"X": 10.0,
"Y": 5.0
},
{
"Y": 10.0
}
],
"XScale": 1.0,
"YScale": 1.0
},
{
"Type": "Shape",
"Name": "cone1",
"Width": 10,
"Height": 10,
"Visible": false,
"Color": {
"Red": 255,
"Green": 255
},
"Points": [
{},
{
"X": 10.0,
"Y": 5.0
},
{
"Y": 10.0
}
],
"XScale": 1.0,
"YScale": 1.0
},
{
"Type": "Shape",
"Name": "cone2",
"Width": 10,
"Height": 10,
"Visible": false,
"Color": {
"Red": 255,
"Green": 255
},
"Points": [
{},
{
"X": 10.0,
"Y": 5.0
},
{
"Y": 10.0
}
],
"XScale": 1.0,
"YScale": 1.0
},
{
"Type": "Shape",
"Name": "cone3",
"Width": 10,
"Height": 10,
"Visible": false,
"Color": {
"Red": 255,
"Green": 255
},
"Points": [
{},
{
"X": 10.0,
"Y": 5.0
},
{
"Y": 10.0
}
],
"XScale": 1.0,
"YScale": 1.0
},
{
"Type": "Shape",
"Name": "cone4",
"Width": 10,
"Height": 10,
"Visible": false,
"Color": {
"Red": 255,
"Green": 255
},
"Points": [
{},
{
"X": 10.0,
"Y": 5.0
},
{
"Y": 10.0
}
],
"XScale": 1.0,
"YScale": 1.0
},
{
"Type": "Shape",
"Name": "cone5",
"Width": 10,
"Height": 10,
"Visible": false,
"Color": {
"Red": 255,
"Green": 255
},
"Points": [
{},
{
"X": 10.0,
"Y": 5.0
},
{
"Y": 10.0
}
],
"XScale": 1.0,
"YScale": 1.0
},
{
"Type": "Shape",
"Name": "cone6",
"Width": 10,
"Height": 10,
"Visible": false,
"Color": {
"Red": 255,
"Green": 255
},
"Points": [
{},
{
"X": 10.0,
"Y": 5.0
},
{
"Y": 10.0
}
],
"XScale": 1.0,
"YScale": 1.0
},
{
"Type": "Shape",
"Name": "cone7",
"Width": 10,
"Height": 10,
"Visible": false,
"Color": {
"Red": 255,
"Green": 255
},
"Points": [
{},
{
"X": 10.0,
"Y": 5.0
},
{
"Y": 10.0
}
],
"XScale": 1.0,
"YScale": 1.0
},
{
"Type": "Shape",
"Name": "cone8",
"Width": 10,
"Height": 10,
"Visible": false,
"Color": {
"Red": 255,
"Green": 255
},
"Points": [
{},
{
"X": 10.0,
"Y": 5.0
},
{
"Y": 10.0
}
],
"XScale": 1.0,
"YScale": 1.0
},
{
"Type": "Shape",
"Name": "cone9",
"Width": 10,
"Height": 10,
"Visible": false,
"Color": {
"Red": 255,
"Green": 255
},
"Points": [
{},
{
"X": 10.0,
"Y": 5.0
},
{
"Y": 10.0
}
],
"XScale": 1.0,
"YScale": 1.0
},
{
"Type": "Shape",
"Name": "ft",
"Y": 91,
"Width": 20,
"Height": 20,
"Color": {
"Red": 255,
"Green": 255,
"Blue": 255
},
"Points": [
{},
{
"X": 20.0,
"Y": 10.0
},
{
"Y": 20.0
}
],
"XScale": 1.0,
"YScale": 1.0
}
]
}
]
},
@ -724,7 +459,7 @@
},
{
"Type": "TextArea",
"Name": "pressB",
"Name": "press2",
"X": 352,
"Y": 185,
"Width": 60,
@ -740,7 +475,7 @@
},
{
"Type": "TextArea",
"Name": "pressA",
"Name": "press1",
"X": 352,
"Y": 153,
"Width": 60,
@ -759,7 +494,7 @@
"Name": "textArea6",
"X": 68,
"Y": 184,
"Width": 259,
"Width": 258,
"Height": 24,
"TextId": "__SingleUse_OOU3",
"TextRotation": "0",
@ -775,7 +510,7 @@
"Name": "textArea5",
"X": 68,
"Y": 152,
"Width": 256,
"Width": 258,
"Height": 24,
"TextId": "__SingleUse_2FPP",
"TextRotation": "0",