diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..3552451 --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +.idea diff --git a/306-controller_interface.X/.gitignore b/306-controller_interface.X/.gitignore index f24b170..11426d8 100644 --- a/306-controller_interface.X/.gitignore +++ b/306-controller_interface.X/.gitignore @@ -7,7 +7,6 @@ debug/ dist/ disassembly/ nbproject/private/ -nbproject/*.mk nbproject/*.bash nbproject/Makefile-genesis.properties diff --git a/306-controller_interface.X/app/can_message.c b/306-controller_interface.X/app/can_message.c index a746c18..72ff705 100644 --- a/306-controller_interface.X/app/can_message.c +++ b/306-controller_interface.X/app/can_message.c @@ -5,9 +5,11 @@ * @file can_message.c */ -#include "../middleware/can_interface.h" +#include "can_message.h" #include "car.h" #include "../app/factory/factory.h" +#include "../middleware/can_interface.h" +#include "kartculator.h" typedef union { struct { @@ -16,84 +18,363 @@ typedef union { uint8_t byte2; uint8_t byte3; } separate; - struct { - uint32_t bytes; - } full; + uint32_t full; } BYTES_4; +typedef union { + struct { + uint8_t byte0; + uint8_t byte1; + } separate; + uint16_t full; +} BYTES_2; + void CM_processIncome(uint8_t idSender, uint8_t idMsg, uint32_t data){ + BYTES_4 incomeData; + incomeData.full = data; + BYTES_4 revertData; + revertData.separate.byte0 = incomeData.separate.byte3; + revertData.separate.byte1 = incomeData.separate.byte2; + revertData.separate.byte2 = incomeData.separate.byte1; + revertData.separate.byte3 = incomeData.separate.byte0; + switch(idSender){ - case 0: // Broadcast / Debug + + /********************* + * BROADCAST / DEBUG * + *********************/ + case 0: + if(idMsg == 0x0) { // CONTROL_SETUP + // steeringMode eraseMemory - controlAliveTime + if (incomeData.separate.byte1) { + MEM_reset(); + } + KART_CST.CONTROL_STEERING_MODE = incomeData.separate.byte0; + KART_CST.CONTROL_ALIVE_TIME = incomeData.separate.byte3; + MEM_write_1_byte(MEMADD_CONTROL_STEERING_MODE, KART_CST.CONTROL_STEERING_MODE); + MEM_write_1_byte(MEMADD_CONTROL_ALIVE_TIME, KART_CST.CONTROL_ALIVE_TIME); + ALIVE_setAliveTime(ALcontroller(), KART_CST.CONTROL_ALIVE_TIME); + ALIVE_emitStart(ALcontroller(), 0, 0); + } + + if(idMsg == 0x1) { // CONTROL_SPEED_FACTOR + // valHH valH valL valLL + KART_CST.CONTROL_SPEED_FACTOR = data; + MEM_write_4_byte(MEMADD_CONTROL_SPEED_FACTOR, KART_CST.CONTROL_SPEED_FACTOR); + + } + + if(idMsg == 0x2) { // CONTROL_POWER_FACTOR + // valHH valH valL valLL + KART_CST.CONTROL_POWER_FACTOR = data; + MEM_write_4_byte(MEMADD_CONTROL_POWER_FACTOR, KART_CST.CONTROL_POWER_FACTOR); + + } + + if(idMsg == 0x3) { // CONTROL_STEERING_FACTOR + // valHH valH valL valLL + KART_CST.CONTROL_STEERING_FACTOR = data; + MEM_write_4_byte(MEMADD_CONTROL_STEERING_FACTOR, KART_CST.CONTROL_STEERING_FACTOR); + + } + + if(idMsg == 0x4) { // CONTROL_SECURITY_PARAM + // maxSpeedFw maxSpeedBw - - + KART_CST.CONTROL_MAX_SPEED_FW = incomeData.separate.byte0; + KART_CST.CONTROL_MAX_SPEED_BW = incomeData.separate.byte1; + MEM_write_1_byte(MEMADD_CONTROL_MAX_SPEED_FW, KART_CST.CONTROL_MAX_SPEED_FW); + MEM_write_1_byte(MEMADD_CONTROL_MAX_SPEED_BW, KART_CST.CONTROL_MAX_SPEED_BW); + + } + + if(idMsg == 0x5) { // CONTROL_SETUP_PARAM + // displayAliveTime steeringAliveTime - - + KART_CST.DISPLAY_ALIVE_TIME = incomeData.separate.byte0; + KART_CST.STEERING_ALIVE_TIME = incomeData.separate.byte1; + MEM_write_1_byte(MEMADD_DISPLAY_ALIVE_TIME, KART_CST.DISPLAY_ALIVE_TIME); + MEM_write_1_byte(MEMADD_STEERING_ALIVE_TIME, KART_CST.STEERING_ALIVE_TIME); + + // TODO set alive times + // start alives + CM_DISPLAY_SETUP(NULL); + CM_STEERING_SETUP(NULL); + + } + + if(idMsg == 0x6) { // CONTROL_SETUP_PARAM_JOY + // joystickMode joystickParam1 joystickParam2 joystickAliveTime + KART_CST.JOYSTICK_MODE = incomeData.separate.byte0; + KART_CST.JOYSTICK_PARAM1 = incomeData.separate.byte1; + KART_CST.JOYSTICK_PARAM2 = incomeData.separate.byte2; + KART_CST.JOYSTICK_ALIVE_TIME = incomeData.separate.byte3; + MEM_write_1_byte(MEMADD_JOYSTICK_MODE, KART_CST.JOYSTICK_MODE); + MEM_write_1_byte(MEMADD_JOYSTICK_PARAM1, KART_CST.JOYSTICK_PARAM1); + MEM_write_1_byte(MEMADD_JOYSTICK_PARAM2, KART_CST.JOYSTICK_PARAM2); + MEM_write_1_byte(MEMADD_JOYSTICK_ALIVE_TIME, KART_CST.JOYSTICK_ALIVE_TIME); + + ALIVE_setAliveTime(ALjoy(), KART_CST.JOYSTICK_ALIVE_TIME); + ALIVE_emitStart(ALjoy(), 0, 0); + CM_JOY_SETUP(NULL); + + } + + if(idMsg == 0x7) { // CONTROL_SETUP_PARAM_DRIVE + // driveAliveTime driveSpeedTime driveStopTime - + KART_CST.DRIVE_ALIVE_TIME = incomeData.separate.byte0; + KART_CST.DRIVE_SPEED_TIME = incomeData.separate.byte1; + KART_CST.DRIVE_STOP_TIME = incomeData.separate.byte2; + MEM_write_1_byte(MEMADD_DRIVE_ALIVE_TIME, KART_CST.DRIVE_ALIVE_TIME); + MEM_write_1_byte(MEMADD_DRIVE_SPEED_TIME, KART_CST.DRIVE_SPEED_TIME); + MEM_write_1_byte(MEMADD_DRIVE_STOP_TIME, KART_CST.DRIVE_STOP_TIME); + + ALIVE_setAliveTime(&drive()->myChecker, KART_CST.DRIVE_ALIVE_TIME); + ALIVE_emitStart(&drive()->myChecker, 0, 0); + CM_DRIVE_SETUP(NULL); + + } + + if(idMsg == 0x8) { // CONTROL_SETUP_PARAM_BATTERY + // batteryVoltTime batteryCurrentTime batteryEnergyTime batteryAliveTime + KART_CST.BATTERY_VOLT_TIME = incomeData.separate.byte0; + KART_CST.BATTERY_CURRENT_TIME = incomeData.separate.byte1; + KART_CST.BATTERY_ENERGY_TIME = incomeData.separate.byte2; + KART_CST.BATTERY_ALIVE_TIME = incomeData.separate.byte3; + MEM_write_1_byte(MEMADD_BATTERY_VOLT_TIME, KART_CST.BATTERY_VOLT_TIME); + MEM_write_1_byte(MEMADD_BATTERY_CURRENT_TIME, KART_CST.BATTERY_CURRENT_TIME); + MEM_write_1_byte(MEMADD_BATTERY_ENERGY_TIME, KART_CST.BATTERY_ENERGY_TIME); + MEM_write_1_byte(MEMADD_BATTERY_ALIVE_TIME, KART_CST.BATTERY_ALIVE_TIME); + + // TODO set alive time + // TODO start alive + CM_SUPPLY_SETUP(NULL); + + } + break; - case 2: // Joystick + + /************ + * JOYSTICK * + ************/ + case 2: if(idMsg == 0x1) { // JOY_MESURE + // posX posY button - + calcTorque(incomeData.separate.byte1); + calcPosition(incomeData.separate.byte0); } if(idMsg == 0xF) { // JOY_ALIVE - ALIVE_CHECKER_ISALIVE(ACjoy()); + // - - - - + ALIVE_ISALIVE(ALjoy()); + if(ALjoy()->state == STAL_DEAD){ + KART_CST.JOYSTICK_MODE = MEM_read_1_byte(MEMADD_JOYSTICK_MODE); + KART_CST.JOYSTICK_PARAM1 = MEM_read_1_byte(MEMADD_JOYSTICK_PARAM1); + KART_CST.JOYSTICK_PARAM2 = MEM_read_1_byte(MEMADD_JOYSTICK_PARAM2); + KART_CST.JOYSTICK_ALIVE_TIME = MEM_read_1_byte(MEMADD_JOYSTICK_ALIVE_TIME); + ALIVE_setAliveTime(ALjoy(), KART_CST.JOYSTICK_ALIVE_TIME); + ALIVE_emitResurrect(ALjoy(), 0, 0); + ALIVE_emitBorn(ALjoy(), 0, 0); + ALIVE_emitReady(ALjoy(), 0, 0); + } } break; - case 3: // Display + + /*********** + * DISPLAY * + ***********/ + case 3: + if(idMsg == 0xF) { // DISPLAY_ALIVE + // powerMode - - - + // TODO display say ALIVE + + } break; - case 4: // Drive + + /********* + * DRIVE * + *********/ + case 4: + if(idMsg == 0x0) { // DRIVE_SPEED + // speedHH speedH speedL speedLL + calcSpeed(revertData.full); + DRIVE_emitPollSpeed(drive()); + } + + if(idMsg == 0xF) { // DRIVE_ALIVE + // statusH statusL - - + ALIVE_ISALIVE(&drive()->myChecker); + if(drive()->myChecker.state == STAL_DEAD){ + KART_CST.DRIVE_SPEED_TIME = MEM_read_1_byte(MEMADD_DRIVE_SPEED_TIME); + KART_CST.DRIVE_STOP_TIME = MEM_read_1_byte(MEMADD_DRIVE_STOP_TIME); + KART_CST.DRIVE_ALIVE_TIME = MEM_read_1_byte(MEMADD_DRIVE_ALIVE_TIME); + ALIVE_emitResurrect(&drive()->myChecker, 0, 0); + ALIVE_emitBorn(&drive()->myChecker, 0, 0); + } + + } break; - case 5: // Steering + + /************ + * STEERING * + ************/ + case 5: + if(idMsg == 0x1) { // STEERING_GET_CENTER + // valHH valH valL valLL + eKart.center = revertData.full; + } + + if(idMsg == 0x2) { // STEERING_GET_POSITION + // valHH valH valL valLL + + } + + if(idMsg == 0xF) { // STEERING_ALIVE + // statusH statusL - - + // TODO steering say ALIVE with his status + + } break; - case 6: // Supply + + /********** + * SUPPLY * + **********/ + case 6: + if(idMsg == 0xF) { // BATTERY_ALIVE + // - - - - + // TODO battery say ALIVE + + } break; - case 7: // Undefined + + /************* + * UNDEFINED * + *************/ + case 7: break; } } void CM_CONTROLLER_ALIVE(void* p) { + // - - - - CAN_Send(0x0, 0xF, 0); } void CM_JOY_SETUP(void* p) { + // mode parm1 param2 aliveTime BYTES_4 joy; - joy.separate.byte0 = CAR_CST.JOYSTICK_MODE; - joy.separate.byte1 = CAR_CST.JOYSTICK_PARAM1; - joy.separate.byte2 = CAR_CST.JOYSTICK_PARAM2; - joy.separate.byte3 = CAR_CST.JOYSTICK_ALIVE_TIME; - CAN_Send(2, 0, joy.full.bytes); - + joy.separate.byte0 = KART_CST.JOYSTICK_MODE; + joy.separate.byte1 = KART_CST.JOYSTICK_PARAM1; + joy.separate.byte2 = KART_CST.JOYSTICK_PARAM2; + joy.separate.byte3 = KART_CST.JOYSTICK_ALIVE_TIME; + CAN_Send(2, 0, joy.full); } void CM_DISPLAY_SETUP(void* p) { - + // reset - - aliveTime + BYTES_4 display; + display.separate.byte0 = 0; // reset + display.separate.byte3 = KART_CST.DISPLAY_ALIVE_TIME; + CAN_Send(3, 0, display.full); } void CM_DISPLAY_SPEED(void* p) { - + // valH valL - - + BYTES_4 tmpData; + // byte0 should be valH but isn't possible to go enough fast for use it + tmpData.separate.byte0 = 0; + tmpData.separate.byte1 = *((uint8_t*) p); + tmpData.separate.byte2 = 0; + tmpData.separate.byte3 = 0; + CAN_Send(3, 2, tmpData.full); } void CM_DISPLAY_DIRECTION(void* p) { - + // direction - - - + BYTES_4 tmpData; + tmpData.separate.byte0 = (uint8_t) p; + tmpData.separate.byte1 = 0; + tmpData.separate.byte2 = 0; + tmpData.separate.byte3 = 0; + CAN_Send(3, 3, tmpData.full); } void CM_DRIVE_SETUP(void* p) { + // reset/init speedTime stopTime aliveTime + BYTES_4 tmpData; + tmpData.separate.byte0 = (uint8_t) p; + tmpData.separate.byte1 = KART_CST.DRIVE_SPEED_TIME; + tmpData.separate.byte2 = KART_CST.DRIVE_STOP_TIME; + tmpData.separate.byte3 = KART_CST.DRIVE_ALIVE_TIME; + CAN_Send(4, 0, tmpData.full); } void CM_DRIVE_POWER(void* p) { - + // valH valL - - + BYTES_2 torque; + BYTES_4 tmpData; + torque.full = *((int16_t*) p); + tmpData.separate.byte0 = torque.separate.byte1; + tmpData.separate.byte1 = torque.separate.byte0; + tmpData.separate.byte2 = 0; + tmpData.separate.byte3 = 0; + CAN_Send(4, 1, tmpData.full); } void CM_STEERING_SETUP(void* p) { - + // reset/init homing setCenter aliveTime + // TODO not working have to fix it + BYTES_4 tmpData; + uint8_t choice = (uint8_t) p; + switch (choice) { + case 1: + tmpData.separate.byte0 = 1; + tmpData.separate.byte1 = 0; + tmpData.separate.byte2 = 0; + break; + case 2: + tmpData.separate.byte0 = 0; + tmpData.separate.byte1 = 1; + tmpData.separate.byte2 = 0; + break; + case 3: + tmpData.separate.byte0 = 0; + tmpData.separate.byte1 = 0; + tmpData.separate.byte2 = 1; + break; + default: + tmpData.separate.byte0 = 0; + tmpData.separate.byte1 = 0; + tmpData.separate.byte2 = 0; + break; + } + tmpData.separate.byte3 = KART_CST.STEERING_ALIVE_TIME; // 0 -> no alive + CAN_Send(5, 0, tmpData.full); } void CM_STEERING_SET(void* p) { - + // valHH valH valL valLL + BYTES_4 pPosition; + pPosition.full = *((uint32_t*) p); + BYTES_4 sPosition; + sPosition.separate.byte0 = pPosition.separate.byte3; + sPosition.separate.byte1 = pPosition.separate.byte2; + sPosition.separate.byte2 = pPosition.separate.byte1; + sPosition.separate.byte3 = pPosition.separate.byte0; + CAN_Send(5, 1, sPosition.full); } -void CM_SETUP_CONTROL(void* p) { - +void CM_SUPPLY_SETUP(void* p) { + // batteryVoltTime batteryCurrentTime batteryEnergyTime aliveTime + BYTES_4 supply; + supply.separate.byte0 = KART_CST.BATTERY_VOLT_TIME; + supply.separate.byte1 = KART_CST.BATTERY_CURRENT_TIME; + supply.separate.byte2 = KART_CST.BATTERY_ENERGY_TIME; + supply.separate.byte3 = KART_CST.BATTERY_ALIVE_TIME; + CAN_Send(6, 0, supply.full); } diff --git a/306-controller_interface.X/app/can_message.h b/306-controller_interface.X/app/can_message.h index cfec699..0249c07 100644 --- a/306-controller_interface.X/app/can_message.h +++ b/306-controller_interface.X/app/can_message.h @@ -8,6 +8,9 @@ #ifndef CAN_MESSAGE_H #define CAN_MESSAGE_H +#include // usage of standard types +#include // usage of boolean types +#include "../mcc_generated_files/mcc.h" /* S R M @@ -23,17 +26,80 @@ S R M 1 6 0 SETUP_CONTROL batteryVoltTime batteryCurrentTime batteryEnergyTime aliveTime */ +/** + * Process an incoming message + * @param idSender id of the sender + * @param idMsg is of the message + * @param data data of the message + */ void CM_processIncome(uint8_t idSender, uint8_t idMsg, uint32_t data); + +/** + * Send alive message from controller + * @param p have to be NULL + */ void CM_CONTROLLER_ALIVE(void* p); + +/** + * Send setup to the joystick (settings from memory) + * @param p have to be NULL + */ void CM_JOY_SETUP(void* p); + +/** + * Send setup to the display (settings from memory) + * @param p have to be NULL + */ void CM_DISPLAY_SETUP(void* p); + +/** + * Send speed to display + * @param p the speed in 100m/h (max 255 m/h) + */ void CM_DISPLAY_SPEED(void* p); + +/** + * Send direction of the steering wheel + * 0 is straight forward + * positive value is going right + * negative value is going left + * @param p the direction (int 8) + */ void CM_DISPLAY_DIRECTION(void* p); + +/** + * Send setup to the drive + * use with reset in parameter + * other settings from memory + * @param p 1 if reset/init 0 else + */ void CM_DRIVE_SETUP(void* p); + +/** + * Send power to the drive + * @param p the torque (int16_t*) + */ void CM_DRIVE_POWER(void* p); + +/** + * Send setup to the steering + * can be use for reset (1), homing (2) and setCenter (3) + * @param p 0 for setup, 1 for reset, 2 for homing, 3 for setCenter + */ void CM_STEERING_SETUP(void* p); + +/** + * Send position for steering + * no negative value because 0 is home (sensor) + * @param p the position (uint32_t*) + */ void CM_STEERING_SET(void* p); -void CM_SETUP_CONTROL(void* p); + +/** + * Send setup to the supply (settings from memory) + * @param p have to be NULL + */ +void CM_SUPPLY_SETUP(void* p); #endif /* CAN_MESSAGE_H */ diff --git a/306-controller_interface.X/app/car.h b/306-controller_interface.X/app/car.h index 5d3a9a8..dfea2a5 100644 --- a/306-controller_interface.X/app/car.h +++ b/306-controller_interface.X/app/car.h @@ -34,12 +34,15 @@ #define MEMADD_JOYSTICK_PARAM1 0x12 #define MEMADD_JOYSTICK_PARAM2 0x13 #define MEMADD_JOYSTICK_ALIVE_TIME 0x14 -#define MEMADD_DISPLAY_ALIVE_TIME 0x -#define MEMADD_DRIVE_SPEED_TIME 0x -#define MEMADD_DRIVE_STOP_TIME 0x -#define MEMADD_DRIVE_ALIVE_TIME 0x -#define MEMADD_STEERING_ALIVE_TIME 0x -#define MEMADD_BATTERY_ALIVE_TIME 0x +#define MEMADD_DISPLAY_ALIVE_TIME 0x15 +#define MEMADD_DRIVE_SPEED_TIME 0x16 +#define MEMADD_DRIVE_STOP_TIME 0x17 +#define MEMADD_DRIVE_ALIVE_TIME 0x18 +#define MEMADD_STEERING_ALIVE_TIME 0x19 +#define MEMADD_BATTERY_VOLT_TIME 0x1A +#define MEMADD_BATTERY_CURRENT_TIME 0x1B +#define MEMADD_BATTERY_ENERGY_TIME 0x1C +#define MEMADD_BATTERY_ALIVE_TIME 0x1D typedef struct { uint8_t CONTROL_STEERING_MODE; @@ -49,7 +52,6 @@ typedef struct { uint32_t CONTROL_STEERING_FACTOR; uint8_t CONTROL_MAX_SPEED_FW; uint8_t CONTROL_MAX_SPEED_BW; - uint8_t JOYSTICK_MODE; uint8_t JOYSTICK_PARAM1; uint8_t JOYSTICK_PARAM2; @@ -59,9 +61,20 @@ typedef struct { uint8_t DRIVE_STOP_TIME; uint8_t DRIVE_ALIVE_TIME; uint8_t STEERING_ALIVE_TIME; + uint8_t BATTERY_VOLT_TIME; + uint8_t BATTERY_CURRENT_TIME; + uint8_t BATTERY_ENERGY_TIME; uint8_t BATTERY_ALIVE_TIME; -} CAR_CST_TYPE; -CAR_CST_TYPE CAR_CST; +} KART_CST_TYPE; +KART_CST_TYPE KART_CST; + +typedef struct { + int16_t torque; // + uint32_t center; // + uint32_t position; // + uint8_t speed; // 100m/h +} KART_VAR_TYPE; +KART_VAR_TYPE eKart; #endif /* CAR_H */ diff --git a/306-controller_interface.X/app/drive.c b/306-controller_interface.X/app/drive.c new file mode 100644 index 0000000..f926b1f --- /dev/null +++ b/306-controller_interface.X/app/drive.c @@ -0,0 +1,171 @@ +/** + * @author Rémi Heredero + * @version 1.0.0 + * @date August 2023 + * @file drive.c + */ + +#include "drive.h" +#include "car.h" +#include "can_message.h" + +void DRIVE_init(DRIVE* me){ + me->state = STDR_INIT; + ALIVE_init(&me->myChecker); + ALIVE_onSetup(&me->myChecker, CM_DRIVE_SETUP, NULL); + ALIVE_onWait(&me->myChecker, DRIVE_emitStart, me); + ALIVE_onDead(&me->myChecker, DRIVE_emitStop, me); + ALIVE_onBorn(&me->myChecker, DRIVE_emitResurrect, me); + me->wait.f = NULL; + me->run.f = NULL; + me->dead.f = NULL; +} + +void DRIVE_startBehaviour(DRIVE* me){ + POST(me, &DRIVE_processEvent, evDRinit, 0, 0); +} + +bool DRIVE_processEvent(Event* ev) { + bool processed = false; + DRIVE* me = (DRIVE*)Event_getTarget(ev); + DRIVE_STATES oldState = me->state; + evIDT evid = Event_getId(ev); + uint64_t data = Event_getData(ev); + + switch (me->state) { // onState + case STDR_INIT: + if (ev->id == evDRinit) { + me->state = STDR_WAIT; + ALIVE_startBehaviourChecker(&me->myChecker); // Start alive checker + } + break; + + case STDR_WAIT: + if (ev->id == evDRstart) { + me->state = STDR_RUN; + } + ALIVE_setAliveTime(&me->myChecker, KART_CST.DRIVE_ALIVE_TIME); + ALIVE_emitBorn(&me->myChecker, 100, 0); // Born after 100 ms + ALIVE_emitReady(&me->myChecker, 200, 0); // Ready after 200 ms + break; + + case STDR_RUN: + if (ev->id == evDRstop) { + me->state = STDR_DEAD; + } + + if (ev->id == evDRpollTorque) { + CM_DRIVE_POWER(&eKart.torque); + } + + if (ev->id == evDRpollSpeed) { + CM_DISPLAY_SPEED(&eKart.speed); + } + + DRIVE_emitPollTorque(me, KART_CST.DRIVE_STOP_TIME*9, 0); + break; + + case STDR_DEAD: + if (ev->id == evDRresurrect) { + me->state = STDR_WAIT; + } + break; + } + + if(oldState != me->state){ + switch (oldState) { // onExit + case STDR_INIT: + break; + + case STDR_WAIT: + break; + + case STDR_RUN: + break; + + case STDR_DEAD: + break; + } + + switch (me->state) { // onEntry + case STDR_INIT: + break; + + case STDR_WAIT: + if (me->wait.f != NULL) { + me->wait.f(me->wait.p); + } + break; + + case STDR_RUN: + if (me->run.f != NULL) { + me->run.f(me->run.p); + } + break; + + case STDR_DEAD: + if (me->dead.f != NULL) { + me->dead.f(me->dead.p); + } + break; + } + + processed = true; + } + return processed; +} + +/************* + * Callbacks * + *************/ + +void DRIVE_onWait(DRIVE* me, DRIVE_CALLBACK_FUNCTION f, void* p) { + me->wait.f = f; + me->wait.p = p; +} + +void DRIVE_onRun(DRIVE* me, DRIVE_CALLBACK_FUNCTION f, void* p) { + me->run.f = f; + me->run.p = p; +} + +void DRIVE_onDead(DRIVE* me, DRIVE_CALLBACK_FUNCTION f, void* p) { + me->dead.f = f; + me->dead.p = p; +} + +/************ + * EMITTERS * + ************/ + +void DRIVE_emitStart(void* p) { + DRIVE* me = (DRIVE*) p; + POST(me, &DRIVE_processEvent, evDRstart, 0, 0); +} + +void DRIVE_emitStop(void* p) { + DRIVE* me = (DRIVE*) p; + POST(me, &DRIVE_processEvent, evDRstop, 0, 0); +} + +void DRIVE_emitResurrect(void* p) { + DRIVE* me = (DRIVE*) p; + POST(me, &DRIVE_processEvent, evDRresurrect, 0, 0); +} + +void DRIVE_emitPollSpeed(void* p) { + DRIVE* me = (DRIVE*) p; + POST(me, &DRIVE_processEvent, evDRpollSpeed, 0, 0); +} + +void DRIVE_emitPollTorque(DRIVE* me, uint16_t t, int64_t data) { + POST(me, &DRIVE_processEvent, evDRpollTorque, t, data); +} + +/*********** + * SETTERS * + ***********/ + +void DRIVE_setMyChecker(DRIVE* me, ALIVE v) { + me->myChecker = v; +} diff --git a/306-controller_interface.X/app/drive.h b/306-controller_interface.X/app/drive.h new file mode 100644 index 0000000..647e66e --- /dev/null +++ b/306-controller_interface.X/app/drive.h @@ -0,0 +1,130 @@ +/** + * @author Rémi Heredero + * @version 1.0.0 + * @date August 2023 + * @file drive.h + */ +#ifndef DRIVE_H +#define DRIVE_H + +#include "../xf/xf.h" +#include "../middleware/alive.h" + +typedef enum { + STDR_INIT, + STDR_WAIT, + STDR_RUN, + STDR_DEAD +} DRIVE_STATES; + +typedef enum { + evDRinit = 100, + evDRstart, + evDRstop, + evDRresurrect, + evDRpollSpeed, + evDRpollTorque +} DRIVE_EVENTS; + +typedef void (*DRIVE_CALLBACK_FUNCTION)(void*); +typedef struct { + DRIVE_CALLBACK_FUNCTION f; // function + void* p; // param(s) +} DRIVE_CALLBACK; + +typedef struct { + DRIVE_STATES state; + ALIVE myChecker; + DRIVE_CALLBACK wait; + DRIVE_CALLBACK run; + DRIVE_CALLBACK dead; +} DRIVE; + +/** + * Initialize the DRIVE + * @param me the DRIVE itself + */ +void DRIVE_init(DRIVE* me); + +/** + * Start the DRIVE state machine + * @param me the DRIVE itself + */ +void DRIVE_startBehaviour(DRIVE* me); + +/** + * Process the event + * @param ev the event to process + * @return true if the event is processed + */ +bool DRIVE_processEvent(Event* ev); + +/************* + * Callbacks * + *************/ + +/** + * Set the callback function to call when the DRIVE is entering state wait + * @param me the DRIVE itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void DRIVE_onWait(DRIVE* me, DRIVE_CALLBACK_FUNCTION f, void* p); + +/** + * Set the callback function to call when the DRIVE is entering state run + * @param me the DRIVE itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void DRIVE_onRun(DRIVE* me, DRIVE_CALLBACK_FUNCTION f, void* p); + +/** + * Set the callback function to call when the DRIVE is entering state dead + * @param me the DRIVE itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void DRIVE_onDead(DRIVE* me, DRIVE_CALLBACK_FUNCTION f, void* p); + +/************ + * EMITTERS * + ************/ + +/** + * Emit the start event + * @param p the DRIVE itself + */ +void DRIVE_emitStart(void* p); + +/** + * Emit the stop event + * @param p the DRIVE itself + */ +void DRIVE_emitStop(void* p); + +/** + * Emit the resurrect event + * @param p the DRIVE itself + */ +void DRIVE_emitResurrect(void* p); + +/** + * Emit the pollSpeed event + * @param p the DRIVE itself + */ +void DRIVE_emitPollSpeed(void* p); + +/** + * Emit the pollTorque event + * @param p the DRIVE itself + */ +void DRIVE_emitPollTorque(DRIVE* me, uint16_t t, int64_t data); + +/*********** + * SETTERS * + ***********/ + + + +#endif diff --git a/306-controller_interface.X/app/eeprom.c b/306-controller_interface.X/app/eeprom.c new file mode 100644 index 0000000..2e1ba5d --- /dev/null +++ b/306-controller_interface.X/app/eeprom.c @@ -0,0 +1,139 @@ +/** + * @author R�mi Heredero + * @version 1.0.0 + * @date August 2023 + * @file eeprom_interface.h + */ + +#include "eeprom.h" +#include "../app/car.h" + +typedef union { + struct { + uint8_t byte0; + uint8_t byte1; + uint8_t byte2; + uint8_t byte3; + } separate; + uint32_t full; + uint8_t array[4]; +} BYTES_4; + +void MEM_init(){ + uint8_t check = MEM_read_1_byte(0x0); + if(check != 0x2A){ + KART_CST.CONTROL_STEERING_MODE = 0; + KART_CST.CONTROL_ALIVE_TIME = 50; + KART_CST.CONTROL_SPEED_FACTOR = 111111; + KART_CST.CONTROL_POWER_FACTOR = 10000; + KART_CST.CONTROL_STEERING_FACTOR = 400000000; + KART_CST.CONTROL_MAX_SPEED_FW = 50; + KART_CST.CONTROL_MAX_SPEED_BW = 25; + + KART_CST.JOYSTICK_MODE = 0; + KART_CST.JOYSTICK_PARAM1 = 5; + KART_CST.JOYSTICK_PARAM2 = 1; + KART_CST.JOYSTICK_ALIVE_TIME = 25; + + KART_CST.DISPLAY_ALIVE_TIME = 100; + + KART_CST.DRIVE_SPEED_TIME = 20; + KART_CST.DRIVE_STOP_TIME = 10; + KART_CST.DRIVE_ALIVE_TIME = 250; + + KART_CST.STEERING_ALIVE_TIME = 100; + + KART_CST.BATTERY_VOLT_TIME = 50; + KART_CST.BATTERY_CURRENT_TIME = 50; + KART_CST.BATTERY_ENERGY_TIME = 50; + KART_CST.BATTERY_ALIVE_TIME = 50; + + MEM_write_1_byte(MEMADD_CONTROL_STEERING_MODE, KART_CST.CONTROL_STEERING_MODE); + MEM_write_1_byte(MEMADD_CONTROL_ALIVE_TIME, KART_CST.CONTROL_ALIVE_TIME); + MEM_write_4_byte(MEMADD_CONTROL_SPEED_FACTOR, KART_CST.CONTROL_SPEED_FACTOR); + MEM_write_4_byte(MEMADD_CONTROL_POWER_FACTOR, KART_CST.CONTROL_POWER_FACTOR); + MEM_write_4_byte(MEMADD_CONTROL_STEERING_FACTOR, KART_CST.CONTROL_STEERING_FACTOR); + MEM_write_1_byte(MEMADD_CONTROL_MAX_SPEED_FW, KART_CST.CONTROL_MAX_SPEED_FW); + MEM_write_1_byte(MEMADD_CONTROL_MAX_SPEED_BW, KART_CST.CONTROL_MAX_SPEED_BW); + + MEM_write_1_byte(MEMADD_JOYSTICK_MODE, KART_CST.JOYSTICK_MODE); + MEM_write_1_byte(MEMADD_JOYSTICK_PARAM1, KART_CST.JOYSTICK_PARAM1); + MEM_write_1_byte(MEMADD_JOYSTICK_PARAM2, KART_CST.JOYSTICK_PARAM2); + MEM_write_1_byte(MEMADD_JOYSTICK_ALIVE_TIME, KART_CST.JOYSTICK_ALIVE_TIME); + + MEM_write_1_byte(MEMADD_DISPLAY_ALIVE_TIME, KART_CST.DISPLAY_ALIVE_TIME); + + MEM_write_1_byte(MEMADD_DRIVE_SPEED_TIME, KART_CST.DRIVE_SPEED_TIME); + MEM_write_1_byte(MEMADD_DRIVE_STOP_TIME, KART_CST.DRIVE_STOP_TIME); + MEM_write_1_byte(MEMADD_DRIVE_ALIVE_TIME, KART_CST.DRIVE_ALIVE_TIME); + + MEM_write_1_byte(MEMADD_STEERING_ALIVE_TIME, KART_CST.STEERING_ALIVE_TIME); + + MEM_write_1_byte(MEMADD_BATTERY_VOLT_TIME, KART_CST.BATTERY_VOLT_TIME); + MEM_write_1_byte(MEMADD_BATTERY_CURRENT_TIME, KART_CST.BATTERY_CURRENT_TIME); + MEM_write_1_byte(MEMADD_BATTERY_ENERGY_TIME, KART_CST.BATTERY_ENERGY_TIME); + MEM_write_1_byte(MEMADD_BATTERY_ALIVE_TIME, KART_CST.BATTERY_ALIVE_TIME); + + MEM_write_1_byte(0x0, 0x2A); + } else { + KART_CST.CONTROL_STEERING_MODE = MEM_read_1_byte(MEMADD_CONTROL_STEERING_MODE); + KART_CST.CONTROL_ALIVE_TIME = MEM_read_1_byte(MEMADD_CONTROL_ALIVE_TIME); + KART_CST.CONTROL_SPEED_FACTOR = MEM_read_1_byte(MEMADD_CONTROL_SPEED_FACTOR); + KART_CST.CONTROL_POWER_FACTOR = MEM_read_1_byte(MEMADD_CONTROL_POWER_FACTOR); + KART_CST.CONTROL_STEERING_FACTOR = MEM_read_1_byte(MEMADD_CONTROL_STEERING_FACTOR); + KART_CST.CONTROL_MAX_SPEED_FW = MEM_read_1_byte(MEMADD_CONTROL_MAX_SPEED_FW); + KART_CST.CONTROL_MAX_SPEED_BW = MEM_read_1_byte(MEMADD_CONTROL_MAX_SPEED_BW); + + KART_CST.JOYSTICK_MODE = MEM_read_1_byte(MEMADD_JOYSTICK_MODE); + KART_CST.JOYSTICK_PARAM1 = MEM_read_1_byte(MEMADD_JOYSTICK_PARAM1); + KART_CST.JOYSTICK_PARAM2 = MEM_read_1_byte(MEMADD_JOYSTICK_PARAM2); + KART_CST.JOYSTICK_ALIVE_TIME = MEM_read_1_byte(MEMADD_JOYSTICK_ALIVE_TIME); + + KART_CST.DISPLAY_ALIVE_TIME = MEM_read_1_byte(MEMADD_DISPLAY_ALIVE_TIME); + + KART_CST.DRIVE_SPEED_TIME = MEM_read_1_byte(MEMADD_DRIVE_SPEED_TIME); + KART_CST.DRIVE_STOP_TIME = MEM_read_1_byte(MEMADD_DRIVE_STOP_TIME); + KART_CST.DRIVE_ALIVE_TIME = MEM_read_1_byte(MEMADD_DRIVE_ALIVE_TIME); + + KART_CST.STEERING_ALIVE_TIME = MEM_read_1_byte(MEMADD_STEERING_ALIVE_TIME); + + KART_CST.BATTERY_VOLT_TIME = MEM_read_1_byte(MEMADD_BATTERY_VOLT_TIME); + KART_CST.BATTERY_CURRENT_TIME = MEM_read_1_byte(MEMADD_BATTERY_CURRENT_TIME); + KART_CST.BATTERY_ENERGY_TIME = MEM_read_1_byte(MEMADD_BATTERY_ENERGY_TIME); + KART_CST.BATTERY_ALIVE_TIME = MEM_read_1_byte(MEMADD_BATTERY_ALIVE_TIME); + + } +} + +void MEM_reset() { + MEM_write_1_byte(0x0, 0x0); +} + +void MEM_write_1_byte(uint8_t address, uint8_t data) { + DATAEE_WriteByte(address, data); +} + +void MEM_write_4_byte(uint8_t address, uint32_t data) { + BYTES_4 tmpData; + tmpData.full = data; + for(uint8_t i = 0; i<4;i++) { + uint8_t add = address; + add += i; + MEM_write_1_byte(add, tmpData.array[i]); + } + +} + +uint8_t MEM_read_1_byte(uint8_t address) { + return DATAEE_ReadByte(address); +} + +uint32_t MEM_read_4_byte(uint8_t address) { + BYTES_4 tmpData; + for(uint8_t i = 0; i<4;i++) { + uint8_t add = address; + add += i; + tmpData.array[i] = MEM_read_1_byte(add); + } + return tmpData.full; +} diff --git a/306-controller_interface.X/app/eeprom.h b/306-controller_interface.X/app/eeprom.h new file mode 100644 index 0000000..dbf0bb8 --- /dev/null +++ b/306-controller_interface.X/app/eeprom.h @@ -0,0 +1,22 @@ +/** + * @author R�mi Heredero + * @version 1.0.0 + * @date August 2023 + * @file eeprom_interface.h + */ +#ifndef EEPROM_INTERFACE_H +#define EEPROM_INTERFACE_H + +#include // usage of standard types +#include // usage of boolean types +#include "../mcc_generated_files/mcc.h" + +void MEM_init(); +void MEM_reset(); +void MEM_write_1_byte(uint8_t address, uint8_t data); +void MEM_write_4_byte(uint8_t address, uint32_t data); +uint8_t MEM_read_1_byte(uint8_t address); +uint32_t MEM_read_4_byte(uint8_t address); + +#endif /* EEPROM_INTERFACE_H */ + diff --git a/306-controller_interface.X/app/factory/factory.c b/306-controller_interface.X/app/factory/factory.c index 2f62bfd..41b271d 100644 --- a/306-controller_interface.X/app/factory/factory.c +++ b/306-controller_interface.X/app/factory/factory.c @@ -30,12 +30,20 @@ LED* l8() { return &theFactory.l8_; } -WATCHDOG* WDcontroller(){ - return &theFactory.WDcontroller_; +BLINKER* b1() { + return &theFactory.b1_; } -ALIVE_CHECKER* ACjoy() { - return &theFactory.ACjoy_; +ALIVE* ALcontroller(){ + return &theFactory.ALcontroller_; +} + +ALIVE* ALjoy(){ + return &theFactory.ALjoy_; +} + +DRIVE* drive(){ + return &theFactory.drive_; } @@ -58,24 +66,20 @@ void Factory_init() { LED_initHW(l6()); LED_initHW(l7()); LED_initHW(l8()); + + BLINKER_init(b1()); CAN_init(); CAN_setSender(1); LED_off(l1()); - // TODO init EPROM interface + MEM_init(); - // TODO init watchdog with EPROM CST - WATCHDOG_init(WDcontroller()); - CAR_CST.CONTROL_ALIVE_TIME = 100; - WATCHDOG_setTime(WDcontroller(), CAR_CST.CONTROL_ALIVE_TIME); + ALIVE_init(ALcontroller()); + ALIVE_setAliveTime(ALcontroller(), KART_CST.CONTROL_ALIVE_TIME); - // TODO init ALIVE CHECKER with EPROM CST - CAR_CST.JOYSTICK_MODE = 0; - CAR_CST.JOYSTICK_PARAM1 = 100; - CAR_CST.JOYSTICK_PARAM2 = 1; - CAR_CST.JOYSTICK_ALIVE_TIME = 10; - ALIVE_CHECKER_init(ACjoy()); + ALIVE_init(ALjoy()); + DRIVE_init(drive()); } //connect objects if required @@ -83,20 +87,32 @@ void Factory_build() { ECAN_SetRXBnInterruptHandler(CAN_newMsg); CAN_onReceiveCan(CM_processIncome); - WATCHDOG_onAlive(WDcontroller(), CM_CONTROLLER_ALIVE, NULL); - ALIVE_CHECKER_onSetup(ACjoy(), CM_JOY_SETUP, NULL); - ALIVE_CHECKER_setAliveTime(ACjoy(), CAR_CST.JOYSTICK_ALIVE_TIME); - ALIVE_CHECKER_onBorn(ACjoy(), LED_on, l1()); - ALIVE_CHECKER_onDead(ACjoy(), LED_off, l1()); + ALIVE_onAlive(ALcontroller(), CM_CONTROLLER_ALIVE, NULL); + + //BLINKER_onOn(b1(), LED_on, l6()); + //BLINKER_onOff(b1(), LED_off, l6()); + + ALIVE_onSetup(ALjoy(), CM_JOY_SETUP, NULL); + ALIVE_setAliveTime(ALjoy(), KART_CST.JOYSTICK_ALIVE_TIME); + ALIVE_onBorn(ALjoy(), LED_on, l1()); + ALIVE_onDead(ALjoy(), LED_off, l1()); + + DRIVE_onRun(drive(), LED_on, l2()); + DRIVE_onDead(drive(), LED_off, l2()); } //start all state machines void Factory_start() { CAN_startBehaviour(); - WATCHDOG_startBehaviour(WDcontroller()); - ALIVE_CHECKER_startBehaviour(ACjoy()); - ALIVE_CHECKER_emitBorn(ACjoy(), 100, 0); - ALIVE_CHECKER_emitReady(ACjoy(), 200, 0); + + DRIVE_startBehaviour(drive()); + + ALIVE_startBehaviourSender(ALcontroller()); + ALIVE_startBehaviourChecker(ALjoy()); + ALIVE_emitBorn(ALjoy(), 100, 0); + ALIVE_emitReady(ALjoy(), 200, 0); + + } diff --git a/306-controller_interface.X/app/factory/factory.h b/306-controller_interface.X/app/factory/factory.h index 015a4ba..1a35e49 100644 --- a/306-controller_interface.X/app/factory/factory.h +++ b/306-controller_interface.X/app/factory/factory.h @@ -14,11 +14,13 @@ #include "../car.h" #include "../can_message.h" +#include "../eeprom.h" +#include "../drive.h" #include "../../board/led/led.h" #include "../../board/button/button.h" -#include "../../middleware/alive_checker.h" +#include "../../middleware/alive.h" #include "../../middleware/can_interface.h" -#include "../../middleware/watchdog.h" +#include "../../middleware/blinker.h" typedef struct { @@ -31,8 +33,11 @@ typedef struct { LED l7_; LED l8_; - WATCHDOG WDcontroller_; - ALIVE_CHECKER ACjoy_; + BLINKER b1_; + + ALIVE ALcontroller_; + ALIVE ALjoy_; + DRIVE drive_; } Factory; @@ -51,8 +56,11 @@ LED* l6(); LED* l7(); LED* l8(); -WATCHDOG* WDcontroller(); -ALIVE_CHECKER* ACjoy(); +BLINKER* b1(); + +ALIVE* ALcontroller(); +ALIVE* ALjoy(); +DRIVE* drive(); #endif \ No newline at end of file diff --git a/306-controller_interface.X/app/kartculator.c b/306-controller_interface.X/app/kartculator.c new file mode 100644 index 0000000..88a490b --- /dev/null +++ b/306-controller_interface.X/app/kartculator.c @@ -0,0 +1,47 @@ +/** + * @author Rémi Heredero + * @version. 0.0.0 + * @date August 2023 + * @file kartculator.c + */ + +#include "kartculator.h" + +void calcTorque(uint8_t joy_pos) { + int32_t calcTorque; + calcTorque = (int8_t) joy_pos; // joystick position + calcTorque *= KART_CST.CONTROL_POWER_FACTOR; // convert by power factor + calcTorque /= 1000; // torque define by joystick + eKart.torque = (int16_t) calcTorque; +} + +void calcPosition(uint8_t joy_pos){ + int32_t calcPosition; + calcPosition = (int8_t) joy_pos; +} + +void calcSpeed(int32_t rpm) { + int32_t calcSpeed; + if(rpm>=0){ + calcSpeed = rpm; + } else { + calcSpeed = -rpm; + } + calcSpeed *= 1000; + calcSpeed /= KART_CST.CONTROL_SPEED_FACTOR; + eKart.speed = (uint8_t) calcSpeed; +} + +int16_t getTorque() { + +} + +uint32_t getPosition() { + +} + +uint8_t getSpeed() { + +} + + diff --git a/306-controller_interface.X/app/kartculator.h b/306-controller_interface.X/app/kartculator.h new file mode 100644 index 0000000..a2ce5cb --- /dev/null +++ b/306-controller_interface.X/app/kartculator.h @@ -0,0 +1,24 @@ +/** + * @author Rémi Heredero + * @version. 0.0.0 + * @date August 2023 + * @file kartculator.h + */ + +#ifndef KARTCULATOR_H +#define KARTCULATOR_H + +#include // usage of standard types +#include // usage of boolean types +#include "../mcc_generated_files/mcc.h" +#include "car.h" + +void calcTorque(uint8_t joy_pos); +void calcPosition(uint8_t joy_pos); +void calcSpeed(int32_t rpm); +int16_t getTorque(); +uint32_t getPosition(); +uint8_t getSpeed(); + +#endif /* KARTCULATOR_H */ + diff --git a/306-controller_interface.X/defmplabxtrace.log b/306-controller_interface.X/defmplabxtrace.log new file mode 100644 index 0000000..e69de29 diff --git a/306-controller_interface.X/defmplabxtrace.log.inx b/306-controller_interface.X/defmplabxtrace.log.inx new file mode 100644 index 0000000..29197e3 Binary files /dev/null and b/306-controller_interface.X/defmplabxtrace.log.inx differ diff --git a/306-controller_interface.X/main.c b/306-controller_interface.X/main.c index 6a05435..d81327c 100644 --- a/306-controller_interface.X/main.c +++ b/306-controller_interface.X/main.c @@ -10,8 +10,6 @@ void main(void) // Initialize the device SYSTEM_Initialize(); - // Enable the Global Interrupts - INTERRUPT_GlobalInterruptEnable(); // Disable the Global Interrupts // INTERRUPT_GlobalInterruptDisable(); @@ -29,6 +27,8 @@ void main(void) // TMR0 is interrupting. Important: Set the TICKINTERVAL define in //the xf.h file to the same value as the TMR0 value. TMR0_SetInterruptHandler(XF_decrementAndQueueTimers); + // Enable the Global Interrupts + INTERRUPT_GlobalInterruptEnable(); while (1) { diff --git a/306-controller_interface.X/mcc_generated_files/device_config.c b/306-controller_interface.X/mcc_generated_files/device_config.c index eb96dd3..1e3bf51 100644 --- a/306-controller_interface.X/mcc_generated_files/device_config.c +++ b/306-controller_interface.X/mcc_generated_files/device_config.c @@ -14,7 +14,7 @@ This header file provides implementations for driver APIs for all modules selected in the GUI. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 2.00 The generated drivers are tested against the following: Compiler : XC8 2.36 and above or later diff --git a/306-controller_interface.X/mcc_generated_files/device_config.h b/306-controller_interface.X/mcc_generated_files/device_config.h index 0c48b82..72f9a53 100644 --- a/306-controller_interface.X/mcc_generated_files/device_config.h +++ b/306-controller_interface.X/mcc_generated_files/device_config.h @@ -14,7 +14,7 @@ This header file provides implementations for driver APIs for all modules selected in the GUI. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 2.00 The generated drivers are tested against the following: Compiler : XC8 2.36 and above or later diff --git a/306-controller_interface.X/mcc_generated_files/ecan.c b/306-controller_interface.X/mcc_generated_files/ecan.c index 8b2c89b..e1bfd4d 100644 --- a/306-controller_interface.X/mcc_generated_files/ecan.c +++ b/306-controller_interface.X/mcc_generated_files/ecan.c @@ -130,17 +130,21 @@ void ECAN_Initialize(void) /* * ENABLE FILTERS * - * Filter 0 set on mask 0 - * Filter 1 set on mask 0 - * Filter 2 set on mask 1 + * RXF7EN RXF6EN RXF5EN RXF4EN RXF3EN RXF2EN RXF1EN RXF0EN + * 0b 00000111 */ RXFCON0 = 0x07; - /** - Assign Filters to Masks - */ - // Filter 0 & 1 assigned to mask 0 and filter 2 assigned to mask 1 + /* + * Assign Filters to Masks + * + * Filter 0 set on mask 0 + * Filter 1 set on mask 0 + * Filter 2 set on mask 1 + * 0b F3 F2 F1 F0 + * 0b 00 01 00 00 + */ MSEL0 = 0x10; /** diff --git a/306-controller_interface.X/mcc_generated_files/interrupt_manager.c b/306-controller_interface.X/mcc_generated_files/interrupt_manager.c index bd0b551..db7e86a 100644 --- a/306-controller_interface.X/mcc_generated_files/interrupt_manager.c +++ b/306-controller_interface.X/mcc_generated_files/interrupt_manager.c @@ -16,7 +16,7 @@ all modules selected in the GUI. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 2.04 The generated drivers are tested against the following: Compiler : XC8 2.36 and above or later diff --git a/306-controller_interface.X/mcc_generated_files/interrupt_manager.h b/306-controller_interface.X/mcc_generated_files/interrupt_manager.h index 90330f6..babb6f2 100644 --- a/306-controller_interface.X/mcc_generated_files/interrupt_manager.h +++ b/306-controller_interface.X/mcc_generated_files/interrupt_manager.h @@ -16,7 +16,7 @@ all modules selected in the GUI. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 2.03 The generated drivers are tested against the following: Compiler : XC8 2.36 and above or later diff --git a/306-controller_interface.X/mcc_generated_files/mcc.c b/306-controller_interface.X/mcc_generated_files/mcc.c index 0abd635..e2cbde5 100644 --- a/306-controller_interface.X/mcc_generated_files/mcc.c +++ b/306-controller_interface.X/mcc_generated_files/mcc.c @@ -14,7 +14,7 @@ This header file provides implementations for driver APIs for all modules selected in the GUI. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 2.00 The generated drivers are tested against the following: Compiler : XC8 2.36 and above or later diff --git a/306-controller_interface.X/mcc_generated_files/mcc.h b/306-controller_interface.X/mcc_generated_files/mcc.h index 6360c59..f681b38 100644 --- a/306-controller_interface.X/mcc_generated_files/mcc.h +++ b/306-controller_interface.X/mcc_generated_files/mcc.h @@ -14,7 +14,7 @@ This header file provides implementations for driver APIs for all modules selected in the GUI. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 2.00 The generated drivers are tested against the following: Compiler : XC8 2.36 and above or later diff --git a/306-controller_interface.X/mcc_generated_files/memory.c b/306-controller_interface.X/mcc_generated_files/memory.c index 3bf3c4c..a2ebbd8 100644 --- a/306-controller_interface.X/mcc_generated_files/memory.c +++ b/306-controller_interface.X/mcc_generated_files/memory.c @@ -14,7 +14,7 @@ This file provides implementations of driver APIs for MEMORY. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 2.1.3 The generated drivers are tested against the following: Compiler : XC8 2.36 and above @@ -198,7 +198,6 @@ uint8_t DATAEE_ReadByte(uint16_t bAdd) void MEMORY_Tasks( void ) { - /* TODO : Add interrupt handling code */ PIR0bits.NVMIF = 0; } /** diff --git a/306-controller_interface.X/mcc_generated_files/memory.h b/306-controller_interface.X/mcc_generated_files/memory.h index e295cca..5020390 100644 --- a/306-controller_interface.X/mcc_generated_files/memory.h +++ b/306-controller_interface.X/mcc_generated_files/memory.h @@ -14,7 +14,7 @@ This header file provides APIs for driver for MEMORY. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 2.1.3 The generated drivers are tested against the following: Compiler : XC8 2.36 and above @@ -64,9 +64,9 @@ Section: Macro Declarations */ -#define WRITE_FLASH_BLOCKSIZE 64 -#define ERASE_FLASH_BLOCKSIZE 64 -#define END_FLASH 0x008000 +#define WRITE_FLASH_BLOCKSIZE 128 +#define ERASE_FLASH_BLOCKSIZE 128 +#define END_FLASH 0x010000 /** Section: Flash Module APIs diff --git a/306-controller_interface.X/mcc_generated_files/pin_manager.c b/306-controller_interface.X/mcc_generated_files/pin_manager.c index adf9b9a..b9c898e 100644 --- a/306-controller_interface.X/mcc_generated_files/pin_manager.c +++ b/306-controller_interface.X/mcc_generated_files/pin_manager.c @@ -14,7 +14,7 @@ This header file provides implementations for pin APIs for all pins selected in the GUI. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 2.11 The generated drivers are tested against the following: Compiler : XC8 2.36 and above diff --git a/306-controller_interface.X/mcc_generated_files/pin_manager.h b/306-controller_interface.X/mcc_generated_files/pin_manager.h index 791e977..a4d0d24 100644 --- a/306-controller_interface.X/mcc_generated_files/pin_manager.h +++ b/306-controller_interface.X/mcc_generated_files/pin_manager.h @@ -14,7 +14,7 @@ This header file provides APIs for driver for . Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 2.11 The generated drivers are tested against the following: Compiler : XC8 2.36 and above diff --git a/306-controller_interface.X/mcc_generated_files/tmr0.c b/306-controller_interface.X/mcc_generated_files/tmr0.c index 5e32ee5..72ae03d 100644 --- a/306-controller_interface.X/mcc_generated_files/tmr0.c +++ b/306-controller_interface.X/mcc_generated_files/tmr0.c @@ -14,7 +14,7 @@ This source file provides APIs for TMR0. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 3.10 The generated drivers are tested against the following: Compiler : XC8 2.36 and above diff --git a/306-controller_interface.X/mcc_generated_files/tmr0.h b/306-controller_interface.X/mcc_generated_files/tmr0.h index ad9154b..60b06d7 100644 --- a/306-controller_interface.X/mcc_generated_files/tmr0.h +++ b/306-controller_interface.X/mcc_generated_files/tmr0.h @@ -14,7 +14,7 @@ This header file provides APIs for TMR0. Generation Information : Product Revision : PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 - Device : PIC18F25K83 + Device : PIC18F26K83 Driver Version : 3.10 The generated drivers are tested against the following: Compiler : XC8 2.36 and above diff --git a/306-controller_interface.X/middleware/alive.c b/306-controller_interface.X/middleware/alive.c new file mode 100644 index 0000000..1565dd3 --- /dev/null +++ b/306-controller_interface.X/middleware/alive.c @@ -0,0 +1,265 @@ +/** + * @author Rémi Heredero + * @version 1.0.0 + * @date August 2023 + * @file alive.c + */ + +#include "alive.h" + +void ALIVE_init(ALIVE* me){ + me->state = STAL_INIT; + me->isAlive = false; + me->checker = false; + me->sender = false; + me->haveBreak = true; + me->aliveTime = 10; + me->setup.f = NULL; + me->born.f = NULL; + me->wait.f = NULL; + me->dead.f = NULL; + me->alive.f = NULL; + me->break_cb.f = NULL; +} + +void ALIVE_startBehaviourChecker(ALIVE* me){ + POST(me, &ALIVE_processEvent, evALinitChecker, 0, 0); +} + +void ALIVE_startBehaviourSender(ALIVE* me){ + POST(me, &ALIVE_processEvent, evALinitSender, 0, 0); +} + +bool ALIVE_processEvent(Event* ev) { + bool processed = false; + ALIVE* me = (ALIVE*)Event_getTarget(ev); + ALIVE_STATES oldState = me->state; + evIDT evid = Event_getId(ev); + uint64_t data = Event_getData(ev); + + switch (me->state) { // onState + case STAL_INIT: + if (ev->id == evALinitChecker) { + me->state = STAL_SETUP; + } + if (ev->id == evALinitSender) { + me->state = STAL_ALIVE; + ALIVE_emitPoll(me, me->aliveTime*10, 0); + } + break; + + case STAL_SETUP: + if (ev->id == evALborn) { + me->state = STAL_BORN; + } + break; + + case STAL_BORN: + if (ev->id == evALready) { + me->state = STAL_WAIT; + ALIVE_emitPoll(me, me->aliveTime*10, 0); + } + break; + + case STAL_WAIT: + if (ev->id == evALpoll) { + + if (me->aliveTime == 0) { + if (me->haveBreak){ + me->state = STAL_BREAK; + } + } else if (me->isAlive){ + me->state = STAL_WAIT; + ALIVE_emitPoll(me, me->aliveTime*10, 0); + } else { + me->state = STAL_DEAD; + } + me->isAlive = false; + + } + break; + + case STAL_DEAD: + if (ev->id == evALresurrect) { + me->state = STAL_SETUP; + } + break; + + case STAL_ALIVE: + if (ev->id == evALpoll) { + if (me->alive.f != NULL) { + me->alive.f(me->alive.p); + } + if (me->aliveTime == 0) { + if (me->haveBreak){ + me->state = STAL_BREAK; + } + } else { + ALIVE_emitPoll(me, me->aliveTime*10, 0); + } + } + break; + + case STAL_BREAK: + if (ev->id == evALstart) { + ALIVE_emitPoll(me, me->aliveTime*10, 0); + if (me->checker) { + me->state = STAL_WAIT; + } + if (me->sender) { + me->state = STAL_ALIVE; + } + } + break; + } + + if(oldState != me->state){ + switch (oldState) { // onExit + case STAL_INIT: + break; + + case STAL_SETUP: + break; + + case STAL_BORN: + break; + + case STAL_WAIT: + break; + + case STAL_DEAD: + break; + + case STAL_ALIVE: + break; + + case STAL_BREAK: + break; + } + + switch (me->state) { // onEntry + case STAL_INIT: + break; + + case STAL_SETUP: + me->checker = true; + if (me->setup.f != NULL) { + me->setup.f(me->setup.p); + } + break; + + case STAL_BORN: + if (me->born.f != NULL) { + me->born.f(me->born.p); + } + break; + + case STAL_WAIT: + if (me->wait.f != NULL) { + me->wait.f(me->wait.p); + } + break; + + case STAL_DEAD: + if (me->dead.f != NULL) { + me->dead.f(me->dead.p); + } + break; + + case STAL_ALIVE: + me->sender = true; + break; + + case STAL_BREAK: + if (me->break_cb.f != NULL) { + me->break_cb.f(me->break_cb.p); + } + break; + } + + processed = true; + } + return processed; +} + +/************* + * Callbacks * + *************/ + +void ALIVE_onSetup(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p) { + me->setup.f = f; + me->setup.p = p; +} + +void ALIVE_onBorn(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p) { + me->born.f = f; + me->born.p = p; +} + +void ALIVE_onWait(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p) { + me->wait.f = f; + me->wait.p = p; +} + +void ALIVE_onDead(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p) { + me->dead.f = f; + me->dead.p = p; +} + +void ALIVE_onAlive(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p) { + me->alive.f = f; + me->alive.p = p; +} + +void ALIVE_onBreak(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p) { + me->break_cb.f = f; + me->break_cb.p = p; +} + +/************ + * EMITTERS * + ************/ + +void ALIVE_emitInitSender(ALIVE* me, uint16_t t, int64_t data) { + POST(me, &ALIVE_processEvent, evALinitSender, t, data); +} + +void ALIVE_emitBorn(ALIVE* me, uint16_t t, int64_t data) { + POST(me, &ALIVE_processEvent, evALborn, t, data); +} + +void ALIVE_emitReady(ALIVE* me, uint16_t t, int64_t data) { + POST(me, &ALIVE_processEvent, evALready, t, data); +} + +void ALIVE_emitPoll(ALIVE* me, uint16_t t, int64_t data) { + POST(me, &ALIVE_processEvent, evALpoll, t, data); +} + +void ALIVE_emitStart(ALIVE* me, uint16_t t, int64_t data) { + POST(me, &ALIVE_processEvent, evALstart, t, data); +} + +void ALIVE_emitResurrect(ALIVE* me, uint16_t t, int64_t data) { + POST(me, &ALIVE_processEvent, evALresurrect, t, data); +} + +/*********** + * SETTERS * + ***********/ + +void ALIVE_setIsAlive(ALIVE* me, bool v) { + me->isAlive = v; +} + +void ALIVE_setHaveBreak(ALIVE* me, bool v) { + me->haveBreak = v; +} + +void ALIVE_setAliveTime(ALIVE* me, uint8_t v) { + me->aliveTime = v; +} + +void ALIVE_ISALIVE(ALIVE* me) { + ALIVE_setIsAlive(me, true); +} diff --git a/306-controller_interface.X/middleware/alive.h b/306-controller_interface.X/middleware/alive.h new file mode 100644 index 0000000..580e735 --- /dev/null +++ b/306-controller_interface.X/middleware/alive.h @@ -0,0 +1,187 @@ +/** + * @author Rémi Heredero + * @version 1.0.0 + * @date August 2023 + * @file alive.h + */ +#ifndef ALIVE_H +#define ALIVE_H + +#include "../xf/xf.h" + +typedef enum { + STAL_INIT, + STAL_SETUP, + STAL_BORN, + STAL_WAIT, + STAL_DEAD, + STAL_ALIVE, + STAL_BREAK +} ALIVE_STATES; + +typedef enum { + evALinitChecker = 15, + evALinitSender, + evALborn, + evALready, + evALpoll, + evALstart, + evALresurrect +} ALIVE_EVENTS; + +typedef void (*ALIVE_CALLBACK_FUNCTION)(void*); +typedef struct { + ALIVE_CALLBACK_FUNCTION f; // function + void* p; // param(s) +} ALIVE_CALLBACK; + +typedef struct { + ALIVE_STATES state; + bool isAlive; + bool checker; + bool sender; + bool haveBreak; + uint8_t aliveTime; + ALIVE_CALLBACK setup; + ALIVE_CALLBACK born; + ALIVE_CALLBACK wait; + ALIVE_CALLBACK dead; + ALIVE_CALLBACK alive; + ALIVE_CALLBACK break_cb; +} ALIVE; + +/** + * Initialize the ALIVE + * @param me the ALIVE itself + */ +void ALIVE_init(ALIVE* me); + +/** + * Start the ALIVE state machine for checker part + * @param me the ALIVE itself + */ +void ALIVE_startBehaviourChecker(ALIVE* me); + +/** + * Start the ALIVE state machine for sender part + * @param me the ALIVE itself + */ +void ALIVE_startBehaviourSender(ALIVE* me); + +/** + * Process the event + * @param ev the event to process + * @return true if the event is processed + */ +bool ALIVE_processEvent(Event* ev); + +/************* + * Callbacks * + *************/ + +/** + * Set the callback function to call when the ALIVE is entering state setup + * @param me the ALIVE itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void ALIVE_onSetup(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p); + +/** + * Set the callback function to call when the ALIVE is entering state born + * @param me the ALIVE itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void ALIVE_onBorn(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p); + +/** + * Set the callback function to call when the ALIVE is entering state wait + * @param me the ALIVE itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void ALIVE_onWait(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p); + +/** + * Set the callback function to call when the ALIVE is entering state dead + * @param me the ALIVE itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void ALIVE_onDead(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p); + +/** + * Set the callback function to call when the ALIVE is entering state alive + * @param me the ALIVE itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void ALIVE_onAlive(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p); + +/** + * Set the callback function to call when the ALIVE is entering state break + * @param me the ALIVE itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void ALIVE_onBreak(ALIVE* me, ALIVE_CALLBACK_FUNCTION f, void* p); + +/************ + * EMITTERS * + ************/ + +/** + * Emit the born event + * @param me the ALIVE itself + * @param t time to wait in ms before triggering event + * @param data data to put on the event for XF + */ +void ALIVE_emitBorn(ALIVE* me, uint16_t t, int64_t data); + +/** + * Emit the ready event + * @param me the ALIVE itself + * @param t time to wait in ms before triggering event + * @param data data to put on the event for XF + */ +void ALIVE_emitReady(ALIVE* me, uint16_t t, int64_t data); + +/** + * Emit the poll event + * @param me the ALIVE itself + * @param t time to wait in ms before triggering event + * @param data data to put on the event for XF + */ +void ALIVE_emitPoll(ALIVE* me, uint16_t t, int64_t data); + +/** + * Emit the start event + * @param me the ALIVE itself + * @param t time to wait in ms before triggering event + * @param data data to put on the event for XF + */ +void ALIVE_emitStart(ALIVE* me, uint16_t t, int64_t data); + +/** + * Emit the resurrect event + * @param me the ALIVE itself + * @param t time to wait in ms before triggering event + * @param data data to put on the event for XF + */ +void ALIVE_emitResurrect(ALIVE* me, uint16_t t, int64_t data); + + +/*********** + * SETTERS * + ***********/ + +void ALIVE_setIsAlive(ALIVE* me, bool v); + +void ALIVE_setHaveBreak(ALIVE* me, bool v); + +void ALIVE_setAliveTime(ALIVE* me, uint8_t v); + +void ALIVE_ISALIVE(ALIVE* me); + +#endif diff --git a/306-controller_interface.X/middleware/alive_checker.c b/306-controller_interface.X/middleware/alive_checker.c deleted file mode 100644 index 00466a4..0000000 --- a/306-controller_interface.X/middleware/alive_checker.c +++ /dev/null @@ -1,176 +0,0 @@ -/** - * @author Rémi Heredero - * @version 1.0.0 - * @date August 2023 - * @file alive_checker.c - */ - -#include "alive_checker.h" - -void ALIVE_CHECKER_init(ALIVE_CHECKER* me){ - me->state = STAC_INIT; - me->isAlive = false; - me->aliveTime = 10; - me->setup.f = NULL; - me->born.f = NULL; - me->wait.f = NULL; - me->dead.f = NULL; -} - -void ALIVE_CHECKER_startBehaviour(ALIVE_CHECKER* me){ - POST(me, &ALIVE_CHECKER_processEvent, evACinit, 0, 0); -} - -bool ALIVE_CHECKER_processEvent(Event* ev) { - bool processed = false; - ALIVE_CHECKER* me = (ALIVE_CHECKER*)Event_getTarget(ev); - ALIVE_CHECKER_STATES oldState = me->state; - evIDT evid = Event_getId(ev); - uint64_t data = Event_getData(ev); - - switch (me->state) { // onState - case STAC_INIT: - if (ev->id == evACinit) { - me->state = STAC_SETUP; - } - break; - - case STAC_SETUP: - if (ev->id == evACborn) { - me->state = STAC_BORN; - } - break; - - case STAC_BORN: - if (ev->id == evACready) { - me->state = STAC_WAIT; - ALIVE_CHECKER_emitPoll(me, me->aliveTime*10, 0); - } - break; - - case STAC_WAIT: - if (ev->id == evACpoll) { - if (me->isAlive) { - me->state = STAC_WAIT; - ALIVE_CHECKER_emitPoll(me, me->aliveTime*10, 0); - } else { - me->state = STAC_DEAD; - } - me->isAlive = false; - } - break; - - case STAC_DEAD: - if(ev->id == evACborn) { - me->state = STAC_BORN; - } - break; - } - - if(oldState != me->state){ - switch (oldState) { // onExit - case STAC_INIT: - break; - - case STAC_SETUP: - break; - - case STAC_BORN: - break; - - case STAC_WAIT: - break; - - case STAC_DEAD: - break; - } - - switch (me->state) { // onEntry - case STAC_INIT: - break; - - case STAC_SETUP: - if (me->setup.f != NULL) { - me->setup.f(me->setup.p); - } - break; - - case STAC_BORN: - if (me->born.f != NULL) { - me->born.f(me->born.p); - } - break; - - case STAC_WAIT: - if (me->wait.f != NULL) { - me->wait.f(me->wait.p); - } - break; - - case STAC_DEAD: - if (me->dead.f != NULL) { - me->dead.f(me->dead.p); - } - break; - } - - processed = true; - } - return processed; -} - -/************* - * Callbacks * - *************/ - -void ALIVE_CHECKER_onSetup(ALIVE_CHECKER* me, ALIVE_CHECKER_CALLBACK_FUNCTION f, void* p) { - me->setup.f = f; - me->setup.p = p; -} - -void ALIVE_CHECKER_onBorn(ALIVE_CHECKER* me, ALIVE_CHECKER_CALLBACK_FUNCTION f, void* p) { - me->born.f = f; - me->born.p = p; -} - -void ALIVE_CHECKER_onWait(ALIVE_CHECKER* me, ALIVE_CHECKER_CALLBACK_FUNCTION f, void* p) { - me->wait.f = f; - me->wait.p = p; -} - -void ALIVE_CHECKER_onDead(ALIVE_CHECKER* me, ALIVE_CHECKER_CALLBACK_FUNCTION f, void* p) { - me->dead.f = f; - me->dead.p = p; -} - -/************ - * EMITTERS * - ************/ - -void ALIVE_CHECKER_emitBorn(ALIVE_CHECKER* me, uint16_t t, int64_t data) { - POST(me, &ALIVE_CHECKER_processEvent, evACborn, t, data); -} - -void ALIVE_CHECKER_emitReady(ALIVE_CHECKER* me, uint16_t t, int64_t data) { - POST(me, &ALIVE_CHECKER_processEvent, evACready, t, data); -} - -void ALIVE_CHECKER_emitPoll(ALIVE_CHECKER* me, uint16_t t, int64_t data) { - POST(me, &ALIVE_CHECKER_processEvent, evACpoll, t, data); -} - -/*********** - * SETTERS * - ***********/ - -void ALIVE_CHECKER_setAliveTime(ALIVE_CHECKER* me, uint8_t v) { - me->aliveTime = v; -} - -void ALIVE_CHECKER_setIsAlive(ALIVE_CHECKER* me, bool v) { - me->isAlive = v; -} - -void ALIVE_CHECKER_ISALIVE(ALIVE_CHECKER* me) { - ALIVE_CHECKER_setIsAlive(me, true); -} diff --git a/306-controller_interface.X/middleware/alive_checker.h b/306-controller_interface.X/middleware/alive_checker.h deleted file mode 100644 index 6b57ac7..0000000 --- a/306-controller_interface.X/middleware/alive_checker.h +++ /dev/null @@ -1,134 +0,0 @@ -/** - * @author Rémi Heredero - * @version 1.0.0 - * @date August 2023 - * @file alive_checker.h - */ -#ifndef ALIVE_CHECKER_H -#define ALIVE_CHECKER_H - -#include "../xf/xf.h" - -typedef enum { - STAC_INIT, - STAC_SETUP, - STAC_BORN, - STAC_WAIT, - STAC_DEAD -} ALIVE_CHECKER_STATES; - -typedef enum { - evACinit = 15, - evACborn, - evACready, - evACpoll -} ALIVE_CHECKER_EVENTS; - -typedef void (*ALIVE_CHECKER_CALLBACK_FUNCTION)(void*); -typedef struct { - ALIVE_CHECKER_CALLBACK_FUNCTION f; // function - void* p; // param(s) -} ALIVE_CHECKER_CALLBACK; - -typedef struct { - ALIVE_CHECKER_STATES state; - bool isAlive; - uint8_t aliveTime; - ALIVE_CHECKER_CALLBACK setup; - ALIVE_CHECKER_CALLBACK born; - ALIVE_CHECKER_CALLBACK wait; - ALIVE_CHECKER_CALLBACK dead; -} ALIVE_CHECKER; - -/** - * Initialize the ALIVE_CHECKER - * @param me the ALIVE_CHECKER itself - */ -void ALIVE_CHECKER_init(ALIVE_CHECKER* me); - -/** - * Start the ALIVE_CHECKER state machine - * @param me the ALIVE_CHECKER itself - */ -void ALIVE_CHECKER_startBehaviour(ALIVE_CHECKER* me); - -/** - * Process the event - * @param ev the event to process - * @return true if the event is processed - */ -bool ALIVE_CHECKER_processEvent(Event* ev); - -/************* - * Callbacks * - *************/ - -/** - * Set the callback function to call when the ALIVE_CHECKER is entering state setup - * @param me the ALIVE_CHECKER itself - * @param f the function to call - * @param p the param(s) to pass to the function - */ -void ALIVE_CHECKER_onSetup(ALIVE_CHECKER* me, ALIVE_CHECKER_CALLBACK_FUNCTION f, void* p); - -/** - * Set the callback function to call when the ALIVE_CHECKER is entering state born - * @param me the ALIVE_CHECKER itself - * @param f the function to call - * @param p the param(s) to pass to the function - */ -void ALIVE_CHECKER_onBorn(ALIVE_CHECKER* me, ALIVE_CHECKER_CALLBACK_FUNCTION f, void* p); - -/** - * Set the callback function to call when the ALIVE_CHECKER is entering state wait - * @param me the ALIVE_CHECKER itself - * @param f the function to call - * @param p the param(s) to pass to the function - */ -void ALIVE_CHECKER_onWait(ALIVE_CHECKER* me, ALIVE_CHECKER_CALLBACK_FUNCTION f, void* p); - -/** - * Set the callback function to call when the ALIVE_CHECKER is entering state dead - * @param me the ALIVE_CHECKER itself - * @param f the function to call - * @param p the param(s) to pass to the function - */ -void ALIVE_CHECKER_onDead(ALIVE_CHECKER* me, ALIVE_CHECKER_CALLBACK_FUNCTION f, void* p); - -/************ - * EMITTERS * - ************/ - -/** - * Emit the born event - * @param me the ALIVE_CHECKER itself - * @param t time to wait in ms before triggering event - * @param data data to put on the event for XF - */ -void ALIVE_CHECKER_emitBorn(ALIVE_CHECKER* me, uint16_t t, int64_t data); - -/** - * Emit the ready event - * @param me the ALIVE_CHECKER itself - * @param t time to wait in ms before triggering event - * @param data data to put on the event for XF - */ -void ALIVE_CHECKER_emitReady(ALIVE_CHECKER* me, uint16_t t, int64_t data); - -/** - * Emit the poll event - * @param me the ALIVE_CHECKER itself - * @param t time to wait in ms before triggering event - * @param data data to put on the event for XF - */ -void ALIVE_CHECKER_emitPoll(ALIVE_CHECKER* me, uint16_t t, int64_t data); - -/*********** - * SETTERS * - ***********/ - -void ALIVE_CHECKER_setAliveTime(ALIVE_CHECKER* me, uint8_t v); -void ALIVE_CHECKER_setIsAlive(ALIVE_CHECKER* me, bool v); -void ALIVE_CHECKER_ISALIVE(ALIVE_CHECKER* me); // Use this one when you receive CAN message - -#endif diff --git a/306-controller_interface.X/middleware/blinker.c b/306-controller_interface.X/middleware/blinker.c new file mode 100644 index 0000000..f8a948f --- /dev/null +++ b/306-controller_interface.X/middleware/blinker.c @@ -0,0 +1,189 @@ +/** + * @author Rémi Heredero + * @version 1.0.0 + * @date July 2023 + * @file blinker.c + */ + +#include "blinker.h" + +void BLINKER_init(BLINKER* me){ + me->state = STBL_INIT; + me->timeOn = 500; + me->timeOff = 500; + me->numberOfBlink = 3; + me->nBlinkIsOn = false; + me->remainBlinks = 3; + me->wait.f = NULL; + me->on.f = NULL; + me->off.f = NULL; + me->finished.f = NULL; +} + +void BLINKER_startBehaviour(BLINKER* me) { + POST(me, &BLINKER_processEvent, evBLinit, 0, 0); +} + +bool BLINKER_processEvent(Event* ev) { + bool processed = false; + BLINKER* me = (BLINKER*)Event_getTarget(ev); + BLINKER_STATES oldState = me->state; + evIDT evid = Event_getId(ev); + + switch (me->state) { // onState + case STBL_INIT: + if (ev->id == evBLinit) { + me->state = STBL_WAIT; + } + break; + + case STBL_WAIT: + me->remainBlinks = me->numberOfBlink; + if(evid == evBLblinkN) { + me->state = STBL_ON; + me->nBlinkIsOn = true; + BLINKER_emitTimer(me, me->timeOn); + } + if(evid == evBLblink) { + me->state = STBL_ON; + me->nBlinkIsOn = false; + BLINKER_emitTimer(me, me->timeOn); + } + break; + + case STBL_ON: + if (me->nBlinkIsOn) { + me->remainBlinks--; + } + if (evid == evBLtimer) { + me->state = STBL_OFF; + BLINKER_emitTimer(me, me->timeOff); + } + break; + + case STBL_OFF: + if (evid == evBLtimer) { + if (me->remainBlinks == 0) { + me->state = STBL_WAIT; + if (me->finished.f != NULL) { + me->finished.f(me->finished.p); + } + } else { + me->state = STBL_ON; + BLINKER_emitTimer(me, me->timeOn); + } + } + break; + } + + if(oldState != me->state){ + switch (oldState) { // onExit + case STBL_INIT: + break; + + case STBL_WAIT: + break; + + case STBL_ON: + break; + + case STBL_OFF: + break; + } + + switch (me->state) { // onEntry + case STBL_INIT: + break; + + case STBL_WAIT: + if (me->wait.f != NULL) { + me->wait.f(me->wait.p); + } + break; + + case STBL_ON: + if (me->on.f != NULL) { + me->on.f(me->on.p); + } + break; + + case STBL_OFF: + if (me->off.f != NULL) { + me->off.f(me->off.p); + } + break; + } + + processed = true; + } + return processed; +} + +/************* + * Callbacks * + *************/ + +void BLINKER_onWait(BLINKER* me, BLINKER_CALLBACK_FUNCTION f, void* p) { + me->wait.f = f; + me->wait.p = p; +} + +void BLINKER_onOn(BLINKER* me, BLINKER_CALLBACK_FUNCTION f, void* p) { + me->on.f = f; + me->on.p = p; +} + +void BLINKER_onOff(BLINKER* me, BLINKER_CALLBACK_FUNCTION f, void* p) { + me->off.f = f; + me->off.p = p; +} + +void BLINKER_onFinished(BLINKER* me, BLINKER_CALLBACK_FUNCTION f, void* p) { + me->finished.f = f; + me->finished.p = p; +} + +/************ + * EMITTERS * + ************/ + +void BLINKER_emitBlink(BLINKER* me, uint16_t t) { + POST(me, &BLINKER_processEvent, evBLblink, t, 0); +} + +void BLINKER_emitBlinkN(BLINKER* me, uint16_t t) { + POST(me, &BLINKER_processEvent, evBLblinkN, t, 0); +} + +void BLINKER_emitTimer(BLINKER* me, uint16_t t) { + POST(me, &BLINKER_processEvent, evBLtimer, t, 0); +} + +/*********** + * SETTERS * + ***********/ + +void BLINKER_setTimeOn(BLINKER* me, uint16_t v) { + me->timeOn = v; +} + +void BLINKER_setTimeOff(BLINKER* me, uint16_t v) { + me->timeOff = v; +} + +void BLINKER_setNumberOfBlink(BLINKER* me, uint8_t v) { + me->numberOfBlink = v; +} + +void BLINKER_setNBlinkIsOn(BLINKER* me, bool v) { + me->nBlinkIsOn = v; +} + +void BLINKER_setRemainBlinks(BLINKER* me, uint8_t v) { + me->remainBlinks = v; +} + + +void BLINKER_endBlink(BLINKER* me) { + me->remainBlinks = 0; +} diff --git a/306-controller_interface.X/middleware/blinker.h b/306-controller_interface.X/middleware/blinker.h new file mode 100644 index 0000000..4b2366e --- /dev/null +++ b/306-controller_interface.X/middleware/blinker.h @@ -0,0 +1,167 @@ +/** + * @author Rémi Heredero + * @version 1.0.0 + * @date July 2023 + * @file blinker.h + */ +#ifndef BLINKER_H +#define BLINKER_H + +#include "../xf/xf.h" + +typedef enum { + STBL_INIT, + STBL_WAIT, + STBL_ON, + STBL_OFF +} BLINKER_STATES; + +typedef enum { + evBLinit = 200, + evBLblink, + evBLblinkN, + evBLtimer +} BLINKER_EVENTS; + +typedef void (*BLINKER_CALLBACK_FUNCTION)(void*); +typedef struct { + BLINKER_CALLBACK_FUNCTION f; // function + void* p; // param(s) +} BLINKER_CALLBACK; + +typedef struct { + BLINKER_STATES state; //Actual state + uint16_t timeOn; // Time on + uint16_t timeOff; // Time off + uint8_t numberOfBlink; // Number of blink for this blinker when start with blinkN + bool nBlinkIsOn; // If the nBlink way is enable + uint8_t remainBlinks; // Actual remain blink + BLINKER_CALLBACK wait; + BLINKER_CALLBACK on; + BLINKER_CALLBACK off; + BLINKER_CALLBACK finished; +} BLINKER; + +/** + * Initialize the BLINKER + * @param me the BLINKER itself + */ +void BLINKER_init(BLINKER* me); + +/** + * Start the BLINKER state machine + * @param me the BLINKER itself + */ +void BLINKER_startBehaviour(BLINKER* me); + +/** + * Process the event + * @param ev the event to process + * @return true if the event is processed + */ +bool BLINKER_processEvent(Event* ev); + +/************* + * Callbacks * + *************/ + +/** + * Set the callback function to call when the BLINKER is entering state wait + * @param me the BLINKER itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void BLINKER_onWait(BLINKER* me, BLINKER_CALLBACK_FUNCTION f, void* p); + +/** + * Set the callback function to call when the BLINKER is entering state on + * @param me the BLINKER itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void BLINKER_onOn(BLINKER* me, BLINKER_CALLBACK_FUNCTION f, void* p); + +/** + * Set the callback function to call when the BLINKER is entering state off + * @param me the BLINKER itself + * @param f the function to call + * @param p the param(s) to pass to the function + */ +void BLINKER_onOff(BLINKER* me, BLINKER_CALLBACK_FUNCTION f, void* p); + +/** + * Set the callabck function to call when the BLINKER is entering state finished + * @param me the BLINKER itself + * @param f the function to call + * @param t the param(s) to pass to the function + */ +void BLINKER_onFinished(BLINKER* me, BLINKER_CALLBACK_FUNCTION f, void* p); + +/************ + * EMITTERS * + ************/ + +/** + * Emit the blink event + * @param me the BLINKER itself + * @param t time to wait in ms before triggering event + */void BLINKER_emitBlink(BLINKER* me, uint16_t t); + +/** + * Emit the blinkn event + * @param me the BLINKER itself + * @param t time to wait in ms before triggering event + */void BLINKER_emitBlinkN(BLINKER* me, uint16_t t); + +/** + * Emit the timer event + * @param me the BLINKER itself + * @param t time to wait in ms before triggering event + */void BLINKER_emitTimer(BLINKER* me, uint16_t t); + +/*********** + * SETTERS * + ***********/ + +/** + * Set the time on + * @param me the BLINKER itself + * @param v the value to set + */ +void BLINKER_setTimeOn(BLINKER* me, uint16_t v); + +/** + * Set the time off + * @param me the BLINKER itself + * @param v the value to set + */ +void BLINKER_setTimeOff(BLINKER* me, uint16_t v); + +/** + * Set the number of blink + * @param me the BLINKER itself + * @param v the value to set + */ +void BLINKER_setNumberOfBlink(BLINKER* me, uint8_t v); + +/** + * Set the nBlinkIsOn + * @param me the BLINKER itself + * @param v the value to set + */ +void BLINKER_setNBlinkIsOn(BLINKER* me, bool v); + +/** + * Set the remain blink(s) + * @param me the BLINKER itself + * @param v the value to set + */ +void BLINKER_setRemainBlinks(BLINKER* me, uint8_t v); + +/** + * Stop to blink if it was indefinitely blinking + * @param me the blinker itself + */ +void BLINKER_endBlink(BLINKER* me); + +#endif diff --git a/306-controller_interface.X/middleware/can_interface.c b/306-controller_interface.X/middleware/can_interface.c index 0847b1f..6c893fd 100644 --- a/306-controller_interface.X/middleware/can_interface.c +++ b/306-controller_interface.X/middleware/can_interface.c @@ -146,13 +146,13 @@ void CAN_newMsg() { CAN_receive(&canMsg); data = canMsg.frame.id; data = data<<12; - data = data | canMsg.frame.data0; - data = data<<8; - data = data | canMsg.frame.data1; + data = data | canMsg.frame.data3; data = data<<8; data = data | canMsg.frame.data2; data = data<<8; - data = data | canMsg.frame.data3; + data = data | canMsg.frame.data1; + data = data<<8; + data = data | canMsg.frame.data0; POST(&CAN_myself, &CAN_processEvent, evCAnewMsg, 0, data); } diff --git a/306-controller_interface.X/middleware/watchdog.c b/306-controller_interface.X/middleware/watchdog.c deleted file mode 100644 index 5840bf5..0000000 --- a/306-controller_interface.X/middleware/watchdog.c +++ /dev/null @@ -1,90 +0,0 @@ -/** - * @author Rémi Heredero - * @version 1.0.0 - * @date August 2023 - * @file watchdog.c - */ - -#include "watchdog.h" - -void WATCHDOG_init(WATCHDOG* me){ - me->state = STWD_INIT; - me->time = 10; - me->alive.f = NULL; -} - -void WATCHDOG_startBehaviour(WATCHDOG* me){ - POST(me, &WATCHDOG_processEvent, evWDinit, 0, 0); -} - -bool WATCHDOG_processEvent(Event* ev) { - bool processed = false; - WATCHDOG* me = (WATCHDOG*)Event_getTarget(ev); - WATCHDOG_STATES oldState = me->state; - evIDT evid = Event_getId(ev); - uint64_t data = Event_getData(ev); - - switch (me->state) { // onState - case STWD_INIT: - if (ev->id == evWDinit) { - me->state = STWD_ALIVE; - WATCHDOG_emitPoll(me, 10*me->time, 0); - } - break; - - case STWD_ALIVE: - if (ev->id == evWDpoll) { - WATCHDOG_emitPoll(me, 10*me->time, 0); - if (me->alive.f != NULL) { - me->alive.f(me->alive.p); - } - } - break; - } - - if(oldState != me->state){ - switch (oldState) { // onExit - case STWD_INIT: - break; - - case STWD_ALIVE: - break; - } - - switch (me->state) { // onEntry - case STWD_INIT: - break; - - case STWD_ALIVE: - break; - } - - processed = true; - } - return processed; -} - -/************* - * Callbacks * - *************/ - -void WATCHDOG_onAlive(WATCHDOG* me, WATCHDOG_CALLBACK_FUNCTION f, void* p) { - me->alive.f = f; - me->alive.p = p; -} - -/************ - * EMITTERS * - ************/ - -void WATCHDOG_emitPoll(WATCHDOG* me, uint16_t t, int64_t data) { - POST(me, &WATCHDOG_processEvent, evWDpoll, t, data); -} - -/*********** - * SETTERS * - ***********/ - -void WATCHDOG_setTime(WATCHDOG* me, uint8_t v) { - me->time = v; -} diff --git a/306-controller_interface.X/middleware/watchdog.h b/306-controller_interface.X/middleware/watchdog.h deleted file mode 100644 index ed2d184..0000000 --- a/306-controller_interface.X/middleware/watchdog.h +++ /dev/null @@ -1,83 +0,0 @@ -/** - * @author Rémi Heredero - * @version 1.0.0 - * @date August 2023 - * @file watchdog.h - */ -#ifndef WATCHDOG_H -#define WATCHDOG_H - -#include "../xf/xf.h" - -typedef enum { - STWD_INIT, - STWD_ALIVE -} WATCHDOG_STATES; - -typedef enum { - evWDinit = 20, - evWDpoll -} WATCHDOG_EVENTS; - -typedef void (*WATCHDOG_CALLBACK_FUNCTION)(void*); -typedef struct { - WATCHDOG_CALLBACK_FUNCTION f; // function - void* p; // param(s) -} WATCHDOG_CALLBACK; - -typedef struct { - WATCHDOG_STATES state; - uint8_t time; - WATCHDOG_CALLBACK alive; -} WATCHDOG; - -/** - * Initialize the WATCHDOG - * @param me the WATCHDOG itself - */ -void WATCHDOG_init(WATCHDOG* me); - -/** - * Start the WATCHDOG state machine - * @param me the WATCHDOG itself - */ -void WATCHDOG_startBehaviour(WATCHDOG* me); - -/** - * Process the event - * @param ev the event to process - * @return true if the event is processed - */ -bool WATCHDOG_processEvent(Event* ev); - -/************* - * Callbacks * - *************/ - -/** - * Set the callback function to call when the WATCHDOG is entering state alive - * @param me the WATCHDOG itself - * @param f the function to call - * @param p the param(s) to pass to the function - */ -void WATCHDOG_onAlive(WATCHDOG* me, WATCHDOG_CALLBACK_FUNCTION f, void* p); - -/************ - * EMITTERS * - ************/ - -/** - * Emit the poll event - * @param me the WATCHDOG itself - * @param t time to wait in ms before triggering event - * @param data data to put on the event for XF - */ -void WATCHDOG_emitPoll(WATCHDOG* me, uint16_t t, int64_t data); - -/*********** - * SETTERS * - ***********/ - -void WATCHDOG_setTime(WATCHDOG* me, uint8_t v); - -#endif diff --git a/306-controller_interface.X/nbproject/Makefile-default.mk b/306-controller_interface.X/nbproject/Makefile-default.mk new file mode 100644 index 0000000..17547ef --- /dev/null +++ b/306-controller_interface.X/nbproject/Makefile-default.mk @@ -0,0 +1,444 @@ +# +# Generated Makefile - do not edit! +# +# Edit the Makefile in the project folder instead (../Makefile). Each target +# has a -pre and a -post target defined where you can add customized code. +# +# This makefile implements configuration specific macros and targets. + + +# Include project Makefile +ifeq "${IGNORE_LOCAL}" "TRUE" +# do not include local makefile. User is passing all local related variables already +else +include Makefile +# Include makefile containing local settings +ifeq "$(wildcard nbproject/Makefile-local-default.mk)" "nbproject/Makefile-local-default.mk" +include nbproject/Makefile-local-default.mk +endif +endif + +# Environment +MKDIR=gnumkdir -p +RM=rm -f +MV=mv +CP=cp + +# Macros +CND_CONF=default +ifeq ($(TYPE_IMAGE), DEBUG_RUN) +IMAGE_TYPE=debug +OUTPUT_SUFFIX=elf +DEBUGGABLE_SUFFIX=elf +FINAL_IMAGE=${DISTDIR}/306-controller_interface.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX} +else +IMAGE_TYPE=production +OUTPUT_SUFFIX=hex +DEBUGGABLE_SUFFIX=elf +FINAL_IMAGE=${DISTDIR}/306-controller_interface.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX} +endif + +ifeq ($(COMPARE_BUILD), true) +COMPARISON_BUILD=-mafrlcsj +else +COMPARISON_BUILD= +endif + +# Object Directory +OBJECTDIR=build/${CND_CONF}/${IMAGE_TYPE} + +# Distribution Directory +DISTDIR=dist/${CND_CONF}/${IMAGE_TYPE} + +# Source Files Quoted if spaced +SOURCEFILES_QUOTED_IF_SPACED=app/factory/factory.c app/can_message.c app/kartculator.c app/eeprom.c app/drive.c board/led/led.c mcc_generated_files/interrupt_manager.c mcc_generated_files/tmr0.c mcc_generated_files/pin_manager.c mcc_generated_files/device_config.c mcc_generated_files/mcc.c mcc_generated_files/ecan.c mcc_generated_files/memory.c middleware/can_interface.c middleware/alive.c middleware/blinker.c xf/event.c xf/xf.c main.c + +# Object Files Quoted if spaced +OBJECTFILES_QUOTED_IF_SPACED=${OBJECTDIR}/app/factory/factory.p1 ${OBJECTDIR}/app/can_message.p1 ${OBJECTDIR}/app/kartculator.p1 ${OBJECTDIR}/app/eeprom.p1 ${OBJECTDIR}/app/drive.p1 ${OBJECTDIR}/board/led/led.p1 ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1 ${OBJECTDIR}/mcc_generated_files/tmr0.p1 ${OBJECTDIR}/mcc_generated_files/pin_manager.p1 ${OBJECTDIR}/mcc_generated_files/device_config.p1 ${OBJECTDIR}/mcc_generated_files/mcc.p1 ${OBJECTDIR}/mcc_generated_files/ecan.p1 ${OBJECTDIR}/mcc_generated_files/memory.p1 ${OBJECTDIR}/middleware/can_interface.p1 ${OBJECTDIR}/middleware/alive.p1 ${OBJECTDIR}/middleware/blinker.p1 ${OBJECTDIR}/xf/event.p1 ${OBJECTDIR}/xf/xf.p1 ${OBJECTDIR}/main.p1 +POSSIBLE_DEPFILES=${OBJECTDIR}/app/factory/factory.p1.d ${OBJECTDIR}/app/can_message.p1.d ${OBJECTDIR}/app/kartculator.p1.d ${OBJECTDIR}/app/eeprom.p1.d ${OBJECTDIR}/app/drive.p1.d ${OBJECTDIR}/board/led/led.p1.d ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1.d ${OBJECTDIR}/mcc_generated_files/tmr0.p1.d ${OBJECTDIR}/mcc_generated_files/pin_manager.p1.d ${OBJECTDIR}/mcc_generated_files/device_config.p1.d ${OBJECTDIR}/mcc_generated_files/mcc.p1.d ${OBJECTDIR}/mcc_generated_files/ecan.p1.d ${OBJECTDIR}/mcc_generated_files/memory.p1.d ${OBJECTDIR}/middleware/can_interface.p1.d ${OBJECTDIR}/middleware/alive.p1.d ${OBJECTDIR}/middleware/blinker.p1.d ${OBJECTDIR}/xf/event.p1.d ${OBJECTDIR}/xf/xf.p1.d ${OBJECTDIR}/main.p1.d + +# Object Files +OBJECTFILES=${OBJECTDIR}/app/factory/factory.p1 ${OBJECTDIR}/app/can_message.p1 ${OBJECTDIR}/app/kartculator.p1 ${OBJECTDIR}/app/eeprom.p1 ${OBJECTDIR}/app/drive.p1 ${OBJECTDIR}/board/led/led.p1 ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1 ${OBJECTDIR}/mcc_generated_files/tmr0.p1 ${OBJECTDIR}/mcc_generated_files/pin_manager.p1 ${OBJECTDIR}/mcc_generated_files/device_config.p1 ${OBJECTDIR}/mcc_generated_files/mcc.p1 ${OBJECTDIR}/mcc_generated_files/ecan.p1 ${OBJECTDIR}/mcc_generated_files/memory.p1 ${OBJECTDIR}/middleware/can_interface.p1 ${OBJECTDIR}/middleware/alive.p1 ${OBJECTDIR}/middleware/blinker.p1 ${OBJECTDIR}/xf/event.p1 ${OBJECTDIR}/xf/xf.p1 ${OBJECTDIR}/main.p1 + +# Source Files +SOURCEFILES=app/factory/factory.c app/can_message.c app/kartculator.c app/eeprom.c app/drive.c board/led/led.c mcc_generated_files/interrupt_manager.c mcc_generated_files/tmr0.c mcc_generated_files/pin_manager.c mcc_generated_files/device_config.c mcc_generated_files/mcc.c mcc_generated_files/ecan.c mcc_generated_files/memory.c middleware/can_interface.c middleware/alive.c middleware/blinker.c xf/event.c xf/xf.c main.c + + + +CFLAGS= +ASFLAGS= +LDLIBSOPTIONS= + +############# Tool locations ########################################## +# If you copy a project from one host to another, the path where the # +# compiler is installed may be different. # +# If you open this project with MPLAB X in the new host, this # +# makefile will be regenerated and the paths will be corrected. # +####################################################################### +# fixDeps replaces a bunch of sed/cat/printf statements that slow down the build +FIXDEPS=fixDeps + +.build-conf: ${BUILD_SUBPROJECTS} +ifneq ($(INFORMATION_MESSAGE), ) + @echo $(INFORMATION_MESSAGE) +endif + ${MAKE} -f nbproject/Makefile-default.mk ${DISTDIR}/306-controller_interface.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX} + +MP_PROCESSOR_OPTION=18F26K83 +# ------------------------------------------------------------------------------------ +# Rules for buildStep: compile +ifeq ($(TYPE_IMAGE), DEBUG_RUN) +${OBJECTDIR}/app/factory/factory.p1: app/factory/factory.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/app/factory" + @${RM} ${OBJECTDIR}/app/factory/factory.p1.d + @${RM} ${OBJECTDIR}/app/factory/factory.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/app/factory/factory.p1 app/factory/factory.c + @-${MV} ${OBJECTDIR}/app/factory/factory.d ${OBJECTDIR}/app/factory/factory.p1.d + @${FIXDEPS} ${OBJECTDIR}/app/factory/factory.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/app/can_message.p1: app/can_message.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/app" + @${RM} ${OBJECTDIR}/app/can_message.p1.d + @${RM} ${OBJECTDIR}/app/can_message.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/app/can_message.p1 app/can_message.c + @-${MV} ${OBJECTDIR}/app/can_message.d ${OBJECTDIR}/app/can_message.p1.d + @${FIXDEPS} ${OBJECTDIR}/app/can_message.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/app/kartculator.p1: app/kartculator.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/app" + @${RM} ${OBJECTDIR}/app/kartculator.p1.d + @${RM} ${OBJECTDIR}/app/kartculator.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/app/kartculator.p1 app/kartculator.c + @-${MV} ${OBJECTDIR}/app/kartculator.d ${OBJECTDIR}/app/kartculator.p1.d + @${FIXDEPS} ${OBJECTDIR}/app/kartculator.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/app/eeprom.p1: app/eeprom.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/app" + @${RM} ${OBJECTDIR}/app/eeprom.p1.d + @${RM} ${OBJECTDIR}/app/eeprom.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/app/eeprom.p1 app/eeprom.c + @-${MV} ${OBJECTDIR}/app/eeprom.d ${OBJECTDIR}/app/eeprom.p1.d + @${FIXDEPS} ${OBJECTDIR}/app/eeprom.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/app/drive.p1: app/drive.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/app" + @${RM} ${OBJECTDIR}/app/drive.p1.d + @${RM} ${OBJECTDIR}/app/drive.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/app/drive.p1 app/drive.c + @-${MV} ${OBJECTDIR}/app/drive.d ${OBJECTDIR}/app/drive.p1.d + @${FIXDEPS} ${OBJECTDIR}/app/drive.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/board/led/led.p1: board/led/led.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/board/led" + @${RM} ${OBJECTDIR}/board/led/led.p1.d + @${RM} ${OBJECTDIR}/board/led/led.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/board/led/led.p1 board/led/led.c + @-${MV} ${OBJECTDIR}/board/led/led.d ${OBJECTDIR}/board/led/led.p1.d + @${FIXDEPS} ${OBJECTDIR}/board/led/led.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1: mcc_generated_files/interrupt_manager.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1 mcc_generated_files/interrupt_manager.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/interrupt_manager.d ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/tmr0.p1: mcc_generated_files/tmr0.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/tmr0.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/tmr0.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/tmr0.p1 mcc_generated_files/tmr0.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/tmr0.d ${OBJECTDIR}/mcc_generated_files/tmr0.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/tmr0.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/pin_manager.p1: mcc_generated_files/pin_manager.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/pin_manager.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/pin_manager.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/pin_manager.p1 mcc_generated_files/pin_manager.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/pin_manager.d ${OBJECTDIR}/mcc_generated_files/pin_manager.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/pin_manager.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/device_config.p1: mcc_generated_files/device_config.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/device_config.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/device_config.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/device_config.p1 mcc_generated_files/device_config.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/device_config.d ${OBJECTDIR}/mcc_generated_files/device_config.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/device_config.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/mcc.p1: mcc_generated_files/mcc.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/mcc.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/mcc.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/mcc.p1 mcc_generated_files/mcc.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/mcc.d ${OBJECTDIR}/mcc_generated_files/mcc.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/mcc.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/ecan.p1: mcc_generated_files/ecan.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/ecan.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/ecan.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/ecan.p1 mcc_generated_files/ecan.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/ecan.d ${OBJECTDIR}/mcc_generated_files/ecan.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/ecan.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/memory.p1: mcc_generated_files/memory.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/memory.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/memory.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/memory.p1 mcc_generated_files/memory.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/memory.d ${OBJECTDIR}/mcc_generated_files/memory.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/memory.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/middleware/can_interface.p1: middleware/can_interface.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/middleware" + @${RM} ${OBJECTDIR}/middleware/can_interface.p1.d + @${RM} ${OBJECTDIR}/middleware/can_interface.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/middleware/can_interface.p1 middleware/can_interface.c + @-${MV} ${OBJECTDIR}/middleware/can_interface.d ${OBJECTDIR}/middleware/can_interface.p1.d + @${FIXDEPS} ${OBJECTDIR}/middleware/can_interface.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/middleware/alive.p1: middleware/alive.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/middleware" + @${RM} ${OBJECTDIR}/middleware/alive.p1.d + @${RM} ${OBJECTDIR}/middleware/alive.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/middleware/alive.p1 middleware/alive.c + @-${MV} ${OBJECTDIR}/middleware/alive.d ${OBJECTDIR}/middleware/alive.p1.d + @${FIXDEPS} ${OBJECTDIR}/middleware/alive.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/middleware/blinker.p1: middleware/blinker.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/middleware" + @${RM} ${OBJECTDIR}/middleware/blinker.p1.d + @${RM} ${OBJECTDIR}/middleware/blinker.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/middleware/blinker.p1 middleware/blinker.c + @-${MV} ${OBJECTDIR}/middleware/blinker.d ${OBJECTDIR}/middleware/blinker.p1.d + @${FIXDEPS} ${OBJECTDIR}/middleware/blinker.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/xf/event.p1: xf/event.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/xf" + @${RM} ${OBJECTDIR}/xf/event.p1.d + @${RM} ${OBJECTDIR}/xf/event.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/xf/event.p1 xf/event.c + @-${MV} ${OBJECTDIR}/xf/event.d ${OBJECTDIR}/xf/event.p1.d + @${FIXDEPS} ${OBJECTDIR}/xf/event.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/xf/xf.p1: xf/xf.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/xf" + @${RM} ${OBJECTDIR}/xf/xf.p1.d + @${RM} ${OBJECTDIR}/xf/xf.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/xf/xf.p1 xf/xf.c + @-${MV} ${OBJECTDIR}/xf/xf.d ${OBJECTDIR}/xf/xf.p1.d + @${FIXDEPS} ${OBJECTDIR}/xf/xf.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/main.p1: main.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}" + @${RM} ${OBJECTDIR}/main.p1.d + @${RM} ${OBJECTDIR}/main.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -D__DEBUG=1 -mdebugger=pickit3 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/main.p1 main.c + @-${MV} ${OBJECTDIR}/main.d ${OBJECTDIR}/main.p1.d + @${FIXDEPS} ${OBJECTDIR}/main.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +else +${OBJECTDIR}/app/factory/factory.p1: app/factory/factory.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/app/factory" + @${RM} ${OBJECTDIR}/app/factory/factory.p1.d + @${RM} ${OBJECTDIR}/app/factory/factory.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/app/factory/factory.p1 app/factory/factory.c + @-${MV} ${OBJECTDIR}/app/factory/factory.d ${OBJECTDIR}/app/factory/factory.p1.d + @${FIXDEPS} ${OBJECTDIR}/app/factory/factory.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/app/can_message.p1: app/can_message.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/app" + @${RM} ${OBJECTDIR}/app/can_message.p1.d + @${RM} ${OBJECTDIR}/app/can_message.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/app/can_message.p1 app/can_message.c + @-${MV} ${OBJECTDIR}/app/can_message.d ${OBJECTDIR}/app/can_message.p1.d + @${FIXDEPS} ${OBJECTDIR}/app/can_message.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/app/kartculator.p1: app/kartculator.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/app" + @${RM} ${OBJECTDIR}/app/kartculator.p1.d + @${RM} ${OBJECTDIR}/app/kartculator.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/app/kartculator.p1 app/kartculator.c + @-${MV} ${OBJECTDIR}/app/kartculator.d ${OBJECTDIR}/app/kartculator.p1.d + @${FIXDEPS} ${OBJECTDIR}/app/kartculator.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/app/eeprom.p1: app/eeprom.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/app" + @${RM} ${OBJECTDIR}/app/eeprom.p1.d + @${RM} ${OBJECTDIR}/app/eeprom.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/app/eeprom.p1 app/eeprom.c + @-${MV} ${OBJECTDIR}/app/eeprom.d ${OBJECTDIR}/app/eeprom.p1.d + @${FIXDEPS} ${OBJECTDIR}/app/eeprom.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/app/drive.p1: app/drive.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/app" + @${RM} ${OBJECTDIR}/app/drive.p1.d + @${RM} ${OBJECTDIR}/app/drive.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/app/drive.p1 app/drive.c + @-${MV} ${OBJECTDIR}/app/drive.d ${OBJECTDIR}/app/drive.p1.d + @${FIXDEPS} ${OBJECTDIR}/app/drive.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/board/led/led.p1: board/led/led.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/board/led" + @${RM} ${OBJECTDIR}/board/led/led.p1.d + @${RM} ${OBJECTDIR}/board/led/led.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/board/led/led.p1 board/led/led.c + @-${MV} ${OBJECTDIR}/board/led/led.d ${OBJECTDIR}/board/led/led.p1.d + @${FIXDEPS} ${OBJECTDIR}/board/led/led.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1: mcc_generated_files/interrupt_manager.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1 mcc_generated_files/interrupt_manager.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/interrupt_manager.d ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/interrupt_manager.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/tmr0.p1: mcc_generated_files/tmr0.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/tmr0.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/tmr0.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/tmr0.p1 mcc_generated_files/tmr0.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/tmr0.d ${OBJECTDIR}/mcc_generated_files/tmr0.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/tmr0.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/pin_manager.p1: mcc_generated_files/pin_manager.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/pin_manager.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/pin_manager.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/pin_manager.p1 mcc_generated_files/pin_manager.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/pin_manager.d ${OBJECTDIR}/mcc_generated_files/pin_manager.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/pin_manager.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/device_config.p1: mcc_generated_files/device_config.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/device_config.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/device_config.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/device_config.p1 mcc_generated_files/device_config.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/device_config.d ${OBJECTDIR}/mcc_generated_files/device_config.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/device_config.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/mcc.p1: mcc_generated_files/mcc.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/mcc.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/mcc.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/mcc.p1 mcc_generated_files/mcc.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/mcc.d ${OBJECTDIR}/mcc_generated_files/mcc.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/mcc.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/ecan.p1: mcc_generated_files/ecan.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/ecan.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/ecan.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/ecan.p1 mcc_generated_files/ecan.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/ecan.d ${OBJECTDIR}/mcc_generated_files/ecan.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/ecan.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/mcc_generated_files/memory.p1: mcc_generated_files/memory.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/mcc_generated_files" + @${RM} ${OBJECTDIR}/mcc_generated_files/memory.p1.d + @${RM} ${OBJECTDIR}/mcc_generated_files/memory.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/mcc_generated_files/memory.p1 mcc_generated_files/memory.c + @-${MV} ${OBJECTDIR}/mcc_generated_files/memory.d ${OBJECTDIR}/mcc_generated_files/memory.p1.d + @${FIXDEPS} ${OBJECTDIR}/mcc_generated_files/memory.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/middleware/can_interface.p1: middleware/can_interface.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/middleware" + @${RM} ${OBJECTDIR}/middleware/can_interface.p1.d + @${RM} ${OBJECTDIR}/middleware/can_interface.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/middleware/can_interface.p1 middleware/can_interface.c + @-${MV} ${OBJECTDIR}/middleware/can_interface.d ${OBJECTDIR}/middleware/can_interface.p1.d + @${FIXDEPS} ${OBJECTDIR}/middleware/can_interface.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/middleware/alive.p1: middleware/alive.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/middleware" + @${RM} ${OBJECTDIR}/middleware/alive.p1.d + @${RM} ${OBJECTDIR}/middleware/alive.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/middleware/alive.p1 middleware/alive.c + @-${MV} ${OBJECTDIR}/middleware/alive.d ${OBJECTDIR}/middleware/alive.p1.d + @${FIXDEPS} ${OBJECTDIR}/middleware/alive.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/middleware/blinker.p1: middleware/blinker.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/middleware" + @${RM} ${OBJECTDIR}/middleware/blinker.p1.d + @${RM} ${OBJECTDIR}/middleware/blinker.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/middleware/blinker.p1 middleware/blinker.c + @-${MV} ${OBJECTDIR}/middleware/blinker.d ${OBJECTDIR}/middleware/blinker.p1.d + @${FIXDEPS} ${OBJECTDIR}/middleware/blinker.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/xf/event.p1: xf/event.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/xf" + @${RM} ${OBJECTDIR}/xf/event.p1.d + @${RM} ${OBJECTDIR}/xf/event.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/xf/event.p1 xf/event.c + @-${MV} ${OBJECTDIR}/xf/event.d ${OBJECTDIR}/xf/event.p1.d + @${FIXDEPS} ${OBJECTDIR}/xf/event.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/xf/xf.p1: xf/xf.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}/xf" + @${RM} ${OBJECTDIR}/xf/xf.p1.d + @${RM} ${OBJECTDIR}/xf/xf.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/xf/xf.p1 xf/xf.c + @-${MV} ${OBJECTDIR}/xf/xf.d ${OBJECTDIR}/xf/xf.p1.d + @${FIXDEPS} ${OBJECTDIR}/xf/xf.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +${OBJECTDIR}/main.p1: main.c nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} "${OBJECTDIR}" + @${RM} ${OBJECTDIR}/main.p1.d + @${RM} ${OBJECTDIR}/main.p1 + ${MP_CC} $(MP_EXTRA_CC_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -c -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -DXPRJ_default=$(CND_CONF) -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits $(COMPARISON_BUILD) -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto -o ${OBJECTDIR}/main.p1 main.c + @-${MV} ${OBJECTDIR}/main.d ${OBJECTDIR}/main.p1.d + @${FIXDEPS} ${OBJECTDIR}/main.p1.d $(SILENT) -rsi ${MP_CC_DIR}../ + +endif + +# ------------------------------------------------------------------------------------ +# Rules for buildStep: assemble +ifeq ($(TYPE_IMAGE), DEBUG_RUN) +else +endif + +# ------------------------------------------------------------------------------------ +# Rules for buildStep: assembleWithPreprocess +ifeq ($(TYPE_IMAGE), DEBUG_RUN) +else +endif + +# ------------------------------------------------------------------------------------ +# Rules for buildStep: link +ifeq ($(TYPE_IMAGE), DEBUG_RUN) +${DISTDIR}/306-controller_interface.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX}: ${OBJECTFILES} nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} ${DISTDIR} + ${MP_CC} $(MP_EXTRA_LD_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -Wl,-Map=${DISTDIR}/306-controller_interface.X.${IMAGE_TYPE}.map -D__DEBUG=1 -mdebugger=pickit3 -DXPRJ_default=$(CND_CONF) -Wl,--defsym=__MPLAB_BUILD=1 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto $(COMPARISON_BUILD) -Wl,--memorysummary,${DISTDIR}/memoryfile.xml -o ${DISTDIR}/306-controller_interface.X.${IMAGE_TYPE}.${DEBUGGABLE_SUFFIX} ${OBJECTFILES_QUOTED_IF_SPACED} + @${RM} ${DISTDIR}/306-controller_interface.X.${IMAGE_TYPE}.hex + +else +${DISTDIR}/306-controller_interface.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX}: ${OBJECTFILES} nbproject/Makefile-${CND_CONF}.mk + @${MKDIR} ${DISTDIR} + ${MP_CC} $(MP_EXTRA_LD_PRE) -mcpu=$(MP_PROCESSOR_OPTION) -Wl,-Map=${DISTDIR}/306-controller_interface.X.${IMAGE_TYPE}.map -DXPRJ_default=$(CND_CONF) -Wl,--defsym=__MPLAB_BUILD=1 -mdfp="${DFP_DIR}/xc8" -fno-short-double -fno-short-float -memi=wordwrite -O0 -fasmfile -maddrqual=ignore -xassembler-with-cpp -mwarn=3 -Wa,-a -msummary=-psect,-class,+mem,-hex,-file -ginhx32 -Wl,--data-init -mno-keep-startup -mno-download -mdefault-config-bits -std=c99 -gdwarf-3 -mstack=compiled:auto:auto:auto $(COMPARISON_BUILD) -Wl,--memorysummary,${DISTDIR}/memoryfile.xml -o ${DISTDIR}/306-controller_interface.X.${IMAGE_TYPE}.${DEBUGGABLE_SUFFIX} ${OBJECTFILES_QUOTED_IF_SPACED} + +endif + + +# Subprojects +.build-subprojects: + + +# Subprojects +.clean-subprojects: + +# Clean Targets +.clean-conf: ${CLEAN_SUBPROJECTS} + ${RM} -r ${OBJECTDIR} + ${RM} -r ${DISTDIR} + +# Enable dependency checking +.dep.inc: .depcheck-impl + +DEPFILES=$(wildcard ${POSSIBLE_DEPFILES}) +ifneq (${DEPFILES},) +include ${DEPFILES} +endif diff --git a/306-controller_interface.X/nbproject/Makefile-impl.mk b/306-controller_interface.X/nbproject/Makefile-impl.mk new file mode 100644 index 0000000..d489d6a --- /dev/null +++ b/306-controller_interface.X/nbproject/Makefile-impl.mk @@ -0,0 +1,69 @@ +# +# Generated Makefile - do not edit! +# +# Edit the Makefile in the project folder instead (../Makefile). Each target +# has a pre- and a post- target defined where you can add customization code. +# +# This makefile implements macros and targets common to all configurations. +# +# NOCDDL + + +# Building and Cleaning subprojects are done by default, but can be controlled with the SUB +# macro. If SUB=no, subprojects will not be built or cleaned. The following macro +# statements set BUILD_SUB-CONF and CLEAN_SUB-CONF to .build-reqprojects-conf +# and .clean-reqprojects-conf unless SUB has the value 'no' +SUB_no=NO +SUBPROJECTS=${SUB_${SUB}} +BUILD_SUBPROJECTS_=.build-subprojects +BUILD_SUBPROJECTS_NO= +BUILD_SUBPROJECTS=${BUILD_SUBPROJECTS_${SUBPROJECTS}} +CLEAN_SUBPROJECTS_=.clean-subprojects +CLEAN_SUBPROJECTS_NO= +CLEAN_SUBPROJECTS=${CLEAN_SUBPROJECTS_${SUBPROJECTS}} + + +# Project Name +PROJECTNAME=306-controller_interface.X + +# Active Configuration +DEFAULTCONF=default +CONF=${DEFAULTCONF} + +# All Configurations +ALLCONFS=default + + +# build +.build-impl: .build-pre + ${MAKE} -f nbproject/Makefile-${CONF}.mk SUBPROJECTS=${SUBPROJECTS} .build-conf + + +# clean +.clean-impl: .clean-pre + ${MAKE} -f nbproject/Makefile-${CONF}.mk SUBPROJECTS=${SUBPROJECTS} .clean-conf + +# clobber +.clobber-impl: .clobber-pre .depcheck-impl + ${MAKE} SUBPROJECTS=${SUBPROJECTS} CONF=default clean + + + +# all +.all-impl: .all-pre .depcheck-impl + ${MAKE} SUBPROJECTS=${SUBPROJECTS} CONF=default build + + + +# dependency checking support +.depcheck-impl: +# @echo "# This code depends on make tool being used" >.dep.inc +# @if [ -n "${MAKE_VERSION}" ]; then \ +# echo "DEPFILES=\$$(wildcard \$$(addsuffix .d, \$${OBJECTFILES}))" >>.dep.inc; \ +# echo "ifneq (\$${DEPFILES},)" >>.dep.inc; \ +# echo "include \$${DEPFILES}" >>.dep.inc; \ +# echo "endif" >>.dep.inc; \ +# else \ +# echo ".KEEP_STATE:" >>.dep.inc; \ +# echo ".KEEP_STATE_FILE:.make.state.\$${CONF}" >>.dep.inc; \ +# fi diff --git a/306-controller_interface.X/nbproject/Makefile-local-default.mk b/306-controller_interface.X/nbproject/Makefile-local-default.mk new file mode 100644 index 0000000..14e862a --- /dev/null +++ b/306-controller_interface.X/nbproject/Makefile-local-default.mk @@ -0,0 +1,37 @@ +# +# Generated Makefile - do not edit! +# +# +# This file contains information about the location of compilers and other tools. +# If you commmit this file into your revision control server, you will be able to +# to checkout the project and build it from the command line with make. However, +# if more than one person works on the same project, then this file might show +# conflicts since different users are bound to have compilers in different places. +# In that case you might choose to not commit this file and let MPLAB X recreate this file +# for each user. The disadvantage of not commiting this file is that you must run MPLAB X at +# least once so the file gets created and the project can be built. Finally, you can also +# avoid using this file at all if you are only building from the command line with make. +# You can invoke make with the values of the macros: +# $ makeMP_CC="/opt/microchip/mplabc30/v3.30c/bin/pic30-gcc" ... +# +SHELL=cmd.exe +PATH_TO_IDE_BIN=C:/Program Files/Microchip/MPLABX/v6.15/mplab_platform/platform/../mplab_ide/modules/../../bin/ +# Adding MPLAB X bin directory to path. +PATH:=C:/Program Files/Microchip/MPLABX/v6.15/mplab_platform/platform/../mplab_ide/modules/../../bin/:$(PATH) +# Path to java used to run MPLAB X when this makefile was created +MP_JAVA_PATH="C:\Program Files\Microchip\MPLABX\v6.15\sys\java\zulu8.64.0.19-ca-fx-jre8.0.345-win_x64/bin/" +OS_CURRENT="$(shell uname -s)" +MP_CC="C:\Program Files\Microchip\xc8\v2.41\bin\xc8-cc.exe" +# MP_CPPC is not defined +# MP_BC is not defined +MP_AS="C:\Program Files\Microchip\xc8\v2.41\bin\xc8-cc.exe" +MP_LD="C:\Program Files\Microchip\xc8\v2.41\bin\xc8-cc.exe" +MP_AR="C:\Program Files\Microchip\xc8\v2.41\bin\xc8-ar.exe" +DEP_GEN=${MP_JAVA_PATH}java -jar "C:/Program Files/Microchip/MPLABX/v6.15/mplab_platform/platform/../mplab_ide/modules/../../bin/extractobjectdependencies.jar" +MP_CC_DIR="C:\Program Files\Microchip\xc8\v2.41\bin" +# MP_CPPC_DIR is not defined +# MP_BC_DIR is not defined +MP_AS_DIR="C:\Program Files\Microchip\xc8\v2.41\bin" +MP_LD_DIR="C:\Program Files\Microchip\xc8\v2.41\bin" +MP_AR_DIR="C:\Program Files\Microchip\xc8\v2.41\bin" +DFP_DIR=C:/Users/remi.heredero/.mchp_packs/Microchip/PIC18F-K_DFP/1.7.134 diff --git a/306-controller_interface.X/nbproject/Makefile-variables.mk b/306-controller_interface.X/nbproject/Makefile-variables.mk new file mode 100644 index 0000000..de1b034 --- /dev/null +++ b/306-controller_interface.X/nbproject/Makefile-variables.mk @@ -0,0 +1,10 @@ +# +# Generated - do not edit! +# +# NOCDDL +# +CND_BASEDIR=`pwd` +# default configuration +CND_ARTIFACT_DIR_default=dist/default/production +CND_ARTIFACT_NAME_default=306-controller_interface.X.production.hex +CND_ARTIFACT_PATH_default=dist/default/production/306-controller_interface.X.production.hex diff --git a/306-controller_interface.X/nbproject/configurations.xml b/306-controller_interface.X/nbproject/configurations.xml index 4b844cc..2d248e4 100644 --- a/306-controller_interface.X/nbproject/configurations.xml +++ b/306-controller_interface.X/nbproject/configurations.xml @@ -8,6 +8,9 @@ app/factory/factory.h app/car.h app/can_message.h + app/kartculator.h + app/eeprom.h + app/drive.h board/led/led.h @@ -25,8 +28,8 @@ middleware/can_interface.h - middleware/alive_checker.h - middleware/watchdog.h + middleware/alive.h + middleware/blinker.h xf/event.h @@ -44,6 +47,9 @@ app/factory/factory.c app/can_message.c + app/kartculator.c + app/eeprom.c + app/drive.c board/led/led.c @@ -61,8 +67,8 @@ middleware/can_interface.c - middleware/alive_checker.c - middleware/watchdog.c + middleware/alive.c + middleware/blinker.c xf/event.c @@ -86,7 +92,7 @@ localhost - PIC18F25K83 + PIC18F26K83 PICkit3PlatformTool @@ -214,7 +220,10 @@ + + + @@ -236,7 +245,7 @@ - + @@ -244,7 +253,7 @@ - + @@ -258,8 +267,10 @@ - + + + @@ -281,7 +292,7 @@ - + @@ -289,7 +300,7 @@ - + diff --git a/306-controller_interface.X/ss22ep.mc3 b/306-controller_interface.X/ss22ep.mc3 index 6fedf69..2f25ff4 100644 --- a/306-controller_interface.X/ss22ep.mc3 +++ b/306-controller_interface.X/ss22ep.mc3 @@ -1,4 +1,4 @@ - + @@ -1948,7 +1948,7 @@ - {"dataArray":[{"DMA Channels":{"data":{"isDisable":"true","options":"--NONE--","text":"DMA CHANNEL1","value":"false"},"id":"DMA Channels_rowCount_0"},"Src Module":{"data":{"isDisable":"true","options":"--NONE--,TMR0,ECAN,MEMORY","text":"--NONE--","value":"--NONE--"},"id":"Src Module_rowCount_0"},"Src Region":{"data":{"isDisable":"true","options":"SFR#disabled,GPR#enabled,Program Flash#enabled,Data EEPROM#enabled","text":"GPR","value":"GPR"},"id":"Src Region_rowCount_0"},"Src SFR":{"Src SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Src SFR_rowCount_0"},"Src VarName":{"data":{"isDisable":"true","options":"","text":"SrcVarName0","value":"SrcVarName0"},"Src VarName":{"isDisable":"true","options":"","text":"SrcVarName0","value":"SrcVarName0"},"id":"Src VarName_rowCount_0"},"Src VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Src VarSize_rowCount_0","Src VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Src Address":{"data":{"isDisable":"true","options":"","text":"Enter Address0","value":"Enter Address0"},"id":"Src Address_rowCount_0","Src Address":{"isDisable":"true","options":"","text":"Enter Address0","value":"Enter Address0"}},"Src Mode":{"Src Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Src Mode_rowCount_0"},"Src Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Src Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Src Message Size_rowCount_0"},"Dst Module":{"data":{"isDisable":"true","options":"--NONE--,TMR0,ECAN,MEMORY","text":"--NONE--","value":"--NONE--"},"id":"Dst Module_rowCount_0"},"Dst Region":{"data":{"isDisable":"true","options":"SFR,GPR","text":"GPR","value":"GPR"},"id":"Dst Region_rowCount_0"},"Dst SFR":{"Dst SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Dst SFR_rowCount_0"},"Dst VarName":{"data":{"isDisable":"true","options":"","text":"DstVarName0","value":"DstVarName0"},"Dst VarName":{"isDisable":"true","options":"","text":"DstVarName0","value":"DstVarName0"},"id":"Dst VarName_rowCount_0"},"Dst VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Dst VarSize_rowCount_0","Dst VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Dst Mode":{"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"Dst Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Dst Mode_rowCount_0"},"Dst Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Dst Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Dst Message Size_rowCount_0"},"Start Trigger":{"Start Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Start Trigger_rowCount_0"},"Abort Trigger":{"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Abort Trigger_rowCount_0","Abort Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"}}},{"DMA Channels":{"data":{"isDisable":"true","options":"--NONE--","text":"DMA CHANNEL2","value":"false"},"id":"DMA Channels_rowCount_1"},"Src Module":{"data":{"isDisable":"true","options":"--NONE--,TMR0,ECAN,MEMORY","text":"--NONE--","value":"--NONE--"},"id":"Src Module_rowCount_1"},"Src Region":{"data":{"isDisable":"true","options":"SFR#disabled,GPR#enabled,Program Flash#enabled,Data EEPROM#enabled","text":"GPR","value":"GPR"},"id":"Src Region_rowCount_1"},"Src SFR":{"Src SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Src SFR_rowCount_1"},"Src VarName":{"data":{"isDisable":"true","options":"","text":"SrcVarName1","value":"SrcVarName1"},"Src VarName":{"isDisable":"true","options":"","text":"SrcVarName1","value":"SrcVarName1"},"id":"Src VarName_rowCount_1"},"Src VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Src VarSize_rowCount_1","Src VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Src Address":{"data":{"isDisable":"true","options":"","text":"Enter Address1","value":"Enter Address1"},"id":"Src Address_rowCount_1","Src Address":{"isDisable":"true","options":"","text":"Enter Address1","value":"Enter Address1"}},"Src Mode":{"Src Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Src Mode_rowCount_1"},"Src Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Src Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Src Message Size_rowCount_1"},"Dst Module":{"data":{"isDisable":"true","options":"--NONE--,TMR0,ECAN,MEMORY","text":"--NONE--","value":"--NONE--"},"id":"Dst Module_rowCount_1"},"Dst Region":{"data":{"isDisable":"true","options":"SFR,GPR","text":"GPR","value":"GPR"},"id":"Dst Region_rowCount_1"},"Dst SFR":{"Dst SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Dst SFR_rowCount_1"},"Dst VarName":{"data":{"isDisable":"true","options":"","text":"DstVarName1","value":"DstVarName1"},"Dst VarName":{"isDisable":"true","options":"","text":"DstVarName1","value":"DstVarName1"},"id":"Dst VarName_rowCount_1"},"Dst VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Dst VarSize_rowCount_1","Dst VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Dst Mode":{"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"Dst Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Dst Mode_rowCount_1"},"Dst Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Dst Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Dst Message Size_rowCount_1"},"Start Trigger":{"Start Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Start Trigger_rowCount_1"},"Abort Trigger":{"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Abort Trigger_rowCount_1","Abort Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"}}}],"type":"tableDynamicControls","key":"dmaTable"} + {"dataArray":[{"DMA Channels":{"data":{"isDisable":"true","options":"--NONE--","text":"DMA CHANNEL1","value":"false"},"id":"DMA Channels_rowCount_0"},"Src Module":{"data":{"isDisable":"true","options":"--NONE--,MEMORY,ECAN,TMR0","text":"--NONE--","value":"--NONE--"},"id":"Src Module_rowCount_0"},"Src Region":{"data":{"isDisable":"true","options":"SFR#disabled,GPR#enabled,Program Flash#enabled,Data EEPROM#enabled","text":"GPR","value":"GPR"},"id":"Src Region_rowCount_0"},"Src SFR":{"Src SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Src SFR_rowCount_0"},"Src VarName":{"data":{"isDisable":"true","options":"","text":"SrcVarName0","value":"SrcVarName0"},"Src VarName":{"isDisable":"true","options":"","text":"SrcVarName0","value":"SrcVarName0"},"id":"Src VarName_rowCount_0"},"Src VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Src VarSize_rowCount_0","Src VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Src Address":{"data":{"isDisable":"true","options":"","text":"Enter Address0","value":"Enter Address0"},"id":"Src Address_rowCount_0","Src Address":{"isDisable":"true","options":"","text":"Enter Address0","value":"Enter Address0"}},"Src Mode":{"Src Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Src Mode_rowCount_0"},"Src Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Src Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Src Message Size_rowCount_0"},"Dst Module":{"data":{"isDisable":"true","options":"--NONE--,MEMORY,ECAN,TMR0","text":"--NONE--","value":"--NONE--"},"id":"Dst Module_rowCount_0"},"Dst Region":{"data":{"isDisable":"true","options":"SFR,GPR","text":"GPR","value":"GPR"},"id":"Dst Region_rowCount_0"},"Dst SFR":{"Dst SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Dst SFR_rowCount_0"},"Dst VarName":{"data":{"isDisable":"true","options":"","text":"DstVarName0","value":"DstVarName0"},"Dst VarName":{"isDisable":"true","options":"","text":"DstVarName0","value":"DstVarName0"},"id":"Dst VarName_rowCount_0"},"Dst VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Dst VarSize_rowCount_0","Dst VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Dst Mode":{"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"Dst Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Dst Mode_rowCount_0"},"Dst Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Dst Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Dst Message Size_rowCount_0"},"Start Trigger":{"Start Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Start Trigger_rowCount_0"},"Abort Trigger":{"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Abort Trigger_rowCount_0","Abort Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"}}},{"DMA Channels":{"data":{"isDisable":"true","options":"--NONE--","text":"DMA CHANNEL2","value":"false"},"id":"DMA Channels_rowCount_1"},"Src Module":{"data":{"isDisable":"true","options":"--NONE--,MEMORY,ECAN,TMR0","text":"--NONE--","value":"--NONE--"},"id":"Src Module_rowCount_1"},"Src Region":{"data":{"isDisable":"true","options":"SFR#disabled,GPR#enabled,Program Flash#enabled,Data EEPROM#enabled","text":"GPR","value":"GPR"},"id":"Src Region_rowCount_1"},"Src SFR":{"Src SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Src SFR_rowCount_1"},"Src VarName":{"data":{"isDisable":"true","options":"","text":"SrcVarName1","value":"SrcVarName1"},"Src VarName":{"isDisable":"true","options":"","text":"SrcVarName1","value":"SrcVarName1"},"id":"Src VarName_rowCount_1"},"Src VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Src VarSize_rowCount_1","Src VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Src Address":{"data":{"isDisable":"true","options":"","text":"Enter Address1","value":"Enter Address1"},"id":"Src Address_rowCount_1","Src Address":{"isDisable":"true","options":"","text":"Enter Address1","value":"Enter Address1"}},"Src Mode":{"Src Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Src Mode_rowCount_1"},"Src Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Src Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Src Message Size_rowCount_1"},"Dst Module":{"data":{"isDisable":"true","options":"--NONE--,MEMORY,ECAN,TMR0","text":"--NONE--","value":"--NONE--"},"id":"Dst Module_rowCount_1"},"Dst Region":{"data":{"isDisable":"true","options":"SFR,GPR","text":"GPR","value":"GPR"},"id":"Dst Region_rowCount_1"},"Dst SFR":{"Dst SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Dst SFR_rowCount_1"},"Dst VarName":{"data":{"isDisable":"true","options":"","text":"DstVarName1","value":"DstVarName1"},"Dst VarName":{"isDisable":"true","options":"","text":"DstVarName1","value":"DstVarName1"},"id":"Dst VarName_rowCount_1"},"Dst VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Dst VarSize_rowCount_1","Dst VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Dst Mode":{"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"Dst Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Dst Mode_rowCount_1"},"Dst Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Dst Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Dst Message Size_rowCount_1"},"Start Trigger":{"Start Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Start Trigger_rowCount_1"},"Abort Trigger":{"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Abort Trigger_rowCount_1","Abort Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"}}}],"type":"tableDynamicControls","key":"dmaTable"} @@ -17162,63 +17162,63 @@ main.c - 91afd5df6694cfcd0279d66d9b5b3eb72a9c4eae825f0c0af82824e2ee66e35e + cae37ae3b36cf22e97e106633433f5c00a66dd5d38ec353eb67fbbb0d88bde4d mcc_generated_files\device_config.c - 4288704a051756dce8bb92e77a82ba1285fc638cde56b3676b59406ba0fcea7b + 39a6d1181ef5eab59c7dde2c52a9ea889465d4da43262200f3322abc45e77739 mcc_generated_files\device_config.h - 2f04b3ff01bbe49769634d389433c7010ffb45d0f2973898e33988be7ab07d56 + 89c6172ff575ce515b93f2fbc85dcedc2978e58a8e0e1fbdc52e42511ae3bc05 mcc_generated_files\ecan.c - b60a119876875a2af386474d32176b8be0f47a074a2d8688e79251a2d7cdf6fa + ea62f50d319e1e537d7632774728ad6a779f442e896d043dbdea8066d028a6c6 mcc_generated_files\ecan.h - 0473fedf57d1376193e049ba507abed0960af84f0e416bea25972c4dae59ca26 + aa9a50aae81bab76b876ea6123777af7d6a6d0a58fe953be27e8b88776395b2e mcc_generated_files\interrupt_manager.c - bb0eaf9aec0554de0106cff27f66e56ae02a40bbdcb68d4d58d8a0d84d8929f6 + df04edcd2c7d85ef90a8dbe4e46f1b1c9487b872153f4f2321249a4ce0d9635f mcc_generated_files\interrupt_manager.h - 313560861c27e0a0b39b2bbb6a64ac2068fd1937dc0339d7303ff241bbb52955 + 9c2f1ae45f2ac887bb3e8b3763e1a394a6a22ffe4e9ae1c20c336fe6f12da1aa mcc_generated_files\mcc.c - 34fadc3a271040b358215ec477acf3e135b77137f9a1cc96def75fc2936d3ad6 + cc9ed44843b509879e6a3f676b561ecde91e1df88d855cf7eca77e1afc8920ca mcc_generated_files\mcc.h - aead6835bc73f4332d9abb5de6c2a40829de25cc98452c4c69960d51b52844e9 + a2db7e36e878f686c2bf0c2ef586ef1c6570fa2f27119b4be7b52af6403091a4 mcc_generated_files\memory.c - ae2dbb373f8f03dd013cde153de046ba7c3c41033c1dedb8545cde41837ca3da + 17fb4759c4719b77287f6c4be48edfbcf117b5b8398b771c434f23aceac256e0 mcc_generated_files\memory.h - 77a34d015c961db9ed465b4ca2d85ba910fb030ca14c3c2854428ab0b9b6fac2 + fbbca4e9d7ce92ddcc637d82b694a1f5cbefa75710a8a18bb1dc9ab5161f0924 mcc_generated_files\pin_manager.c - f8ace8a0b0d2a4f0ed3e209db056da57858e5a670ad7d514e44352d9187be806 + 04b16a3d3fcbbb333ee6fb545a405b76aba47ef3935be548bf2b8165c43c5654 mcc_generated_files\pin_manager.h - 3e61569926ed5f184a2267965f2cf7ca26dc997d552c213ebd94dbd80da54891 + 611a409602fd8fba29be052e06a3ce86ad0a3b723b5e0f4c1a998854de7f9a7b mcc_generated_files\tmr0.c - f9702dc8c67433ffc3b8db9e12ee3a73fb0b152a792d26f6c7a89a3846bc4fc9 + e0b4d075e819024ae77ea60a2c01182fdca45b783980cb50358d0a614736339d mcc_generated_files\tmr0.h - 68e2ba0f47166abd2da1a472d6a67bfde31f9be3edc8582ace93062a6a32f441 + 6661ab783aae9f11e952805f9bca14209ec06551939552123056eefd5524fff8 \ No newline at end of file diff --git a/306-controller_interface.X/ss22ep.mc3.bak0 b/306-controller_interface.X/ss22ep.mc3.bak0 new file mode 100644 index 0000000..545a479 --- /dev/null +++ b/306-controller_interface.X/ss22ep.mc3.bak0 @@ -0,0 +1,17224 @@ + + + + + DMA CHANNEL1 + class com.microchip.mcc.mcu8.dmaManager.submodule.DMAModules + + + DMA CHANNEL2 + class com.microchip.mcc.mcu8.dmaManager.submodule.DMAModules + + + DMA Manager + class com.microchip.mcc.mcu8.dmaManager.DMA + + + ECAN + class com.microchip.mcc.mcu8.modules.can.CAN + + + INTERNAL OSCILLATOR + class com.microchip.mcc.mcu8.systemManager.osc.Osc + + + Interrupt Module + class com.microchip.mcc.mcu8.interruptManager_K42.InterruptManager + + + MEMORY + class com.microchip.mcc.mcu8.modules.memory.MEMORY + + + PMD + class com.microchip.mcc.mcu8.systemManager.pmd.PMD + + + Pin Module + class com.microchip.mcc.mcu8.pinManager.PinManager + + + RESET + class com.microchip.mcc.mcu8.systemManager.reset.RESET + + + System Module + class com.microchip.mcc.mcu8.systemManager.SystemManager + + + TMR0 + class com.microchip.mcc.mcu8.modules.tmr0_mid0.TMR0 + + + WWDT + class com.microchip.mcc.mcu8.systemManager.wwdt.WWDT + + + + + + + + + ISR_DMA CHANNEL1_DMAAI + + + + ISR_DMA CHANNEL1_DMADCNTI + + + + ISR_DMA CHANNEL1_DMAORI + + + + ISR_DMA CHANNEL1_DMASCNTI + + + + 10 + + + + 11 + + + + 45 + + + + 47 + + + + 40 + + + + 41 + + + + 42 + + + + 43 + + + + 44 + + + + 46 + + + + 35 + + + + 67 + + + + 74 + + + + 77 + + + + 38 + + + + 69 + + + + 76 + + + + 78 + + + + 12 + + + + 48 + + + + 6 + + + + 3 + + + + 37 + + + + 68 + + + + 75 + + + + 19 + + + + 17 + + + + 18 + + + + 16 + + + + 55 + + + + 53 + + + + 54 + + + + 52 + + + + 25 + + + + 26 + + + + 23 + + + + 24 + + + + 58 + + + + 59 + + + + 56 + + + + 57 + + + + 8 + + + + 39 + + + + 70 + + + + 7 + + + + 1 + + + + 36 + + + + 4 + + + + 0 + + + + 2 + + + + 5 + + + + 13 + + + + 14 + + + + 15 + + + + 49 + + + + 50 + + + + 51 + + + + 22 + + + + 20 + + + + 21 + + + + 31 + + + + 32 + + + + 33 + + + + 34 + + + + 64 + + + + 65 + + + + 66 + + + + 71 + + + + 72 + + + + 73 + + + + 30 + + + + 29 + + + + 27 + + + + 28 + + + + 63 + + + + 62 + + + + 60 + + + + 61 + + + + 9 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 2 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 2 + + + + 1 + + + + 0 + + + + 2 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 10 + + + + 11 + + + + 45 + + + + 47 + + + + 40 + + + + 41 + + + + 42 + + + + 43 + + + + 44 + + + + 46 + + + + 35 + + + + 67 + + + + 74 + + + + 77 + + + + 38 + + + + 69 + + + + 76 + + + + 78 + + + + 12 + + + + 48 + + + + 6 + + + + 3 + + + + 37 + + + + 68 + + + + 75 + + + + 19 + + + + 17 + + + + 18 + + + + 16 + + + + 55 + + + + 53 + + + + 54 + + + + 52 + + + + 25 + + + + 26 + + + + 23 + + + + 24 + + + + 58 + + + + 59 + + + + 56 + + + + 57 + + + + 8 + + + + 39 + + + + 70 + + + + 7 + + + + 1 + + + + 36 + + + + 4 + + + + 0 + + + + 2 + + + + 5 + + + + 13 + + + + 14 + + + + 15 + + + + 49 + + + + 50 + + + + 51 + + + + 22 + + + + 20 + + + + 21 + + + + 31 + + + + 32 + + + + 33 + + + + 34 + + + + 64 + + + + 65 + + + + 66 + + + + 71 + + + + 72 + + + + 73 + + + + 30 + + + + 29 + + + + 27 + + + + 28 + + + + 63 + + + + 62 + + + + 60 + + + + 61 + + + + 9 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + None + + + + disabled + + + + not in progress + + + + disabled + + + + disabled + + + + not in progress + + + + unchanged + + + + not cleared + + + + unchanged + + + + GPR + + + + not cleared + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + None + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + ISR_DMA CHANNEL2_DMAAI + + + + ISR_DMA CHANNEL2_DMADCNTI + + + + ISR_DMA CHANNEL2_DMAORI + + + + ISR_DMA CHANNEL2_DMASCNTI + + + + 10 + + + + 11 + + + + 45 + + + + 47 + + + + 40 + + + + 41 + + + + 42 + + + + 43 + + + + 44 + + + + 46 + + + + 35 + + + + 67 + + + + 74 + + + + 77 + + + + 38 + + + + 69 + + + + 76 + + + + 78 + + + + 12 + + + + 48 + + + + 6 + + + + 3 + + + + 37 + + + + 68 + + + + 75 + + + + 19 + + + + 17 + + + + 18 + + + + 16 + + + + 55 + + + + 53 + + + + 54 + + + + 52 + + + + 25 + + + + 26 + + + + 23 + + + + 24 + + + + 58 + + + + 59 + + + + 56 + + + + 57 + + + + 8 + + + + 39 + + + + 70 + + + + 7 + + + + 1 + + + + 36 + + + + 4 + + + + 0 + + + + 2 + + + + 5 + + + + 13 + + + + 14 + + + + 15 + + + + 49 + + + + 50 + + + + 51 + + + + 22 + + + + 20 + + + + 21 + + + + 31 + + + + 32 + + + + 33 + + + + 34 + + + + 64 + + + + 65 + + + + 66 + + + + 71 + + + + 72 + + + + 73 + + + + 30 + + + + 29 + + + + 27 + + + + 28 + + + + 63 + + + + 62 + + + + 60 + + + + 61 + + + + 9 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 2 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 2 + + + + 1 + + + + 0 + + + + 2 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 10 + + + + 11 + + + + 45 + + + + 47 + + + + 40 + + + + 41 + + + + 42 + + + + 43 + + + + 44 + + + + 46 + + + + 35 + + + + 67 + + + + 74 + + + + 77 + + + + 38 + + + + 69 + + + + 76 + + + + 78 + + + + 12 + + + + 48 + + + + 6 + + + + 3 + + + + 37 + + + + 68 + + + + 75 + + + + 19 + + + + 17 + + + + 18 + + + + 16 + + + + 55 + + + + 53 + + + + 54 + + + + 52 + + + + 25 + + + + 26 + + + + 23 + + + + 24 + + + + 58 + + + + 59 + + + + 56 + + + + 57 + + + + 8 + + + + 39 + + + + 70 + + + + 7 + + + + 1 + + + + 36 + + + + 4 + + + + 0 + + + + 2 + + + + 5 + + + + 13 + + + + 14 + + + + 15 + + + + 49 + + + + 50 + + + + 51 + + + + 22 + + + + 20 + + + + 21 + + + + 31 + + + + 32 + + + + 33 + + + + 34 + + + + 64 + + + + 65 + + + + 66 + + + + 71 + + + + 72 + + + + 73 + + + + 30 + + + + 29 + + + + 27 + + + + 28 + + + + 63 + + + + 62 + + + + 60 + + + + 61 + + + + 9 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + None + + + + disabled + + + + not in progress + + + + disabled + + + + disabled + + + + not in progress + + + + unchanged + + + + not cleared + + + + unchanged + + + + GPR + + + + not cleared + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + None + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + {"dataArray":[{"DMA Channels":{"data":{"isDisable":"true","options":"--NONE--","text":"DMA CHANNEL1","value":"false"},"id":"DMA Channels_rowCount_0"},"Src Module":{"data":{"isDisable":"true","options":"--NONE--,MEMORY,ECAN,TMR0","text":"--NONE--","value":"--NONE--"},"id":"Src Module_rowCount_0"},"Src Region":{"data":{"isDisable":"true","options":"SFR#disabled,GPR#enabled,Program Flash#enabled,Data EEPROM#enabled","text":"GPR","value":"GPR"},"id":"Src Region_rowCount_0"},"Src SFR":{"Src SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Src SFR_rowCount_0"},"Src VarName":{"data":{"isDisable":"true","options":"","text":"SrcVarName0","value":"SrcVarName0"},"Src VarName":{"isDisable":"true","options":"","text":"SrcVarName0","value":"SrcVarName0"},"id":"Src VarName_rowCount_0"},"Src VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Src VarSize_rowCount_0","Src VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Src Address":{"data":{"isDisable":"true","options":"","text":"Enter Address0","value":"Enter Address0"},"id":"Src Address_rowCount_0","Src Address":{"isDisable":"true","options":"","text":"Enter Address0","value":"Enter Address0"}},"Src Mode":{"Src Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Src Mode_rowCount_0"},"Src Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Src Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Src Message Size_rowCount_0"},"Dst Module":{"data":{"isDisable":"true","options":"--NONE--,MEMORY,ECAN,TMR0","text":"--NONE--","value":"--NONE--"},"id":"Dst Module_rowCount_0"},"Dst Region":{"data":{"isDisable":"true","options":"SFR,GPR","text":"GPR","value":"GPR"},"id":"Dst Region_rowCount_0"},"Dst SFR":{"Dst SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Dst SFR_rowCount_0"},"Dst VarName":{"data":{"isDisable":"true","options":"","text":"DstVarName0","value":"DstVarName0"},"Dst VarName":{"isDisable":"true","options":"","text":"DstVarName0","value":"DstVarName0"},"id":"Dst VarName_rowCount_0"},"Dst VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Dst VarSize_rowCount_0","Dst VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Dst Mode":{"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"Dst Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Dst Mode_rowCount_0"},"Dst Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Dst Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Dst Message Size_rowCount_0"},"Start Trigger":{"Start Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Start Trigger_rowCount_0"},"Abort Trigger":{"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Abort Trigger_rowCount_0","Abort Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"}}},{"DMA Channels":{"data":{"isDisable":"true","options":"--NONE--","text":"DMA CHANNEL2","value":"false"},"id":"DMA Channels_rowCount_1"},"Src Module":{"data":{"isDisable":"true","options":"--NONE--,MEMORY,ECAN,TMR0","text":"--NONE--","value":"--NONE--"},"id":"Src Module_rowCount_1"},"Src Region":{"data":{"isDisable":"true","options":"SFR#disabled,GPR#enabled,Program Flash#enabled,Data EEPROM#enabled","text":"GPR","value":"GPR"},"id":"Src Region_rowCount_1"},"Src SFR":{"Src SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Src SFR_rowCount_1"},"Src VarName":{"data":{"isDisable":"true","options":"","text":"SrcVarName1","value":"SrcVarName1"},"Src VarName":{"isDisable":"true","options":"","text":"SrcVarName1","value":"SrcVarName1"},"id":"Src VarName_rowCount_1"},"Src VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Src VarSize_rowCount_1","Src VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Src Address":{"data":{"isDisable":"true","options":"","text":"Enter Address1","value":"Enter Address1"},"id":"Src Address_rowCount_1","Src Address":{"isDisable":"true","options":"","text":"Enter Address1","value":"Enter Address1"}},"Src Mode":{"Src Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Src Mode_rowCount_1"},"Src Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Src Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Src Message Size_rowCount_1"},"Dst Module":{"data":{"isDisable":"true","options":"--NONE--,MEMORY,ECAN,TMR0","text":"--NONE--","value":"--NONE--"},"id":"Dst Module_rowCount_1"},"Dst Region":{"data":{"isDisable":"true","options":"SFR,GPR","text":"GPR","value":"GPR"},"id":"Dst Region_rowCount_1"},"Dst SFR":{"Dst SFR":{"isDisable":"true","options":"","text":"","value":""},"data":{"isDisable":"true","options":"","text":"","value":""},"id":"Dst SFR_rowCount_1"},"Dst VarName":{"data":{"isDisable":"true","options":"","text":"DstVarName1","value":"DstVarName1"},"Dst VarName":{"isDisable":"true","options":"","text":"DstVarName1","value":"DstVarName1"},"id":"Dst VarName_rowCount_1"},"Dst VarSize":{"data":{"isDisable":"true","options":"","text":"10","value":"10"},"id":"Dst VarSize_rowCount_1","Dst VarSize":{"isDisable":"true","options":"","text":"10","value":"10"}},"Dst Mode":{"data":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"Dst Mode":{"isDisable":"true","options":"decremented,incremented,unchanged","text":"unchanged","value":"unchanged"},"id":"Dst Mode_rowCount_1"},"Dst Message Size":{"data":{"isDisable":"true","options":"","text":"1","value":"1"},"Dst Message Size":{"isDisable":"true","options":"","text":"1","value":"1"},"id":"Dst Message Size_rowCount_1"},"Start Trigger":{"Start Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Start Trigger_rowCount_1"},"Abort Trigger":{"data":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"},"id":"Abort Trigger_rowCount_1","Abort Trigger":{"isDisable":"true","options":"AD,ADT,CAN_ERRIF,CAN_IRXIF,CAN_RXB0IF\/FIFOIF,CAN_RXB1IF\/RXBnIF,CAN_TXB0IF,CAN_TXB1IF,CAN_TXB2IF\/TXBnIF,CAN_WAKIF,CCP1,CCP2,CCP3,CCP4,CLC1,CLC2,CLC3,CLC4,CMP1,CMP2,CRC,CSW,CWG1,CWG2,CWG3,DMA1A,DMA1DCNT,DMA1OR,DMA1SCNT,DMA2A,DMA2DCNT,DMA2OR,DMA2SCNT,I2C1,I2C1E,I2C1RX,I2C1TX,I2C2,I2C2E,I2C2RX,I2C2TX,INT0,INT1,INT2,IOC,LVD,NCO,NVM,None,OSF,SCAN,SMT1,SMT1PRA,SMT1PWA,SMT2,SMT2PRA,SMT2PWA,SPI1,SPI1RX,SPI1TX,TMR0,TMR1,TMR1G,TMR2,TMR3,TMR3G,TMR4,TMR5,TMR5G,TMR6,U1,U1E,U1RX,U1TX,U2,U2E,U2RX,U2TX,ZCD","text":"None","value":"None"}}}],"type":"tableDynamicControls","key":"dmaTable"} + + + + ERRI_ISR + + + + FIFOWMI_ISR + + + + IRXI_ISR + + + + RXB0I_ISR + + + + RXB1I_ISR + + + + RXBnI_ISR + + + + TXB0I_ISR + + + + TXB1I_ISR + + + + TXB2I_ISR + + + + TXBnI_ISR + + + + WAKI_ISR + + + + Filter 0 + + + + SID + + + + Acceptance Mask 0 + + + + FIFO + + + + 250kbps + + + + 64000000 + + + + PIC18F26K83 + + + + CANTX pin will drive VDD when recessive + + + + 1000000 + + + + 8 + + + + FIFO Watermark interrupt is disabled + + + + 0 + + + + hfintosc + + + + 1 x TQ + + + + 75% + + + + 8 + + + + 64000000 + + + + 64000000 + + + + 0 + + + + enabled + + + + enabled + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 9 + + + + 10 + + + + 11 + + + + 12 + + + + 13 + + + + 14 + + + + 15 + + + + 16 + + + + 17 + + + + 18 + + + + 1 + + + + 19 + + + + 20 + + + + 21 + + + + 22 + + + + 23 + + + + 24 + + + + 25 + + + + 26 + + + + 27 + + + + 28 + + + + 2 + + + + 29 + + + + 30 + + + + 31 + + + + 32 + + + + 33 + + + + 34 + + + + 35 + + + + 36 + + + + 37 + + + + 38 + + + + 3 + + + + 39 + + + + 40 + + + + 41 + + + + 42 + + + + 43 + + + + 44 + + + + 45 + + + + 46 + + + + 47 + + + + 48 + + + + 4 + + + + 49 + + + + 50 + + + + 51 + + + + 52 + + + + 53 + + + + 54 + + + + 55 + + + + 56 + + + + 57 + + + + 58 + + + + 5 + + + + 59 + + + + 60 + + + + 61 + + + + 14 + + + + 63 + + + + 6 + + + + 7 + + + + 8 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 4 + + + + 3 + + + + 2 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 8 + + + + 9 + + + + 1 + + + + 6 + + + + 7 + + + + 2 + + + + 15 + + + + 16 + + + + 17 + + + + 18 + + + + 19 + + + + 20 + + + + 21 + + + + 22 + + + + 23 + + + + 3 + + + + 4 + + + + 5 + + + + 0 + + + + 1 + + + + 2 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 15 + + + + 152 + + + + 129 + + + + 0 + + + + 128 + + + + 0 + + + + 0 + + + + 144 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + When a remote transmission request is received, TXREQ will be unaffected + + + + Receive buffer is open to receive a new message + + + + Receive all valid messages as per acceptance filters + + + + Received message is not a remote transmission request + + + + Message was not aborted + + + + No message was transmitted + + + + A bus error did not occur while the message was being sent + + + + Message did not lose arbitration while being sent + + + + 0 + + + + 0 + + + + Automatically cleared when the message is successfully sent + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Data length = 0 bytes + + + + This is not a remote transmission request + + + + Transmitted message will have the RTR bit cleared + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Received message is a standard identifier frame + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + When a remote transmission request is received, TXREQ will be unaffected + + + + Receive buffer is open to receive a new message + + + + Receive all valid messages as per acceptance filters + + + + Received message is not a remote transmission request + + + + Message was not aborted + + + + No message was transmitted + + + + A bus error did not occur while the message was being sent + + + + Message did not lose arbitration while being sent + + + + 0 + + + + 0 + + + + Automatically cleared when the message is successfully sent + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Data length = 0 bytes + + + + This is not a remote transmission request + + + + Transmitted message will have the RTR bit cleared + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Received message is a standard identifier frame + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + When a remote transmission request is received, TXREQ will be unaffected + + + + Receive buffer is open to receive a new message + + + + Receive all valid messages as per acceptance filters + + + + Received message is not a remote transmission request + + + + Message was not aborted + + + + No message was transmitted + + + + A bus error did not occur while the message was being sent + + + + Message did not lose arbitration while being sent + + + + 0 + + + + 0 + + + + Automatically cleared when the message is successfully sent + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Data length = 0 bytes + + + + This is not a remote transmission request + + + + Transmitted message will have the RTR bit cleared + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Received message is a standard identifier frame + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + When a remote transmission request is received, TXREQ will be unaffected + + + + Receive buffer is open to receive a new message + + + + Receive all valid messages as per acceptance filters + + + + Received message is not a remote transmission request + + + + Message was not aborted + + + + No message was transmitted + + + + A bus error did not occur while the message was being sent + + + + Message did not lose arbitration while being sent + + + + 0 + + + + 0 + + + + Automatically cleared when the message is successfully sent + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Data length = 0 bytes + + + + This is not a remote transmission request + + + + Transmitted message will have the RTR bit cleared + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Received message is a standard identifier frame + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + When a remote transmission request is received, TXREQ will be unaffected + + + + Receive buffer is open to receive a new message + + + + Receive all valid messages as per acceptance filters + + + + Received message is not a remote transmission request + + + + Message was not aborted + + + + No message was transmitted + + + + A bus error did not occur while the message was being sent + + + + Message did not lose arbitration while being sent + + + + 0 + + + + 0 + + + + Automatically cleared when the message is successfully sent + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Data length = 0 bytes + + + + This is not a remote transmission request + + + + Transmitted message will have the RTR bit cleared + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Received message is a standard identifier frame + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + When a remote transmission request is received, TXREQ will be unaffected + + + + Receive buffer is open to receive a new message + + + + Receive all valid messages as per acceptance filters + + + + Received message is not a remote transmission request + + + + Message was not aborted + + + + No message was transmitted + + + + A bus error did not occur while the message was being sent + + + + Message did not lose arbitration while being sent + + + + 0 + + + + 0 + + + + Automatically cleared when the message is successfully sent + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Data length = 0 bytes + + + + This is not a remote transmission request + + + + Transmitted message will have the RTR bit cleared + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Received message is a standard identifier frame + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Interrupt is disabled + + + + Interrupt is disabled + + + + Interrupt is disabled + + + + Interrupt is disabled + + + + Interrupt is disabled + + + + Interrupt is disabled + + + + Interrupt is disabled + + + + Interrupt is disabled + + + + TQ = (2 x 16)/FOSC + + + + Synchronization jump width time = 1 x TQ + + + + 1 x TQ + + + + Bus line is sampled once at the sample point + + + + 4 x TQ + + + + Freely programmable + + + + 2 x TQ + + + + Disable CAN bus activity wake-up feature + + + + CAN bus line filter is not used for wake-up + + + + Buffer 0 is configured in Receive mode + + + + Buffer 1 is configured in Receive mode + + + + Buffer 2 is configured in Receive mode + + + + Buffer 3 is configured in Receive mode + + + + Buffer 4 is configured in Receive mode + + + + Buffer 5 is configured in Receive mode + + + + Transmissions proceeding as normal + + + + 0 + + + + Requests Configuration Mode + + + + 0 + + + + 0 + + + + 0 + + + + Use system clock as CAN system clock + + + + CANTX1 pin will output CANTX + + + + Neither the RXWARN or the TXWARN bits are set + + + + Receive Buffer 0 has not overflowed + + + + Receive Buffer 1 has not overflowed + + + + Receive error counter LESS OR EQUAL THAN 127 + + + + Receive Buffer n has not overflowed + + + + Receive error counter LESS OR EQUAL THAN 95 + + + + Transmit error counter LESS OR EQUAL THAN 255 + + + + Transmit error counter LESS OR EQUAL THAN 127 + + + + Transmit error counter LESS OR EQUAL THAN 95 + + + + Receive Buffer 0 + + + + FIF0 Interrupt when four receive buffer remains + + + + Enhanced FIFO mode( Mode 2) + + + + enabled + + + + disabled + + + + -1 + + + + 1 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Mask 0 + + + + Acceptance Filter 0 (RXF0) + + + + 0 + + + + Allows jump table offset between 1 and 0 + + + + No Receive Buffer 0 overflow to Receive Buffer 1 + + + + Receive buffer is open to receive a new message + + + + A remote transmission request is not received + + + + Receive all valid messages as per acceptance filters + + + + A remote transmission request is not received + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Receive buffer is open to receive a new message + + + + A remote transmission request is not received + + + + Receive all valid messages as per acceptance filters + + + + A remote transmission request is not received + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + enabled + + + + disabled + + + + -1 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Filter will only accept standard ID messages + + + + 0 + + + + 0 + + + + 0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + RXB0 + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Both standard and extended identifier messages will be accepted + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Both standard and extended identifier messages will be accepted + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Message was not aborted + + + + Transmit buffer has not completed transmission of a message + + + + A bus error did not occur while the message was being sent + + + + Message did not lose arbitration while being sent + + + + Priority Level 0 (lowest priority) + + + + Automatically cleared when the message is successfully sent + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Data length = 0 bytes + + + + Transmitted message will have the TXRTR bit cleared + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Message will transmit standard ID + + + + 0 + + + + 0 + + + + 0 + + + + Message was not aborted + + + + Transmit buffer has not completed transmission of a message + + + + A bus error did not occur while the message was being sent + + + + Message did not lose arbitration while being sent + + + + Priority Level 0 (lowest priority) + + + + Automatically cleared when the message is successfully sent + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Data length = 0 bytes + + + + Transmitted message will have the TXRTR bit cleared + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Message will transmit standard ID + + + + 0 + + + + 0 + + + + 0 + + + + Message was not aborted + + + + Transmit buffer has not completed transmission of a message + + + + A bus error did not occur while the message was being sent + + + + Message did not lose arbitration while being sent + + + + Priority Level 0 (lowest priority) + + + + Automatically cleared when the message is successfully sent + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Data length = 0 bytes + + + + Transmitted message will have the TXRTR bit cleared + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + Message will transmit standard ID + + + + 0 + + + + 0 + + + + 0 + + + + Transmit buffer interrupt is disabled + + + + Transmit buffer interrupt is disabled + + + + Transmit buffer interrupt is disabled + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + + + + + 64000000 + + + + Oscillator not enabled + + + + HFINTOSC with HFFRQ = 64 MHz and CDIV = 1:1 + + + + 64_MHz + + + + 1000000 + + + + 64000000 + + + + 64000000 + + + + 31000 + + + + 31250 + + + + 500000 + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + internal + + + + OFF + + + + PRESENT + + + + disabled + + + + disabled + + + + 0 + + + + 7 + + + + 4 + + + + 1 + + + + 8 + + + + 5 + + + + 2 + + + + 9 + + + + 6 + + + + 3 + + + + 7 + + + + 2 + + + + 6 + + + + 5 + + + + 4 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 4 + + + + 5 + + + + 0 + + + + 1 + + + + 6 + + + + 7 + + + + 2 + + + + 8 + + + + 3 + + + + 96 + + + + 0 + + + + 0 + + + + 8 + + + + 0 + + + + 1 + + + + HFINTOSC + + + + may proceed + + + + not ready + + + + clock switching + + + + Low power + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + 64_MHz + + + + 0 + + + + 8 + + + + IVT1 + + + + disabled + + + + disabled + + + + enabled + + + + enabled + + + + 65536 + + + + 128 + + + + ISR + + + + 128 + + + + enabled + + + + 1 + + + + 0 + + + + 2 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + write + + + + access_data_eeprom + + + + do_not_initiate_read + + + + write_complete + + + + disabled + + + + normal_completion + + + + 0 + + + + 0 + + + + disabled + + + + disabled + + + + -1 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + CLKR enabled + + + + CRC enabled + + + + FVR enabled + + + + HLVD enabled + + + + IOC enabled + + + + NVM enabled + + + + SCANNER enabled + + + + SYSCLK enabled + + + + DDS(NCO1) enabled + + + + TMR0 enabled + + + + TMR1 enabled + + + + TMR2 enabled + + + + TMR3 enabled + + + + TMR4 enabled + + + + TMR5 enabled + + + + TMR6 enabled + + + + ADC enabled + + + + CMP1 enabled + + + + CMP2 enabled + + + + DAC enabled + + + + ZCD enabled + + + + CCP1 enabled + + + + CCP2 enabled + + + + CCP3 enabled + + + + CCP4 enabled + + + + PWM5 enabled + + + + PWM6 enabled + + + + PWM7 enabled + + + + PWM8 enabled + + + + CWG1 enabled + + + + CWG2 enabled + + + + CWG3 enabled + + + + I2C1 enabled + + + + I2C2 enabled + + + + SPI1 enabled + + + + UART1 enabled + + + + UART2 enabled + + + + CLC1 enabled + + + + CLC2 enabled + + + + CLC3 enabled + + + + CLC4 enabled + + + + DSM1 enabled + + + + SMT1 enabled + + + + SMT2 enabled + + + + DMA1 enabled + + + + DMA2 enabled + + + + OUTPUT1 + + + + OUTPUT2 + + + + OUTPUT3 + + + + OUTPUT4 + + + + OUTPUT5 + + + + OUTPUT6 + + + + OUTPUT7 + + + + OUTPUT8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ISR_Pin Module_IOCI + + + + output + + + + output + + + + output + + + + output + + + + output + + + + output + + + + output + + + + output + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + %DESELECT% + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + enabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + none + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + SOIC28 + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + enabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 12 + + + + 0 + + + + 238 + + + + 255 + + + + 12 + + + + 18 + + + + 17 + + + + 13 + + + + 8 + + + + 0 + + + + 1 + + + + 14 + + + + 15 + + + + 8 + + + + 9 + + + + 10 + + + + 19 + + + + 20 + + + + 9 + + + + 2 + + + + 255 + + + + 255 + + + + 255 + + + + 8 + + + + 8 + + + + 9 + + + + 10 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 4 + + + + 3 + + + + 5 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 51 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 255 + + + + 255 + + + + 255 + + + + 17 + + + + 16 + + + + 13 + + + + 12 + + + + 19 + + + + 20 + + + + 5 + + + + 4 + + + + 16 + + + + 13 + + + + 19 + + + + 16 + + + + 16 + + + + 21 + + + + 18 + + + + 12 + + + + 15 + + + + 0 + + + + 246 + + + + 255 + + + + 22 + + + + 23 + + + + 14 + + + + 15 + + + + 128 + + + + 0 + + + + 0 + + + + 0 + + + + 12 + + + + digital + + + + digital + + + + digital + + + + digital + + + + digital + + + + digital + + + + digital + + + + digital + + + + digital + + + + analog + + + + analog + + + + analog + + + + digital + + + + analog + + + + analog + + + + analog + + + + analog + + + + analog + + + + analog + + + + analog + + + + analog + + + + analog + + + + analog + + + + analog + + + + 12 + + + + 18 + + + + 17 + + + + 13 + + + + 8 + + + + 0 + + + + 1 + + + + 14 + + + + 15 + + + + 8 + + + + 9 + + + + 10 + + + + 19 + + + + 20 + + + + 9 + + + + 2 + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + ST_input + + + + 8 + + + + 9 + + + + 10 + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + 0 + + + + 1 + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + 4 + + + + 3 + + + + 5 + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + disabled + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 51 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + 0 + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + limited + + + + 17 + + + + 16 + + + + 13 + + + + 12 + + + + 19 + + + + 20 + + + + 5 + + + + 4 + + + + 16 + + + + 13 + + + + 19 + + + + 16 + + + + 16 + + + + 21 + + + + 18 + + + + 12 + + + + 15 + + + + output + + + + output + + + + output + + + + output + + + + output + + + + output + + + + output + + + + output + + + + output + + + + input + + + + input + + + + output + + + + input + + + + input + + + + input + + + + input + + + + input + + + + input + + + + input + + + + input + + + + input + + + + input + + + + input + + + + input + + + + 22 + + + + 23 + + + + 14 + + + + 15 + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + set + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + clear + + + + 31.0 KHz + + + + enabled + + + + 1 + + + + 0 + + + + 0 + + + + 8 + + + + 0 + + + + 32 + + + + 0 + + + + 2 + + + + 7 + + + + 5 + + + + 6 + + + + 2 + + + + 0 + + + + 4 + + + + 3 + + + + 1 + + + + 112 + + + + 32 + + + + 96 + + + + 0 + + + + 80 + + + + 16 + + + + 64 + + + + 3 + + + + 1 + + + + 0 + + + + 32 + + + + 0 + + + + 0 + + + + 8 + + + + 0 + + + + 16 + + + + 128 + + + + 0 + + + + 4 + + + + 0 + + + + 128 + + + + 0 + + + + 64 + + + + 192 + + + + 0 + + + + 16 + + + + 32 + + + + 0 + + + + 1 + + + + 0 + + + + 0 + + + + 8 + + + + 0 + + + + 2 + + + + 4 + + + + 6 + + + + 0 + + + + 8 + + + + 56 + + + + 16 + + + + 0 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 0 + + + + 1 + + + + 10 + + + + 11 + + + + 12 + + + + 13 + + + + 14 + + + + 15 + + + + 16 + + + + 17 + + + + 18 + + + + 2 + + + + 3 + + + + 31 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 9 + + + + 64 + + + + 0 + + + + 96 + + + + 32 + + + + 0 + + + + 32 + + + + 1 + + + + 0 + + + + 2 + + + + 0 + + + + 4 + + + + 0 + + + + 8 + + + + 0 + + + + 8 + + + + 0 + + + + 6 + + + + 5 + + + + 4 + + + + 7 + + + + 3 + + + + 16 + + + + 0 + + + + 128 + + + + 0 + + + + 1 + + + + 0 + + + + 43 + + + + 4 + + + + 191 + + + + 247 + + + + 63 + + + + 31 + + + + 47 + + + + 159 + + + + 1 + + + + OFF + + + + ON + + + + ON + + + + ON + + + + OFF + + + + HFINTOSC_64MHZ + + + + VBOR_2P45 + + + + OFF + + + + ON + + + + ON + + + + OFF + + + + OFF + + + + SBORDIS + + + + ON + + + + OFF + + + + EXTMCLR + + + + OFF + + + + PWRT_OFF + + + + SC + + + + WDTCWS_7 + + + + WDTCPS_31 + + + + OFF + + + + ON + + + + OFF + + + + OFF + + + + OFF + + + + OFF + + + + OFF + + + + BBSIZE_512 + + + + OFF + + + + OFF + + + + OFF + + + + 0 + + + + ISR + + + + 0.01 + + + + 64000000 + + + + 100000 + + + + periodMode + + + + 0.01024 + + + + 0.00004 + + + + 10 + + + + 64 + + + + 25000 + + + + 0.01 + + + + disabled + + + + 0 + + + + enabled + + + + 8-bit + + + + 1 + + + + 0 + + + + 0 + + + + 1 + + + + 1 + + + + 0 + + + + 0 + + + + 9 + + + + 10 + + + + 11 + + + + 12 + + + + 13 + + + + 14 + + + + 15 + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 7 + + + + 8 + + + + 1 + + + + 0 + + + + 0 + + + + 10 + + + + 7 + + + + 4 + + + + 14 + + + + 1 + + + + 11 + + + + 8 + + + + 5 + + + + 15 + + + + 2 + + + + 12 + + + + 9 + + + + 6 + + + + 3 + + + + 13 + + + + 7 + + + + 2 + + + + 3 + + + + 4 + + + + 5 + + + + 6 + + + + 0 + + + + 1 + + + + 137 + + + + 70 + + + + 249 + + + + 0 + + + + 8-bit + + + + enabled + + + + low + + + + 1:10 + + + + synchronised + + + + 1:64 + + + + FOSC/4 + + + + 249 + + + + 0 + + + + enabled + + + + disabled + + + + -1 + + + + 1 + + + + 2.11406 + + + + 1 + + + + 0 + + + + 1 + + + + 0 + + + + 5 + + + + 15 + + + + 2 + + + + 12 + + + + 9 + + + + 6 + + + + 16 + + + + 3 + + + + 13 + + + + 0 + + + + 10 + + + + 7 + + + + 17 + + + + 4 + + + + 14 + + + + 1 + + + + 11 + + + + 8 + + + + 18 + + + + 0 + + + + 1 + + + + 0 + + + + 1 + + + + 2 + + + + 7 + + + + 6 + + + + 5 + + + + 4 + + + + 3 + + + + 2 + + + + 1 + + + + 0 + + + + 48 + + + + 0 + + + + 0 + + + + WDT reset has not occurred + + + + WDT window violation reset has not occurred + + + + 1:32 + + + + OFF + + + + LFINTOSC 31kHz + + + + Window delay time 87.5% + + + + + mcc_generated_files\interrupt_manager.h + 313560861c27e0a0b39b2bbb6a64ac2068fd1937dc0339d7303ff241bbb52955 + + + mcc_generated_files\mcc.h + aead6835bc73f4332d9abb5de6c2a40829de25cc98452c4c69960d51b52844e9 + + + mcc_generated_files\device_config.h + 2f04b3ff01bbe49769634d389433c7010ffb45d0f2973898e33988be7ab07d56 + + + mcc_generated_files\memory.c + ae2dbb373f8f03dd013cde153de046ba7c3c41033c1dedb8545cde41837ca3da + + + mcc_generated_files\tmr0.h + 68e2ba0f47166abd2da1a472d6a67bfde31f9be3edc8582ace93062a6a32f441 + + + main.c + 91afd5df6694cfcd0279d66d9b5b3eb72a9c4eae825f0c0af82824e2ee66e35e + + + mcc_generated_files\device_config.c + 4288704a051756dce8bb92e77a82ba1285fc638cde56b3676b59406ba0fcea7b + + + mcc_generated_files\pin_manager.h + 3e61569926ed5f184a2267965f2cf7ca26dc997d552c213ebd94dbd80da54891 + + + mcc_generated_files\tmr0.c + f9702dc8c67433ffc3b8db9e12ee3a73fb0b152a792d26f6c7a89a3846bc4fc9 + + + mcc_generated_files\pin_manager.c + f8ace8a0b0d2a4f0ed3e209db056da57858e5a670ad7d514e44352d9187be806 + + + mcc_generated_files\ecan.c + b60a119876875a2af386474d32176b8be0f47a074a2d8688e79251a2d7cdf6fa + + + mcc_generated_files\interrupt_manager.c + bb0eaf9aec0554de0106cff27f66e56ae02a40bbdcb68d4d58d8a0d84d8929f6 + + + mcc_generated_files\mcc.c + 34fadc3a271040b358215ec477acf3e135b77137f9a1cc96def75fc2936d3ad6 + + + mcc_generated_files\ecan.h + 0473fedf57d1376193e049ba507abed0960af84f0e416bea25972c4dae59ca26 + + + mcc_generated_files\memory.h + 77a34d015c961db9ed465b4ca2d85ba910fb030ca14c3c2854428ab0b9b6fac2 + + + \ No newline at end of file diff --git a/306-controller_interface.X/xf/xf.h b/306-controller_interface.X/xf/xf.h index 38c1f14..1d280d8 100644 --- a/306-controller_interface.X/xf/xf.h +++ b/306-controller_interface.X/xf/xf.h @@ -27,8 +27,8 @@ typedef struct Timer_ // timer structure /*----------------------------------------------------------------------------*/ /* depending on usage, change MAXTIMER and MAXEVENT */ /*----------------------------------------------------------------------------*/ -#define MAXTIMER 8 // number of timers in our system -#define MAXEVENT 12 // number of events in our system +#define MAXTIMER 15 // number of timers in our system +#define MAXEVENT 20 // number of events in our system #define NULLTIMER 0 // no value for time #define TICKINTERVAL 10 // this is the ticktimers duration diff --git a/UML/alive.pdf b/UML/alive.pdf new file mode 100644 index 0000000..cd22870 Binary files /dev/null and b/UML/alive.pdf differ diff --git a/UML/alive.uxf b/UML/alive.uxf index 0f31457..fe59b01 100644 --- a/UML/alive.uxf +++ b/UML/alive.uxf @@ -4,10 +4,10 @@ UMLSpecialState - 266 - 98 - 28 - 28 + 714 + 28 + 56 + 56 type=initial @@ -15,164 +15,257 @@ Relation - 266 - 112 - 112 - 98 + 462 + 70 + 308 + 154 lt=-> -evACinit - 10.0;10.0;10.0;50.0 +evInitChecker + 200.0;10.0;200.0;50.0;10.0;50.0;10.0;90.0 UMLState - 210 - 182 - 140 - 56 + 350 + 196 + 266 + 112 - STAC_SETUP - - - - UMLNote - - 434 - 182 - 140 - 42 - - Send params + SETUP +-- +/entry: sendParamsOnCan +/entry: checker = true Relation - 266 - 224 - 126 + 462 + 294 + 98 98 lt=-> -evACborn +m1=evBorn 10.0;10.0;10.0;50.0 UMLState - 210 - 294 - 140 - 56 - - STAC_BORN - - - - UMLState - - 168 - 406 - 224 + 350 + 364 + 266 84 - STAC_WAIT + BORN -- -/entry: isAlive = false +/entry: init + + + + UMLState + + 350 + 504 + 266 + 112 + + WAIT +-- +/entry: start children class +-- +isAlive = false Relation - 266 - 336 - 140 + 462 + 434 + 112 98 lt=-> -evACready +m1=evReady 10.0;10.0;10.0;50.0 UMLState - 210 - 658 - 140 - 56 + 350 + 784 + 266 + 84 - STAC_DEAD + DEAD +-- + Relation - 266 - 476 - 112 - 98 - - lt=-> -evACpoll - 10.0;10.0;10.0;50.0 - - - UMLSpecialState - - 252 + 280 546 - 56 - 56 + 210 + 182 - type=decision - + lt=-> +m1=evPoll\n[isAlive] + 80.0;50.0;80.0;110.0;10.0;110.0;10.0;10.0;50.0;10.0 Relation - 266 - 588 - 84 - 98 + 224 + 252 + 378 + 700 lt=-> -m1=[else] - 10.0;10.0;10.0;50.0 +m1=evResurrect + 180.0;440.0;180.0;480.0;10.0;480.0;10.0;10.0;90.0;10.0 + + + Relation + + 462 + 602 + 112 + 210 + + lt=-> +m1=evPoll\n[default] + 10.0;10.0;10.0;130.0 + + + Relation + + 728 + 70 + 308 + 154 + + lt=-> +evInitSender + 10.0;10.0;10.0;50.0;200.0;50.0;200.0;90.0 + + + Relation + + 784 + 252 + 224 + 140 + + lt=-> +m1=evPoll\n[else] + 100.0;40.0;100.0;70.0;10.0;70.0;10.0;10.0;60.0;10.0 UMLNote - 434 - 294 + 784 + 28 140 - 42 + 56 - Reset / Init + read time on +EPROM + + + + UMLState + + 868 + 196 + 266 + 112 + + ALIVE +-- +\entry: sender = true +-- +sendAliveOnCan + + + + UMLState + + 868 + 518 + 266 + 84 + + lt=.. +BREAK +-.. + Relation - 294 - 420 - 182 - 196 + 994 + 294 + 210 + 252 - lt=-> -m1=[alive] - 10.0;110.0;110.0;110.0;110.0;10.0;70.0;10.0 + lt=..> +m1=evPoll\n[time==0]\n[haveBreak] + 60.0;10.0;60.0;110.0;10.0;110.0;10.0;160.0 Relation - 140 - 308 - 168 - 490 + 560 + 546 + 336 + 182 - lt=-> -evACborn - 100.0;290.0;100.0;330.0;10.0;330.0;10.0;10.0;50.0;10.0 + lt=..> +m1=evPoll\n[time==0]\n[haveBreak] + 10.0;50.0;10.0;110.0;90.0;110.0;170.0;10.0;220.0;10.0 + + + Relation + + 602 + 546 + 420 + 182 + + lt=..> +m1=evStart\n[checker] + 220.0;40.0;220.0;110.0;140.0;110.0;60.0;10.0;10.0;10.0 + + + Relation + + 1078 + 252 + 182 + 476 + + lt=..> +m1=evStart\n[sender] + 10.0;250.0;10.0;320.0;110.0;320.0;110.0;10.0;40.0;10.0 + + + UMLNote + + 868 + 728 + 266 + 154 + + lt=.. +break part can be disable +with setHaveBreak(false) + +not all childrens have a break +for time at 0 + diff --git a/UML/can.puml b/UML/can.puml new file mode 100644 index 0000000..b574624 --- /dev/null +++ b/UML/can.puml @@ -0,0 +1,29 @@ +@startuml + +actor CAN_BUS as bus +participant interrupt as ISR +queue XF as xf +participant ecan as ecan +participant can_interface as can +control can_message as msg + + +bus -\\ ISR ++ : can message +ISR -> can : newMsg +can -> ecan : read +ecan --> can : message +can -> xf : POST XF +destroy ISR + group clock xf [every 10ms] +xf o-> can : receiveCan +can -> msg : processIncome +msg -> can : create message +can -> xf : POST XF + end + group clock xf [every 10ms] +xf o-> can : sendCan +can -> ecan : write +ecan -\\ bus : can message + end + +@enduml \ No newline at end of file diff --git a/UML/can_sequence.png b/UML/can_sequence.png new file mode 100644 index 0000000..22a7e70 Binary files /dev/null and b/UML/can_sequence.png differ diff --git a/UML/class.uxf b/UML/class.uxf index 4e335b5..550ed7d 100644 --- a/UML/class.uxf +++ b/UML/class.uxf @@ -1,13 +1,13 @@ - 7 + 10 UMLClass - 105 - 77 - 301 - 126 + 80 + 100 + 430 + 180 CAN_INTERFACE -- @@ -28,10 +28,10 @@ CAN_setSender(idSender: uint8_t): void UMLClass - 315 - 350 - 301 - 126 + 0 + 390 + 430 + 180 JOYSTICK -- @@ -51,10 +51,33 @@ CAN_setSender(idSender: uint8_t): void UMLClass - 812 - 154 - 322 - 504 + 580 + 370 + 490 + 210 + + MEMORY_CST +-- ++CM_processIncome(idSender: uint8_t, idMsg: uint8_t, data: uint32_t): void ++CM_CONTROLLER_ALIVE(p: void*): void ++CM_JOY_SETUP(p: void*): void ++CM_DISPLAY_SETUP(p: void*): void ++CM_DISPLAY_SPEED(p: void*): void ++CM_DISPLAY_DIRECTION(p: void*): void ++CM_DRIVE_SETUP(p: void*): void ++CM_DRIVE_POWER(p: void*): void ++CM_STEERING_SETUP(p: void*): void ++CM_STEERING_SET(p: void*): void ++CM_SUPPLY_SETUP(p: void*): void + + + + UMLClass + + 1140 + 40 + 460 + 720 MEMORY_CST -- diff --git a/UML/drive.pdf b/UML/drive.pdf new file mode 100644 index 0000000..5935edf Binary files /dev/null and b/UML/drive.pdf differ diff --git a/UML/drive.uxf b/UML/drive.uxf new file mode 100644 index 0000000..0f5e6c9 --- /dev/null +++ b/UML/drive.uxf @@ -0,0 +1,137 @@ + + + 15 + + Relation + + 660 + 90 + 210 + 120 + + lt=-> +evInit +/startAliveChecker + + 10.0;10.0;10.0;60.0 + + + UMLSpecialState + + 660 + 75 + 30 + 30 + + type=initial + + + + UMLState + + 540 + 405 + 270 + 105 + + RUN +-- +/entry: LED ON +-- +emitPollTorqueEv + + + + Relation + + 735 + 450 + 195 + 270 + + lt=-> +m1= evPollTorque\n/sendTorque + + 10.0;100.0;10.0;160.0;110.0;160.0;110.0;10.0;50.0;10.0 + + + UMLState + + 495 + 180 + 360 + 135 + + WAIT +-- +ALIVE_emitBorn(ALjoy(), 0, 0); +ALIVE_emitReady(ALjoy(), 100, 0); +setAliveTime + + + + Relation + + 660 + 300 + 120 + 135 + + lt=-> +m1=evStart\n(onWait) + + 10.0;10.0;10.0;70.0 + + + Relation + + 735 + 450 + 195 + 180 + + lt=-> +m1= evPollSpeed\n/sendSpeed + + 10.0;40.0;10.0;100.0;110.0;100.0;110.0;10.0;50.0;10.0 + + + Relation + + 390 + 240 + 345 + 555 + + lt=-> +m1= evResurrect\n(onBorn) + + 130.0;300.0;130.0;350.0;10.0;350.0;10.0;10.0;70.0;10.0 + + + UMLState + + 450 + 600 + 270 + 90 + + DEAD +-- +/entry: LED OFF + + + + Relation + + 570 + 495 + 135 + 135 + + lt=-> +m1=evStop\n(onDead) + + 10.0;10.0;10.0;70.0 + + diff --git a/busmaster_config.cfx b/busmaster_config.cfx index 94c32ac..f5a4e23 100644 --- a/busmaster_config.cfx +++ b/busmaster_config.cfx @@ -8,7 +8,7 @@ FALSE FALSE FALSE - FALSE + TRUE TRUE SYSTEM FALSE @@ -28,10 +28,34 @@ threewheeler.DBF + + + + Parameter + 1 + 200 + 1 + + + Channel 1 + 2 + 90 + 1 + + + + SHOWNORMAL + RESTORETOMAXIMIZED + 517 + 489 + 1014 + 911 + + MHS Tiny-CAN - Bus Off + Unknown 250 @@ -85,27 +109,267 @@ + + + display + PASS + + 306 + 306 + ALL + ALL + ALL + 0 + + + 307 + 307 + ALL + ALL + ALL + 0 + + + 48 + 48 + ALL + ALL + ALL + 0 + + + 799 + 799 + ALL + ALL + ALL + 0 + + + 1585 + 1585 + ALL + ALL + ALL + 0 + + + 1586 + 1586 + ALL + ALL + ALL + 0 + + + 1587 + 1587 + ALL + ALL + ALL + 0 + + + + drive + PASS + + 320 + 320 + ALL + ALL + ALL + 0 + + + 321 + 321 + ALL + ALL + ALL + 0 + + + 1040 + 1040 + ALL + ALL + ALL + 0 + + + 1055 + 1055 + ALL + ALL + ALL + 0 + + + + joy + PASS + + 288 + 288 + ALL + ALL + ALL + 0 + + + 529 + 529 + ALL + ALL + ALL + 0 + + + 543 + 543 + ALL + ALL + ALL + 0 + + + + noAlive + STOP + + 271 + 271 + ALL + ALL + ALL + 0 + + + 543 + 543 + ALL + ALL + ALL + 0 + + + 799 + 799 + ALL + ALL + ALL + 0 + + + 1055 + 1055 + ALL + ALL + ALL + 0 + + + 1311 + 1311 + ALL + ALL + ALL + 0 + + + + steering + PASS + + 336 + 336 + ALL + ALL + ALL + 0 + + + 337 + 337 + ALL + ALL + ALL + 0 + + + 1298 + 1298 + ALL + ALL + ALL + 0 + + + 1311 + 1311 + ALL + ALL + ALL + 0 + + + 82 + 82 + ALL + ALL + ALL + 0 + + + - 288 - DeltaY - aliveTime - timeMeasureOrDeltaX - mode + 529 + posY + button + posX + + + 1040 + Speed + + + 321 + Power + + + 306 + Vehiclespeed + + + 336 + HOMING + RESET + SET_CENTER + ALIVE_TIME + + + 82 + CENTER_POS + + + 1298 + POSITION SHOWNORMAL HIDE - 622 - 86 - 816 - 998 + 165 + 599 + 1089 + 452 - 142 - 174 - 285 - 142 + 147 + 94 + 139 + 94 @@ -118,10 +382,10 @@ 300 - 87 - 87 - 174 - 87 + 94 + 94 + 189 + 94 @@ -134,10 +398,10 @@ 300 - 87 - 87 - 174 - 87 + 94 + 94 + 189 + 94 @@ -156,28 +420,42 @@ TRUE NORMAL + + 321 + DRIVE_POWER + + Power + Physical + SOLID + 16711680 + 1 + 8388736 + TRUE + TRUE + NORMAL + - HIDE - HIDE - -1 - 0 - 0 - 0 + SHOWNORMAL + SHOWNORMAL + 291 + 205 + 957 + 1530 - -1 + 479 0 - 0 + 819 0 - 0 + 308 0 - 0 + 308 0 @@ -192,12 +470,12 @@ - HIDE + SHOWNORMAL RESTORETOMAXIMIZED 0 0 - 0 - 0 + 577 + 423 @@ -212,38 +490,43 @@ - 5000 - 2000 - 100 + 1489464112 + 26186104 + 1489464084 + display + drive + joy + noAlive + steering + 5 + 1 + 19 + + + Time + 4 + 1 + 129 + + + Tx/Rx 1 + 1 + 53 + + + Channel + 2 0 0 - - Time - 2 - 1 - 138 - - - Tx/Rx - 3 - 1 - 85 - - - Channel - 4 - 1 - 92 - Msg Type - 5 - 1 - 71 + 3 + 0 + 0 ID @@ -255,39 +538,39 @@ Message 7 1 - 174 + 143 DLC 8 1 - 75 + 38 Data Byte(s) 9 1 - 198 + 139 1 0 - 0 + 1 SYSTEM SHOWNORMAL - RESTORETOMAXIMIZED + SETMINPOSITION 0 0 - 295 - 909 + 810 + 606 SHOWNORMAL RESTORETOMAXIMIZED - 271 - 879 - 958 - 1552 + 173 + 10 + 451 + 359 @@ -370,23 +653,23 @@ 720 1 - 0 + 1 0 SYSTEM SHOWNORMAL - RESTORETOMAXIMIZED + SETMINPOSITION 0 0 - 543 + 549 1614 SHOWNORMAL RESTORETOMAXIMIZED - 179 + 173 10 - 457 + 451 359 @@ -455,23 +738,23 @@ 734 1 - 0 + 1 0 SYSTEM SHOWNORMAL - RESTORETOMAXIMIZED + SETMINPOSITION 0 0 - 543 + 549 1614 SHOWNORMAL RESTORETOMAXIMIZED - 179 + 173 10 - 457 + 451 359 @@ -479,15 +762,27 @@ SHOWNORMAL SETMINPOSITION - 12 - 989 - 667 - 1849 + 3 + 1052 + 658 + 1912 1 - 528 + 16 + FALSE + FALSE + 4 + 0,0,0,10 + 10 + FALSE + a + FALSE + + + 1 + 17 FALSE FALSE 4 @@ -499,7 +794,7 @@ 1 - 529 + 18 FALSE FALSE 4 @@ -511,11 +806,11 @@ 1 - 288 + 19 FALSE FALSE 4 - 0,255,1,5 + 0,0,0,0 10 FALSE a @@ -523,11 +818,35 @@ 1 - 543 + 20 FALSE FALSE - 1 - 0 + 2 + 0,0 + 10 + FALSE + a + FALSE + + + 1 + 21 + FALSE + FALSE + 4 + 0,0,0,0 + 10 + FALSE + a + FALSE + + + 1 + 22 + FALSE + FALSE + 4 + 0,5,1,25 10 FALSE a diff --git a/threewheeler.DBF b/threewheeler.DBF index 6f5fd33..2cc5931 100644 --- a/threewheeler.DBF +++ b/threewheeler.DBF @@ -6,7 +6,7 @@ [BUSMASTER_VERSION] [3.2.2] -[NUMBER_OF_MESSAGES] 25 +[NUMBER_OF_MESSAGES] 29 [START_MSG] JOY_MEASURE,529,3,3,1,S [START_SIGNALS] posX,8,1,0,I,127,-128,1,0.000000,1.000000,%, @@ -38,10 +38,11 @@ [VALUE_DESCRIPTION] RACE,2 [END_MSG] -[START_MSG] CONTROL_SETUP,16,4,2,1,S +[START_MSG] CONTROL_SETUP,16,4,3,1,S [START_SIGNALS] AliveTime,8,4,0,U,255,0,1,0.000000,10.000000,mS, [VALUE_DESCRIPTION] No alive message,0 [START_SIGNALS] STEERING_MODE,1,1,0,B,1,0,1,0.000000,1.000000,, +[START_SIGNALS] ERASE_MEMORY,1,2,0,B,1,0,1,0.000000,1.000000,, [END_MSG] [START_MSG] CONTROL_SPEED_FACTOR,17,4,1,1,S @@ -71,7 +72,7 @@ [VALUE_DESCRIPTION] No alive message,0 [END_MSG] -[START_MSG] DISPLAY_SETUP,48,4,1,1,S +[START_MSG] DISPLAY_SETUP,304,4,1,1,S [START_SIGNALS] AliveTime,8,4,0,U,255,0,1,0.000000,10.000000,ms, [END_MSG] @@ -150,4 +151,29 @@ [START_MSG] STEERING_GET_POS,1298,4,1,1,S [START_SIGNALS] POSITION,32,4,0,I,2147483647,-2147483648,0,0.000000,1.000000,qc, +[END_MSG] + +[START_MSG] CONTROL_SETUP_PARAM_JOY,22,4,4,1,S +[START_SIGNALS] mode,1,1,0,B,1,0,1,0.000000,1.000000,, +[START_SIGNALS] timeMeasureOrDeltaX,8,2,0,U,255,0,1,0.000000,10.000000,msOrVal, +[START_SIGNALS] DeltaY,8,3,0,U,255,0,1,0.000000,1.000000,val, +[START_SIGNALS] aliveTime,8,4,0,U,255,0,1,0.000000,10.000000,ms, +[END_MSG] + +[START_MSG] CONTROL_SETUP_DRIVE,23,4,3,1,S +[START_SIGNALS] driveAliveTime,8,1,0,U,255,0,1,0.000000,10.000000,ms, +[START_SIGNALS] driveSpeedTime,8,2,0,U,255,0,1,0.000000,10.000000,ms, +[START_SIGNALS] driveStopTime,8,3,0,U,255,0,1,0.000000,10.000000,ms, +[END_MSG] + +[START_MSG] CONTROL_SETUP_PARAM_BATTERY,24,4,4,1,S +[START_SIGNALS] batteryVoltTime,8,1,0,U,255,0,1,0.000000,10.000000,ms, +[START_SIGNALS] batteryCurentTime,8,2,0,U,255,0,1,0.000000,10.000000,ms, +[START_SIGNALS] batteryEnergyTime,8,3,0,U,255,0,1,0.000000,10.000000,ms, +[START_SIGNALS] batteryAliveTime,8,4,0,U,255,0,1,0.000000,10.000000,ms, +[END_MSG] + +[START_MSG] CONTROL_SETUP_PARAM,21,4,2,1,S +[START_SIGNALS] displayAliveTime,8,1,0,U,255,0,1,0.000000,10.000000,ms, +[START_SIGNALS] steeringAliveTime,8,2,0,U,255,0,1,0.000000,10.000000,ms, [END_MSG] \ No newline at end of file