Compare commits
	
		
			107 Commits
		
	
	
		
			478b4f2ff9
			...
			Race
		
	
	| Author | SHA1 | Date | |
|---|---|---|---|
| c7c67d2931 | |||
| 1fa34dea8a | |||
|  | 4d10355dd4 | ||
| d667b7d01e | |||
| c5403fe7f9 | |||
| b7aad73c25 | |||
| 8f1b0c2c13 | |||
| 5c555f6ee1 | |||
| 8d389cdea2 | |||
| cc6a8fc39a | |||
| 5da1775718 | |||
| 84630eb6fd | |||
| 7750978f18 | |||
| 44d4d1210c | |||
| 0329c762a0 | |||
| abbeda177d | |||
| ad9e73f2eb | |||
| 47bc51ac68 | |||
| 628bbd7825 | |||
| 8cec88d658 | |||
| e0b94c5250 | |||
| 32f1bd73b4 | |||
| 6edca8bb82 | |||
| 38b5f2d4e1 | |||
| 319ae576ad | |||
| 4e492fb10b | |||
| 0f7f078440 | |||
| 447c9d8801 | |||
| 7bdc3d10c6 | |||
| 79334b5c89 | |||
| 682dca2bb1 | |||
| f45fd4ae7e | |||
| 473d71ff6b | |||
| 3f1672996d | |||
| 3cd456a154 | |||
| a3d6c9ae6c | |||
| c846a12edb | |||
| 24f63b261b | |||
| 11c95d9fd6 | |||
| 242cf4d0da | |||
| 57b19e59d9 | |||
| 1ad382063c | |||
| 59dcf4e47c | |||
| 33dc145a80 | |||
| 9b304aec93 | |||
| 863977e20f | |||
| 4750463f7b | |||
| 397b77ab5a | |||
| b6bb8fca91 | |||
| 1ea26b2a6c | |||
| ae9252cccb | |||
| d94fcb927d | |||
| 26ea7d0870 | |||
| 296575a4b9 | |||
| b52b773633 | |||
| a20667399b | |||
| 2ece901b08 | |||
| 7aab0ef049 | |||
| b95b6619e3 | |||
| d31544783c | |||
| dc6e4ec65a | |||
| 00130b03ee | |||
| 448b5e66ad | |||
| 4987fbabd0 | |||
| 7550d1907b | |||
| debececcfd | |||
| 72a307654f | |||
| f755095523 | |||
| d26155061d | |||
| 19547261bd | |||
| af8b515578 | |||
| 7e5d85070f | |||
| 6bc73fa166 | |||
| 38d7936da7 | |||
| 59edb49d5c | |||
| 4a44fe6fbf | |||
| 318730091a | |||
| ef36b21ad4 | |||
| fbd207c02e | |||
| d1fbd21d41 | |||
| 3de64a329c | |||
| 792625bab1 | |||
| a360586503 | |||
| 233e1ff5ad | |||
| 7d8f91f554 | |||
| cd219510e2 | |||
| 8dab08f7f8 | |||
| 66ebed131d | |||
| 3c0f78d3b3 | |||
| c0dda9d6d7 | |||
| f60b9166ca | |||
| 9bd3e9b4da | |||
| 4d513277b7 | |||
| 2b31ef5c06 | |||
| 5bbc7bc0c3 | |||
| 97b9e38665 | |||
|  | 70127bbb8d | ||
|  | 4d025d7ac4 | ||
| ae84c45e1c | |||
| 0d766220ed | |||
| 88390a294a | |||
| 88096a007c | |||
| deba3fbf0d | |||
| e3f971bb18 | |||
| d6d667a3c4 | |||
| 4c1ed6ba61 | |||
| 7b4fb451c7 | 
							
								
								
									
										1
									
								
								.gitignore
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										1
									
								
								.gitignore
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @@ -0,0 +1 @@ | |||||||
|  | .idea | ||||||
							
								
								
									
										1
									
								
								306-controller_interface.X/.gitignore
									
									
									
									
										vendored
									
									
								
							
							
						
						
									
										1
									
								
								306-controller_interface.X/.gitignore
									
									
									
									
										vendored
									
									
								
							| @@ -7,7 +7,6 @@ debug/ | |||||||
| dist/ | dist/ | ||||||
| disassembly/ | disassembly/ | ||||||
| nbproject/private/ | nbproject/private/ | ||||||
| nbproject/*.mk |  | ||||||
| nbproject/*.bash | nbproject/*.bash | ||||||
| nbproject/Makefile-genesis.properties | nbproject/Makefile-genesis.properties | ||||||
|  |  | ||||||
|   | |||||||
							
								
								
									
										456
									
								
								306-controller_interface.X/app/can_message.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										456
									
								
								306-controller_interface.X/app/can_message.c
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,456 @@ | |||||||
|  | /** | ||||||
|  |  * @author R<>mi Heredero | ||||||
|  |  * @version 1.0.0 | ||||||
|  |  * @date August 2023 | ||||||
|  |  * @file can_message.c | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #include "can_message.h" | ||||||
|  | #include "car.h" | ||||||
|  | #include "../app/factory/factory.h" | ||||||
|  | #include "../middleware/can_interface.h" | ||||||
|  | #include "kartculator.h" | ||||||
|  |  | ||||||
|  | typedef union { | ||||||
|  |     struct { | ||||||
|  |         uint8_t byte0; | ||||||
|  |         uint8_t byte1; | ||||||
|  |         uint8_t byte2; | ||||||
|  |         uint8_t byte3; | ||||||
|  |     } separate; | ||||||
|  |     uint32_t full; | ||||||
|  | } BYTES_4; | ||||||
|  |  | ||||||
|  | typedef union { | ||||||
|  |     struct { | ||||||
|  |         uint8_t byte0; | ||||||
|  |         uint8_t byte1; | ||||||
|  |     } separate; | ||||||
|  |     uint16_t full; | ||||||
|  | } BYTES_2; | ||||||
|  |  | ||||||
|  | typedef union{ | ||||||
|  |     uint16_t data; | ||||||
|  |     struct{ | ||||||
|  |         uint8_t data[2]; | ||||||
|  |     }byteSplit;   | ||||||
|  |     struct{ | ||||||
|  |         unsigned b0:1; | ||||||
|  |         unsigned b1:1; | ||||||
|  |         unsigned b2:1; | ||||||
|  |         unsigned b3:1; | ||||||
|  |         unsigned b4:1; | ||||||
|  |         unsigned b5:1; | ||||||
|  |         unsigned b6:1; | ||||||
|  |         unsigned b7:1; | ||||||
|  |         unsigned b8:1; | ||||||
|  |         unsigned b9:1; | ||||||
|  |         unsigned b10:1; | ||||||
|  |         unsigned b11:1; | ||||||
|  |         unsigned b12:1; | ||||||
|  |         unsigned b13:1; | ||||||
|  |         unsigned b14:1; | ||||||
|  |         unsigned b15:1; | ||||||
|  |     }bitSplit; | ||||||
|  | } BITFIELD16; | ||||||
|  |  | ||||||
|  | void CM_processIncome(uint8_t idSender, uint8_t idMsg, bool rtr, 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; | ||||||
|  |     BITFIELD16 bField; | ||||||
|  |     bField.data = (uint16_t) data; | ||||||
|  |      | ||||||
|  |     switch(idSender){ | ||||||
|  |          | ||||||
|  |         /********************* | ||||||
|  |          * 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 = revertData.full; | ||||||
|  |                 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 = revertData.full; | ||||||
|  |                 MEM_write_4_byte(MEMADD_CONTROL_POWER_FACTOR, KART_CST.CONTROL_POWER_FACTOR); | ||||||
|  |                 CAN_Send(0, 5, KART_CST.CONTROL_POWER_FACTOR);  | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if(idMsg == 0x3) { // CONTROL_STEERING_FACTOR | ||||||
|  |                 //  valHH   valH    valL    valLL | ||||||
|  |                 KART_CST.CONTROL_STEERING_FACTOR = revertData.full; | ||||||
|  |                 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(&ALWAYS0); | ||||||
|  |                  | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             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(&ALWAYSFALSE); | ||||||
|  |                  | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             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); | ||||||
|  |                  | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if(idMsg == 0x9) { // CONTROL_PARAM_MAX_CHANGES | ||||||
|  |                 //  maxChangeSteering   maxChangeDrive  -   - | ||||||
|  |                 KART_CST.CONTROL_PARAM_MAX_CHANGE_STEERING = incomeData.separate.byte0; | ||||||
|  |                 KART_CST.CONTROL_PARAM_MAX_CHANGE_DRIVE = incomeData.separate.byte1; | ||||||
|  |                 MEM_write_1_byte(MEMADD_CONTROL_PARAM_MAX_CHANGE_STEERING, KART_CST.CONTROL_PARAM_MAX_CHANGE_STEERING); | ||||||
|  |                 MEM_write_1_byte(MEMADD_CONTROL_PARAM_MAX_CHANGE_DRIVE, KART_CST.CONTROL_PARAM_MAX_CHANGE_DRIVE); | ||||||
|  |             } | ||||||
|  |  | ||||||
|  |             break; | ||||||
|  |              | ||||||
|  |              | ||||||
|  |         /************ | ||||||
|  |          * JOYSTICK * | ||||||
|  |          ************/ | ||||||
|  |         case 2: | ||||||
|  |             if(idMsg == 0x1) { // JOY_MESURE | ||||||
|  |                 //  posX    posY    button  - | ||||||
|  |                 calcTorque(incomeData.separate.byte1); | ||||||
|  |                 calcPosition(incomeData.separate.byte0); | ||||||
|  |                 eKart.button = (bool) incomeData.separate.byte2; | ||||||
|  |                 STEERING_emitPollDir(steering()); | ||||||
|  |                  | ||||||
|  |                  | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if(idMsg == 0xF) { // JOY_ALIVE | ||||||
|  |                 //  -   -   -   - | ||||||
|  |                 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; | ||||||
|  |              | ||||||
|  |              | ||||||
|  |         /*********** | ||||||
|  |          * DISPLAY * | ||||||
|  |          ***********/ | ||||||
|  |         case 3: | ||||||
|  |             if(idMsg == 0xF) { // DISPLAY_ALIVE | ||||||
|  |                 //  powerMode   -   -   - | ||||||
|  |                 // TODO display say ALIVE | ||||||
|  |                 eKart.powerMode = incomeData.separate.byte0; | ||||||
|  |                 if (eKart.powerMode == 0) { | ||||||
|  |                     CM_HEADLIGHTS(&ALWAYSFALSE); | ||||||
|  |                 } else { | ||||||
|  |                     CM_HEADLIGHTS(&ALWAYSTRUE); | ||||||
|  |                 } | ||||||
|  |             } | ||||||
|  |             break; | ||||||
|  |              | ||||||
|  |              | ||||||
|  |         /********* | ||||||
|  |          * 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; | ||||||
|  |              | ||||||
|  |              | ||||||
|  |         /************ | ||||||
|  |          * STEERING * | ||||||
|  |          ************/ | ||||||
|  |         case 5: | ||||||
|  |             if(idMsg == 0x1) { // STEERING_GET_CENTER | ||||||
|  |                 //  valHH   valH    valL    valLL | ||||||
|  |                 eKart.center = revertData.full; | ||||||
|  |                 ALIVE_emitReady(&steering()->myChecker, 0, 0); | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if(idMsg == 0x2) { // STEERING_GET_POSITION | ||||||
|  |                 //  valHH   valH    valL    valLL | ||||||
|  |                  | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if(idMsg == 0xE) { // DRIVE_BRAKE | ||||||
|  |                 //  status  -   -   - | ||||||
|  |                 eKart.brake = incomeData.separate.byte0; | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if(idMsg == 0xF) { // STEERING_ALIVE | ||||||
|  |                 //  statusH statusL -   - | ||||||
|  |                 ALIVE_ISALIVE(&steering()->myChecker); | ||||||
|  |                 if(steering()->myChecker.state == STAL_DEAD) { | ||||||
|  |                     KART_CST.STEERING_ALIVE_TIME = MEM_read_1_byte(MEMADD_STEERING_ALIVE_TIME); | ||||||
|  |                     ALIVE_emitResurrect(&steering()->myChecker, 500, 0); | ||||||
|  |                     ALIVE_emitBorn(&steering()->myChecker, 1000, 0); | ||||||
|  |                     //ALIVE_emitReady(&steering()->myChecker, 5000, 0); | ||||||
|  |                 } | ||||||
|  |                 if(bField.bitSplit.b4) { | ||||||
|  |                     if (steering()->myChecker.state == STAL_BORN){ | ||||||
|  |                         ALIVE_emitReady(&steering()->myChecker, 1000, 0); | ||||||
|  |                     } | ||||||
|  |                 } | ||||||
|  |                  | ||||||
|  |                  | ||||||
|  |             } | ||||||
|  |             break; | ||||||
|  |              | ||||||
|  |              | ||||||
|  |         /********** | ||||||
|  |          * SUPPLY * | ||||||
|  |          **********/ | ||||||
|  |         case 6: | ||||||
|  |             if(idMsg == 0x4) { | ||||||
|  |                 DRIVE_startBehaviour(drive()); | ||||||
|  |                 STEERING_startBehaviour(steering()); | ||||||
|  |  | ||||||
|  |                 ALIVE_startBehaviourChecker(ALjoy()); | ||||||
|  |                 ALIVE_emitBorn(ALjoy(), 100, 0); | ||||||
|  |                 ALIVE_emitReady(ALjoy(), 200, 0); | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if(idMsg == 0xF) { // BATTERY_ALIVE | ||||||
|  |                 //  -   -	-	- | ||||||
|  |                 // TODO battery say ALIVE | ||||||
|  |                  | ||||||
|  |             } | ||||||
|  |             break; | ||||||
|  |              | ||||||
|  |              | ||||||
|  |         /************* | ||||||
|  |          * 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 = 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_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); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void CM_HEADLIGHTS(void* p) { | ||||||
|  |     //  status  -   -   - | ||||||
|  |     bool status = *((bool*) p); | ||||||
|  |     CAN_send_1_byte(0, 4, status); | ||||||
|  | } | ||||||
							
								
								
									
										99
									
								
								306-controller_interface.X/app/can_message.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										99
									
								
								306-controller_interface.X/app/can_message.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,99 @@ | |||||||
|  | /** | ||||||
|  |  * @author R<>mi Heredero | ||||||
|  |  * @version 1.0.0 | ||||||
|  |  * @date August 2023 | ||||||
|  |  * @file can_message.h | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #ifndef CAN_MESSAGE_H | ||||||
|  | #define CAN_MESSAGE_H | ||||||
|  |  | ||||||
|  | #include <stdint.h>         // usage of standard types | ||||||
|  | #include <stdbool.h>        // usage of boolean types | ||||||
|  | #include "../mcc_generated_files/mcc.h" | ||||||
|  |  | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * 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, bool rtr, 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); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Send setup to the supply (settings from memory) | ||||||
|  |  * @param p have to be NULL | ||||||
|  |  */ | ||||||
|  | void CM_SUPPLY_SETUP(void* p); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Send headlights on or off | ||||||
|  |  * @param p true if on, false if off; | ||||||
|  |  */ | ||||||
|  | void CM_HEADLIGHTS(void* p); | ||||||
|  |  | ||||||
|  |  | ||||||
|  | #endif	/* CAN_MESSAGE_H */ | ||||||
|  |  | ||||||
| @@ -23,20 +23,35 @@ | |||||||
| /******************* | /******************* | ||||||
|  * MEMORY ADRESSES * |  * MEMORY ADRESSES * | ||||||
|  *******************/ |  *******************/ | ||||||
| #define MEMADD_CONTROL_STEERING_MODE        0x00 | #define MEMADD_CONTROL_STEERING_MODE        0x01 | ||||||
| #define MEMADD_CONTROL_ALIVE_TIME           0x01 | #define MEMADD_CONTROL_ALIVE_TIME           0x02 | ||||||
| #define MEMADD_CONTROL_SPEED_FACTOR         0x02 | #define MEMADD_CONTROL_SPEED_FACTOR         0x03 | ||||||
| #define MEMADD_CONTROL_POWER_FACTOR         0x06 | #define MEMADD_CONTROL_POWER_FACTOR         0x07 | ||||||
| #define MEMADD_CONTROL_STEERING_FACTOR      0x0A | #define MEMADD_CONTROL_STEERING_FACTOR      0x0B | ||||||
| #define MEMADD_CONTROL_MAX_SPEED_FW         0x0E | #define MEMADD_CONTROL_MAX_SPEED_FW         0x0F | ||||||
| #define MEMADD_CONTROL_MAX_SPEED_BW         0x0F | #define MEMADD_CONTROL_MAX_SPEED_BW         0x10 | ||||||
| #define MEMADD_JOYSTICK_ALIVE_TIME          0x10 | #define MEMADD_JOYSTICK_MODE                0x11 | ||||||
| #define MEMADD_DISPLAY_ALIVE_TIME           0x11 | #define MEMADD_JOYSTICK_PARAM1              0x12 | ||||||
| #define MEMADD_DRIVE_SPEED_TIME             0x12 | #define MEMADD_JOYSTICK_PARAM2              0x13 | ||||||
| #define MEMADD_DRIVE_STOP_TIME              0x13 | #define MEMADD_JOYSTICK_ALIVE_TIME          0x14 | ||||||
| #define MEMADD_DRIVE_ALIVE_TIME             0x14 | #define MEMADD_DISPLAY_ALIVE_TIME           0x15 | ||||||
| #define MEMADD_STEERING_ALIVE_TIME          0x15 | #define MEMADD_DRIVE_SPEED_TIME             0x16 | ||||||
| #define MEMADD_BATTERY_ALIVE_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 | ||||||
|  | #define MEMADD_CONTROL_PARAM_MAX_CHANGE_STEERING 0x1E | ||||||
|  | #define MEMADD_CONTROL_PARAM_MAX_CHANGE_DRIVE 0x1F | ||||||
|  |  | ||||||
|  | const bool ALWAYSTRUE = true; | ||||||
|  | const bool ALWAYSFALSE = false; | ||||||
|  | const uint8_t ALWAYS0 = 0; | ||||||
|  | const uint8_t ALWAYS1 = 1; | ||||||
|  | const uint8_t ALWAYS2 = 2; | ||||||
|  | const uint8_t ALWAYS3 = 3; | ||||||
|  |  | ||||||
| typedef struct { | typedef struct { | ||||||
|     uint8_t     CONTROL_STEERING_MODE; |     uint8_t     CONTROL_STEERING_MODE; | ||||||
| @@ -46,15 +61,52 @@ typedef struct { | |||||||
|     uint32_t    CONTROL_STEERING_FACTOR; |     uint32_t    CONTROL_STEERING_FACTOR; | ||||||
|     uint8_t     CONTROL_MAX_SPEED_FW; |     uint8_t     CONTROL_MAX_SPEED_FW; | ||||||
|     uint8_t     CONTROL_MAX_SPEED_BW; |     uint8_t     CONTROL_MAX_SPEED_BW; | ||||||
|  |     uint8_t     JOYSTICK_MODE; | ||||||
|  |     uint8_t     JOYSTICK_PARAM1; | ||||||
|  |     uint8_t     JOYSTICK_PARAM2; | ||||||
|     uint8_t     JOYSTICK_ALIVE_TIME; |     uint8_t     JOYSTICK_ALIVE_TIME; | ||||||
|     uint8_t     DISPLAY_ALIVE_TIME; |     uint8_t     DISPLAY_ALIVE_TIME; | ||||||
|     uint8_t     DRIVE_SPEED_TIME; |     uint8_t     DRIVE_SPEED_TIME; | ||||||
|     uint8_t     DRIVE_STOP_TIME; |     uint8_t     DRIVE_STOP_TIME; | ||||||
|     uint8_t     DRIVE_ALIVE_TIME; |     uint8_t     DRIVE_ALIVE_TIME; | ||||||
|     uint8_t     STEERING_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; |     uint8_t     BATTERY_ALIVE_TIME; | ||||||
| } CAR_CST_TYPE; |     uint8_t     CONTROL_PARAM_MAX_CHANGE_STEERING; | ||||||
| CAR_CST_TYPE CAR_CST; |     uint8_t     CONTROL_PARAM_MAX_CHANGE_DRIVE; | ||||||
|  |  | ||||||
|  | } KART_CST_TYPE; | ||||||
|  | KART_CST_TYPE KART_CST; | ||||||
|  |  | ||||||
|  | typedef struct { | ||||||
|  |     int16_t torque;     //  | ||||||
|  |     uint32_t center;    //  | ||||||
|  |     uint32_t position;  //  | ||||||
|  |     bool button; | ||||||
|  |     uint8_t speed;      // 100m/h | ||||||
|  |     bool brake; | ||||||
|  |     uint8_t powerMode; // 0: eco - 1: normal - 2: race | ||||||
|  |     /* | ||||||
|  |      * 0 - ECO MODE | ||||||
|  |      * Eco mod limit to 1/2 of the maximal current.  | ||||||
|  |      * Position is 1/2 of the maximal angle | ||||||
|  |      *  | ||||||
|  |      * 1 - NORMAL MODE | ||||||
|  |      * Standard ramp for normal mode | ||||||
|  |      * Position is limited to 3/4 of the maximal  | ||||||
|  |      *  | ||||||
|  |      * 2 - RACE MODE | ||||||
|  |      *  | ||||||
|  |      *  | ||||||
|  |      */ | ||||||
|  | } KART_VAR_TYPE; | ||||||
|  | KART_VAR_TYPE eKart; | ||||||
|  |  | ||||||
|  | uint8_t rampTorque[101]; | ||||||
|  | uint8_t rampPosition[101]; | ||||||
|  |  | ||||||
|  |  | ||||||
|  |  | ||||||
| #endif	/* CAR_H */ | #endif	/* CAR_H */ | ||||||
|   | |||||||
							
								
								
									
										179
									
								
								306-controller_interface.X/app/drive.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										179
									
								
								306-controller_interface.X/app/drive.c
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,179 @@ | |||||||
|  | /** | ||||||
|  |  * @author R<>mi Heredero | ||||||
|  |  * @version 1.0.0 | ||||||
|  |  * @date August 2023 | ||||||
|  |  * @file drive.c | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #include "drive.h" | ||||||
|  | #include "car.h" | ||||||
|  | #include "can_message.h" | ||||||
|  | //#include "steering.h" | ||||||
|  | //#include "factory/factory.h" | ||||||
|  |  | ||||||
|  | void DRIVE_init(DRIVE* me){ | ||||||
|  |     me->state = STDR_INIT; | ||||||
|  |     ALIVE_init(&me->myChecker, 2); | ||||||
|  |     ALIVE_onSetup(&me->myChecker, CM_DRIVE_SETUP, &ALWAYSTRUE); | ||||||
|  |     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, 3000, 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); | ||||||
|  | //    STEERING_STATES steeringState = steering()->state; | ||||||
|  |  | ||||||
|  |      | ||||||
|  |     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) { | ||||||
|  |                 //if(steeringState == STST_RUN) { | ||||||
|  |                     CM_DRIVE_POWER(&eKart.torque); | ||||||
|  |                     if (KART_CST.DRIVE_STOP_TIME == 0) KART_CST.DRIVE_STOP_TIME = 1; | ||||||
|  |                     DRIVE_emitPollTorque(me, KART_CST.DRIVE_STOP_TIME*5, 0); | ||||||
|  |                 //} | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if (ev->id == evDRpollSpeed) { | ||||||
|  |                 CM_DISPLAY_SPEED(&eKart.speed); | ||||||
|  |             } | ||||||
|  |             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 (KART_CST.DRIVE_STOP_TIME == 0) KART_CST.DRIVE_STOP_TIME = 1; | ||||||
|  |                 DRIVE_emitPollTorque(me, KART_CST.DRIVE_STOP_TIME*5, 0); | ||||||
|  |                 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; | ||||||
|  | } | ||||||
							
								
								
									
										130
									
								
								306-controller_interface.X/app/drive.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										130
									
								
								306-controller_interface.X/app/drive.h
									
									
									
									
									
										Normal file
									
								
							| @@ -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 = 100, | ||||||
|  |     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 | ||||||
							
								
								
									
										149
									
								
								306-controller_interface.X/app/eeprom.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										149
									
								
								306-controller_interface.X/app/eeprom.c
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,149 @@ | |||||||
|  | /** | ||||||
|  |  * @author R<>mi Heredero | ||||||
|  |  * @version 1.0.0 | ||||||
|  |  * @date August 2023 | ||||||
|  |  * @file eeprom_interface.h | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #include "eeprom.h" | ||||||
|  | #include "../app/car.h" | ||||||
|  | #include "../middleware/can_interface.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 != 0x42){ | ||||||
|  |         KART_CST.CONTROL_STEERING_MODE   =   0; | ||||||
|  |         KART_CST.CONTROL_ALIVE_TIME      =   10; | ||||||
|  |         KART_CST.CONTROL_SPEED_FACTOR    =   111111;    //     111'111 | ||||||
|  |         KART_CST.CONTROL_POWER_FACTOR    =   10000;     //      10'000 | ||||||
|  |         KART_CST.CONTROL_STEERING_FACTOR =   5600240;   //   5'600'024 | ||||||
|  |         KART_CST.CONTROL_MAX_SPEED_FW    =   50; | ||||||
|  |         KART_CST.CONTROL_MAX_SPEED_BW    =   25; | ||||||
|  |          | ||||||
|  |         KART_CST.JOYSTICK_MODE           =   0; // mode 0 is time based, mode 1 is change based | ||||||
|  |         KART_CST.JOYSTICK_PARAM1         =   5; // for mode 0, values are send every param1*10ms | ||||||
|  |         KART_CST.JOYSTICK_PARAM2         =   1; // for mode 0, values need to change param2 at least for sending | ||||||
|  |         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; | ||||||
|  |          | ||||||
|  |         KART_CST.CONTROL_PARAM_MAX_CHANGE_STEERING = 10; | ||||||
|  |         KART_CST.CONTROL_PARAM_MAX_CHANGE_DRIVE = 10; | ||||||
|  |          | ||||||
|  |         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(MEMADD_CONTROL_PARAM_MAX_CHANGE_DRIVE, KART_CST.CONTROL_PARAM_MAX_CHANGE_DRIVE); | ||||||
|  |         MEM_write_1_byte(MEMADD_CONTROL_PARAM_MAX_CHANGE_STEERING, KART_CST.CONTROL_PARAM_MAX_CHANGE_STEERING); | ||||||
|  |          | ||||||
|  |         MEM_write_1_byte(0x0, 0x42); | ||||||
|  |     } 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_4_byte(MEMADD_CONTROL_SPEED_FACTOR); | ||||||
|  |         KART_CST.CONTROL_POWER_FACTOR = MEM_read_4_byte(MEMADD_CONTROL_POWER_FACTOR); | ||||||
|  |         KART_CST.CONTROL_STEERING_FACTOR = MEM_read_4_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); | ||||||
|  |          | ||||||
|  |         KART_CST.CONTROL_PARAM_MAX_CHANGE_DRIVE = MEM_read_1_byte(MEMADD_CONTROL_PARAM_MAX_CHANGE_DRIVE); | ||||||
|  |         KART_CST.CONTROL_PARAM_MAX_CHANGE_STEERING = MEM_read_1_byte(MEMADD_CONTROL_PARAM_MAX_CHANGE_STEERING); | ||||||
|  |          | ||||||
|  |     } | ||||||
|  | } | ||||||
|  |  | ||||||
|  | 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; | ||||||
|  | } | ||||||
							
								
								
									
										22
									
								
								306-controller_interface.X/app/eeprom.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										22
									
								
								306-controller_interface.X/app/eeprom.h
									
									
									
									
									
										Normal file
									
								
							| @@ -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 <stdint.h>         // usage of standard types | ||||||
|  | #include <stdbool.h>        // 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 */ | ||||||
|  |  | ||||||
| @@ -5,24 +5,6 @@ | |||||||
| static Factory theFactory; | static Factory theFactory; | ||||||
|  |  | ||||||
| //all the getters | //all the getters | ||||||
| LED* l1() { |  | ||||||
|     return &theFactory.l1_; |  | ||||||
| } |  | ||||||
| LED* l2()  { |  | ||||||
|     return &theFactory.l2_; |  | ||||||
| } |  | ||||||
| LED* l3()  { |  | ||||||
|     return &theFactory.l3_; |  | ||||||
| } |  | ||||||
| LED* l4()  { |  | ||||||
|     return &theFactory.l4_; |  | ||||||
| } |  | ||||||
| LED* l5()  { |  | ||||||
|     return &theFactory.l5_; |  | ||||||
| } |  | ||||||
| LED* l6()  { |  | ||||||
|     return &theFactory.l6_; |  | ||||||
| } |  | ||||||
| LED* l7()  { | LED* l7()  { | ||||||
|     return &theFactory.l7_; |     return &theFactory.l7_; | ||||||
| } | } | ||||||
| @@ -30,48 +12,77 @@ LED* l8()  { | |||||||
|     return &theFactory.l8_; |     return &theFactory.l8_; | ||||||
| } | } | ||||||
|  |  | ||||||
|  | ALIVE* ALcontroller(){ | ||||||
|  |     return &theFactory.ALcontroller_; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | ALIVE* ALjoy(){ | ||||||
|  |     return &theFactory.ALjoy_; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | DRIVE* drive(){ | ||||||
|  |     return &theFactory.drive_; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | STEERING* steering(){ | ||||||
|  |     return &theFactory.steering_; | ||||||
|  | } | ||||||
|  |  | ||||||
|  |  | ||||||
| //initialize all objects | //initialize all objects | ||||||
| void Factory_init() { | void Factory_init() { | ||||||
|     LED_init(l1(), 1); |  | ||||||
|     LED_init(l2(), 2); |  | ||||||
|     LED_init(l3(), 3); |  | ||||||
|     LED_init(l4(), 4); |  | ||||||
|     LED_init(l5(), 5); |  | ||||||
|     LED_init(l6(), 6); |  | ||||||
|     LED_init(l7(), 7); |     LED_init(l7(), 7); | ||||||
|     LED_init(l8(), 8); |     LED_init(l8(), 8); | ||||||
|  |  | ||||||
|     LED_initHW(l1()); |  | ||||||
|     LED_initHW(l2()); |  | ||||||
|     LED_initHW(l3()); |  | ||||||
|     LED_initHW(l4()); |  | ||||||
|     LED_initHW(l5()); |  | ||||||
|     LED_initHW(l6()); |  | ||||||
|     LED_initHW(l7()); |     LED_initHW(l7()); | ||||||
|     LED_initHW(l8()); |     LED_initHW(l8()); | ||||||
|  |  | ||||||
|     CAN_init(); |     CAN_init(); | ||||||
|     CAN_setSender(1); |     CAN_setSender(1); | ||||||
|     LED_off(l1()); |  | ||||||
| } |  | ||||||
|      |      | ||||||
| void foo(uint8_t a, uint8_t b, uint32_t c){ |     MEM_init(); | ||||||
|     if(b){ |     initRamp(); | ||||||
|         LED_on(l1()); |      | ||||||
|     } else { |     ALIVE_init(ALcontroller(), 5); | ||||||
|         LED_off(l1()); |     ALIVE_setAliveTime(ALcontroller(), KART_CST.CONTROL_ALIVE_TIME); | ||||||
|     } |      | ||||||
|     CAN_Send(a, b, c); |     ALIVE_init(ALjoy(), 1); | ||||||
|  |     DRIVE_init(drive()); | ||||||
|  |     STEERING_init(steering()); | ||||||
| } | } | ||||||
|  |  | ||||||
| //connect objects if required | //connect objects if required | ||||||
| void Factory_build() {     | void Factory_build() {     | ||||||
|     ECAN_SetRXBnInterruptHandler(CAN_newMsg); |     ECAN_SetRXBnInterruptHandler(CAN_newMsg); | ||||||
|     CAN_onReceiveCan(foo); |     CAN_onReceiveCan(CM_processIncome); | ||||||
|  |      | ||||||
|  |     ALIVE_onAlive(ALcontroller(), CM_CONTROLLER_ALIVE, NULL); | ||||||
|  |      | ||||||
|  |     //ALIVE_onSetup(ALjoy(), CM_JOY_SETUP, NULL); | ||||||
|  |     ALIVE_setAliveTime(ALjoy(), KART_CST.JOYSTICK_ALIVE_TIME); | ||||||
|  |     //ALIVE_onBorn(ALjoy(), LED_on, l1()); | ||||||
|  |     ALIVE_onDead(ALjoy(), deadJoystick, NULL); | ||||||
|  |      | ||||||
|  |     //DRIVE_onRun(drive(), LED_on, l2()); | ||||||
|  |     //DRIVE_onDead(drive(), LED_off, l2()); | ||||||
|  |      | ||||||
|  |     //STEERING_onRun(steering(), LED_on, l3()); | ||||||
|  |     //STEERING_onDead(steering(), LED_off, l3()); | ||||||
|  |      | ||||||
| } | } | ||||||
|  |  | ||||||
| //start all state machines | //start all state machines | ||||||
| void Factory_start() { | void Factory_start() { | ||||||
|     CAN_startBehaviour(); |     CAN_startBehaviour(); | ||||||
|  |     ALIVE_startBehaviourSender(ALcontroller()); | ||||||
|  |      | ||||||
|  | /*         | ||||||
|  |     DRIVE_startBehaviour(drive()); | ||||||
|  |     STEERING_startBehaviour(steering()); | ||||||
|  |      | ||||||
|  |     ALIVE_startBehaviourChecker(ALjoy()); | ||||||
|  |     ALIVE_emitBorn(ALjoy(), 100, 0); | ||||||
|  |     ALIVE_emitReady(ALjoy(), 200, 0); | ||||||
|  | */     | ||||||
|  |      | ||||||
|  |      | ||||||
| } | } | ||||||
|   | |||||||
| @@ -12,21 +12,28 @@ | |||||||
| #include <stdint.h> | #include <stdint.h> | ||||||
| #include <stdbool.h> | #include <stdbool.h> | ||||||
|  |  | ||||||
|  | #include "../car.h" | ||||||
|  | #include "../can_message.h" | ||||||
|  | #include "../eeprom.h" | ||||||
|  | #include "../drive.h" | ||||||
|  | #include "../steering.h" | ||||||
|  | #include "../kartculator.h" | ||||||
| #include "../../board/led/led.h" | #include "../../board/led/led.h" | ||||||
| #include "../../board/button/button.h" | #include "../../board/button/button.h" | ||||||
|  | #include "../../middleware/alive.h" | ||||||
| #include "../../middleware/can_interface.h" | #include "../../middleware/can_interface.h" | ||||||
|  | #include "../../middleware/blinker.h" | ||||||
|  |  | ||||||
|  |  | ||||||
| typedef struct { | typedef struct { | ||||||
|     LED l1_; |  | ||||||
|     LED l2_; |  | ||||||
|     LED l3_; |  | ||||||
|     LED l4_; |  | ||||||
|     LED l5_; |  | ||||||
|     LED l6_; |  | ||||||
|     LED l7_; |     LED l7_; | ||||||
|     LED l8_; |     LED l8_; | ||||||
|      |      | ||||||
|  |     ALIVE ALcontroller_; | ||||||
|  |     ALIVE ALjoy_; | ||||||
|  |     DRIVE drive_; | ||||||
|  |     STEERING steering_; | ||||||
|  |  | ||||||
| } Factory; | } Factory; | ||||||
|  |  | ||||||
|  |  | ||||||
| @@ -35,14 +42,13 @@ void Factory_build(); | |||||||
| void Factory_start(); | void Factory_start(); | ||||||
|  |  | ||||||
| //these are global getters for our objects | //these are global getters for our objects | ||||||
| LED* l1(); |  | ||||||
| LED* l2(); |  | ||||||
| LED* l3(); |  | ||||||
| LED* l4(); |  | ||||||
| LED* l5(); |  | ||||||
| LED* l6(); |  | ||||||
| LED* l7(); | LED* l7(); | ||||||
| LED* l8(); | LED* l8(); | ||||||
|  |  | ||||||
|  | ALIVE* ALcontroller(); | ||||||
|  | ALIVE* ALjoy(); | ||||||
|  | DRIVE* drive(); | ||||||
|  | STEERING* steering(); | ||||||
|  |  | ||||||
|  |  | ||||||
| #endif | #endif | ||||||
							
								
								
									
										294
									
								
								306-controller_interface.X/app/kartculator.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										294
									
								
								306-controller_interface.X/app/kartculator.c
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,294 @@ | |||||||
|  | /** | ||||||
|  |  * @author R<>mi Heredero | ||||||
|  |  * @version. 0.0.0 | ||||||
|  |  * @date August 2023 | ||||||
|  |  * @file kartculator.c | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #include "kartculator.h" | ||||||
|  |  | ||||||
|  | void deadJoystick(void* p){ | ||||||
|  |     eKart.torque = 0; | ||||||
|  |     eKart.position = eKart.center; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void initRamp() { | ||||||
|  |     rampTorque[0] = 0; | ||||||
|  |     rampTorque[1] = 3; | ||||||
|  |     rampTorque[2] = 5; | ||||||
|  |     rampTorque[3] = 7; | ||||||
|  |     rampTorque[4] = 10; | ||||||
|  |     rampTorque[5] = 12; | ||||||
|  |     rampTorque[6] = 14; | ||||||
|  |     rampTorque[7] = 16; | ||||||
|  |     rampTorque[8] = 18; | ||||||
|  |     rampTorque[9] = 20; | ||||||
|  |     rampTorque[10] = 22; | ||||||
|  |     rampTorque[11] = 24; | ||||||
|  |     rampTorque[12] = 25; | ||||||
|  |     rampTorque[13] = 27; | ||||||
|  |     rampTorque[14] = 28; | ||||||
|  |     rampTorque[15] = 30; | ||||||
|  |     rampTorque[16] = 31; | ||||||
|  |     rampTorque[17] = 33; | ||||||
|  |     rampTorque[18] = 34; | ||||||
|  |     rampTorque[19] = 36; | ||||||
|  |     rampTorque[20] = 37; | ||||||
|  |     rampTorque[21] = 38; | ||||||
|  |     rampTorque[22] = 39; | ||||||
|  |     rampTorque[23] = 40; | ||||||
|  |     rampTorque[24] = 41; | ||||||
|  |     rampTorque[25] = 42; | ||||||
|  |     rampTorque[26] = 43; | ||||||
|  |     rampTorque[27] = 44; | ||||||
|  |     rampTorque[28] = 45; | ||||||
|  |     rampTorque[29] = 46; | ||||||
|  |     rampTorque[30] = 47; | ||||||
|  |     rampTorque[31] = 47; | ||||||
|  |     rampTorque[32] = 48; | ||||||
|  |     rampTorque[33] = 49; | ||||||
|  |     rampTorque[34] = 50; | ||||||
|  |     rampTorque[35] = 50; | ||||||
|  |     rampTorque[36] = 51; | ||||||
|  |     rampTorque[37] = 51; | ||||||
|  |     rampTorque[38] = 52; | ||||||
|  |     rampTorque[39] = 53; | ||||||
|  |     rampTorque[40] = 53; | ||||||
|  |     rampTorque[41] = 53; | ||||||
|  |     rampTorque[42] = 54; | ||||||
|  |     rampTorque[43] = 54; | ||||||
|  |     rampTorque[44] = 55; | ||||||
|  |     rampTorque[45] = 55; | ||||||
|  |     rampTorque[46] = 56; | ||||||
|  |     rampTorque[47] = 56; | ||||||
|  |     rampTorque[48] = 56; | ||||||
|  |     rampTorque[49] = 57; | ||||||
|  |     rampTorque[50] = 57; | ||||||
|  |     rampTorque[51] = 58; | ||||||
|  |     rampTorque[52] = 58; | ||||||
|  |     rampTorque[53] = 58; | ||||||
|  |     rampTorque[54] = 59; | ||||||
|  |     rampTorque[55] = 59; | ||||||
|  |     rampTorque[56] = 59; | ||||||
|  |     rampTorque[57] = 60; | ||||||
|  |     rampTorque[58] = 60; | ||||||
|  |     rampTorque[59] = 60; | ||||||
|  |     rampTorque[60] = 61; | ||||||
|  |     rampTorque[61] = 61; | ||||||
|  |     rampTorque[62] = 62; | ||||||
|  |     rampTorque[63] = 62; | ||||||
|  |     rampTorque[64] = 62; | ||||||
|  |     rampTorque[65] = 63; | ||||||
|  |     rampTorque[66] = 63; | ||||||
|  |     rampTorque[67] = 64; | ||||||
|  |     rampTorque[68] = 64; | ||||||
|  |     rampTorque[69] = 65; | ||||||
|  |     rampTorque[70] = 65; | ||||||
|  |     rampTorque[71] = 66; | ||||||
|  |     rampTorque[72] = 67; | ||||||
|  |     rampTorque[73] = 67; | ||||||
|  |     rampTorque[74] = 68; | ||||||
|  |     rampTorque[75] = 69; | ||||||
|  |     rampTorque[76] = 69; | ||||||
|  |     rampTorque[77] = 70; | ||||||
|  |     rampTorque[78] = 71; | ||||||
|  |     rampTorque[79] = 72; | ||||||
|  |     rampTorque[80] = 72; | ||||||
|  |     rampTorque[81] = 73; | ||||||
|  |     rampTorque[82] = 74; | ||||||
|  |     rampTorque[83] = 75; | ||||||
|  |     rampTorque[84] = 76; | ||||||
|  |     rampTorque[85] = 77; | ||||||
|  |     rampTorque[86] = 78; | ||||||
|  |     rampTorque[87] = 80; | ||||||
|  |     rampTorque[88] = 81; | ||||||
|  |     rampTorque[89] = 82; | ||||||
|  |     rampTorque[90] = 83; | ||||||
|  |     rampTorque[91] = 85; | ||||||
|  |     rampTorque[92] = 86; | ||||||
|  |     rampTorque[93] = 88; | ||||||
|  |     rampTorque[94] = 89; | ||||||
|  |     rampTorque[95] = 91; | ||||||
|  |     rampTorque[96] = 93; | ||||||
|  |     rampTorque[97] = 94; | ||||||
|  |     rampTorque[98] = 96; | ||||||
|  |     rampTorque[99] = 98; | ||||||
|  |     rampTorque[100] = 100; | ||||||
|  |  | ||||||
|  |     rampPosition[0] = 0; | ||||||
|  |     rampPosition[1] = 0; | ||||||
|  |     rampPosition[2] = 0; | ||||||
|  |     rampPosition[3] = 0; | ||||||
|  |     rampPosition[4] = 0; | ||||||
|  |     rampPosition[5] = 1; | ||||||
|  |     rampPosition[6] = 1; | ||||||
|  |     rampPosition[7] = 1; | ||||||
|  |     rampPosition[8] = 2; | ||||||
|  |     rampPosition[9] = 2; | ||||||
|  |     rampPosition[10] = 3; | ||||||
|  |     rampPosition[11] = 3; | ||||||
|  |     rampPosition[12] = 4; | ||||||
|  |     rampPosition[13] = 5; | ||||||
|  |     rampPosition[14] = 5; | ||||||
|  |     rampPosition[15] = 6; | ||||||
|  |     rampPosition[16] = 7; | ||||||
|  |     rampPosition[17] = 8; | ||||||
|  |     rampPosition[18] = 9; | ||||||
|  |     rampPosition[19] = 9; | ||||||
|  |     rampPosition[20] = 10; | ||||||
|  |     rampPosition[21] = 11; | ||||||
|  |     rampPosition[22] = 12; | ||||||
|  |     rampPosition[23] = 13; | ||||||
|  |     rampPosition[24] = 15; | ||||||
|  |     rampPosition[25] = 16; | ||||||
|  |     rampPosition[26] = 17; | ||||||
|  |     rampPosition[27] = 18; | ||||||
|  |     rampPosition[28] = 19; | ||||||
|  |     rampPosition[29] = 20; | ||||||
|  |     rampPosition[30] = 22; | ||||||
|  |     rampPosition[31] = 23; | ||||||
|  |     rampPosition[32] = 24; | ||||||
|  |     rampPosition[33] = 25; | ||||||
|  |     rampPosition[34] = 27; | ||||||
|  |     rampPosition[35] = 28; | ||||||
|  |     rampPosition[36] = 30; | ||||||
|  |     rampPosition[37] = 31; | ||||||
|  |     rampPosition[38] = 32; | ||||||
|  |     rampPosition[39] = 34; | ||||||
|  |     rampPosition[40] = 35; | ||||||
|  |     rampPosition[41] = 37; | ||||||
|  |     rampPosition[42] = 38; | ||||||
|  |     rampPosition[43] = 40; | ||||||
|  |     rampPosition[44] = 41; | ||||||
|  |     rampPosition[45] = 43; | ||||||
|  |     rampPosition[46] = 44; | ||||||
|  |     rampPosition[47] = 46; | ||||||
|  |     rampPosition[48] = 47; | ||||||
|  |     rampPosition[49] = 49; | ||||||
|  |     rampPosition[50] = 50; | ||||||
|  |     rampPosition[51] = 51; | ||||||
|  |     rampPosition[52] = 53; | ||||||
|  |     rampPosition[53] = 54; | ||||||
|  |     rampPosition[54] = 56; | ||||||
|  |     rampPosition[55] = 57; | ||||||
|  |     rampPosition[56] = 59; | ||||||
|  |     rampPosition[57] = 60; | ||||||
|  |     rampPosition[58] = 62; | ||||||
|  |     rampPosition[59] = 63; | ||||||
|  |     rampPosition[60] = 65; | ||||||
|  |     rampPosition[61] = 66; | ||||||
|  |     rampPosition[62] = 68; | ||||||
|  |     rampPosition[63] = 69; | ||||||
|  |     rampPosition[64] = 70; | ||||||
|  |     rampPosition[65] = 72; | ||||||
|  |     rampPosition[66] = 73; | ||||||
|  |     rampPosition[67] = 75; | ||||||
|  |     rampPosition[68] = 76; | ||||||
|  |     rampPosition[69] = 77; | ||||||
|  |     rampPosition[70] = 78; | ||||||
|  |     rampPosition[71] = 80; | ||||||
|  |     rampPosition[72] = 81; | ||||||
|  |     rampPosition[73] = 82; | ||||||
|  |     rampPosition[74] = 83; | ||||||
|  |     rampPosition[75] = 84; | ||||||
|  |     rampPosition[76] = 85; | ||||||
|  |     rampPosition[77] = 87; | ||||||
|  |     rampPosition[78] = 88; | ||||||
|  |     rampPosition[79] = 89; | ||||||
|  |     rampPosition[80] = 90; | ||||||
|  |     rampPosition[81] = 91; | ||||||
|  |     rampPosition[82] = 91; | ||||||
|  |     rampPosition[83] = 92; | ||||||
|  |     rampPosition[84] = 93; | ||||||
|  |     rampPosition[85] = 94; | ||||||
|  |     rampPosition[86] = 95; | ||||||
|  |     rampPosition[87] = 95; | ||||||
|  |     rampPosition[88] = 96; | ||||||
|  |     rampPosition[89] = 97; | ||||||
|  |     rampPosition[90] = 97; | ||||||
|  |     rampPosition[91] = 98; | ||||||
|  |     rampPosition[92] = 98; | ||||||
|  |     rampPosition[93] = 99; | ||||||
|  |     rampPosition[94] = 99; | ||||||
|  |     rampPosition[95] = 99; | ||||||
|  |     rampPosition[96] = 100; | ||||||
|  |     rampPosition[97] = 100; | ||||||
|  |     rampPosition[98] = 100; | ||||||
|  |     rampPosition[99] = 100; | ||||||
|  |     rampPosition[100] = 100; | ||||||
|  |  | ||||||
|  |  | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void calcTorque(uint8_t joy_pos) { | ||||||
|  |     int32_t calcTorque; | ||||||
|  |     calcTorque = (int8_t) joy_pos;                  // joystick position | ||||||
|  |      | ||||||
|  |     // if mode race, use special curve for torque | ||||||
|  |     if(eKart.powerMode == 2) { | ||||||
|  |         if(calcTorque >= 0) { | ||||||
|  |             calcTorque = rampTorque[calcTorque]; | ||||||
|  |         } else { | ||||||
|  |             calcTorque *= -1; | ||||||
|  |             calcTorque = rampTorque[calcTorque]; | ||||||
|  |             calcTorque *= -1; | ||||||
|  |         } | ||||||
|  |     } | ||||||
|  |      | ||||||
|  |     calcTorque *= KART_CST.CONTROL_POWER_FACTOR;    // convert by power factor | ||||||
|  |     calcTorque /= 1000;                             // torque define by joystick | ||||||
|  |      | ||||||
|  |     if(eKart.button) { | ||||||
|  |         calcTorque *= 1150; | ||||||
|  |         calcTorque /= 1000; | ||||||
|  |     } | ||||||
|  |     eKart.torque = (int16_t) calcTorque; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void calcPosition(uint8_t joy_pos){ | ||||||
|  |     int32_t calcPosition; | ||||||
|  |     calcPosition = (int8_t) joy_pos; | ||||||
|  |     calcPosition *= -1;     // change left and right | ||||||
|  |      | ||||||
|  |     // if mode race, use special curve for steering | ||||||
|  |     if (eKart.powerMode == 2) { | ||||||
|  |         if(calcPosition >= 0) { | ||||||
|  |             calcPosition = rampPosition[calcPosition]; | ||||||
|  |         } else { | ||||||
|  |             calcPosition *= -1; | ||||||
|  |             calcPosition = rampPosition[calcPosition]; | ||||||
|  |             calcPosition *= -1; | ||||||
|  |         } | ||||||
|  |     } | ||||||
|  |      | ||||||
|  |     calcPosition *= (int32_t) KART_CST.CONTROL_STEERING_FACTOR; | ||||||
|  |     calcPosition /= 1000; | ||||||
|  |     calcPosition += eKart.center; | ||||||
|  |     eKart.position = (uint32_t) calcPosition; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void calcSpeed(int32_t rpm) { | ||||||
|  |     int32_t calcSpeed; | ||||||
|  |     if(rpm>=0){ | ||||||
|  |         calcSpeed = rpm; | ||||||
|  |     } else { | ||||||
|  |         calcSpeed = -rpm; | ||||||
|  |     } | ||||||
|  |     calcSpeed *= 2000; | ||||||
|  |     calcSpeed /= KART_CST.CONTROL_SPEED_FACTOR; | ||||||
|  |     eKart.speed = (uint8_t) calcSpeed; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | int16_t getTorque() { | ||||||
|  |      | ||||||
|  | } | ||||||
|  |  | ||||||
|  | uint32_t getPosition() { | ||||||
|  |      | ||||||
|  | } | ||||||
|  |  | ||||||
|  | uint8_t getSpeed() { | ||||||
|  |      | ||||||
|  | } | ||||||
|  |  | ||||||
|  |  | ||||||
							
								
								
									
										26
									
								
								306-controller_interface.X/app/kartculator.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										26
									
								
								306-controller_interface.X/app/kartculator.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,26 @@ | |||||||
|  | /** | ||||||
|  |  * @author R<>mi Heredero | ||||||
|  |  * @version. 0.0.0 | ||||||
|  |  * @date August 2023 | ||||||
|  |  * @file kartculator.h | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #ifndef KARTCULATOR_H | ||||||
|  | #define	KARTCULATOR_H | ||||||
|  |  | ||||||
|  | #include <stdint.h>         // usage of standard types | ||||||
|  | #include <stdbool.h>        // usage of boolean types | ||||||
|  | #include "../mcc_generated_files/mcc.h" | ||||||
|  | #include "car.h" | ||||||
|  |  | ||||||
|  | void initRamp(); | ||||||
|  | void deadJoystick(void* p); | ||||||
|  | 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 */ | ||||||
|  |  | ||||||
							
								
								
									
										173
									
								
								306-controller_interface.X/app/steering.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										173
									
								
								306-controller_interface.X/app/steering.c
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,173 @@ | |||||||
|  | /** | ||||||
|  |  * @author R<>mi Heredero | ||||||
|  |  * @version 1.0.0 | ||||||
|  |  * @date September 2023 | ||||||
|  |  * @file steering.c | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #include "steering.h" | ||||||
|  | #include "can_message.h" | ||||||
|  | #include "car.h" | ||||||
|  | //#include "drive.h" | ||||||
|  |  | ||||||
|  | void alive_born(void* p){ | ||||||
|  |     STEERING* me = (STEERING*) p; | ||||||
|  |     STEERING_emitResurrect(me); | ||||||
|  |     //CM_STEERING_SETUP(&ALWAYS3); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void STEERING_init(STEERING* me){ | ||||||
|  |     me->state = STST_INIT; | ||||||
|  |     ALIVE_init(&me->myChecker, 3); | ||||||
|  |     ALIVE_onSetup(&me->myChecker, CM_STEERING_SETUP, &ALWAYS2); | ||||||
|  |     ALIVE_onWait(&me->myChecker, STEERING_emitStart, me); | ||||||
|  |     ALIVE_onDead(&me->myChecker, STEERING_emitStop, me); | ||||||
|  |     ALIVE_onBorn(&me->myChecker, alive_born, me); | ||||||
|  |     me->wait.f = NULL; | ||||||
|  |     me->run.f = NULL; | ||||||
|  |     me->dead.f = NULL; | ||||||
|  |     eKart.center = 560024; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void STEERING_startBehaviour(STEERING* me){ | ||||||
|  |     POST(me, &STEERING_processEvent, evSTinit, 3000, 0); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool STEERING_processEvent(Event* ev) { | ||||||
|  |     bool processed = false; | ||||||
|  |     STEERING* me = (STEERING*)Event_getTarget(ev); | ||||||
|  |     STEERING_STATES oldState = me->state; | ||||||
|  |     evIDT evid = Event_getId(ev); | ||||||
|  |     uint64_t data = Event_getData(ev); | ||||||
|  |      | ||||||
|  |     switch (me->state) {        // onState | ||||||
|  |         case STST_INIT: | ||||||
|  |             if (ev->id == evSTinit) { | ||||||
|  |                 me->state = STST_WAIT; | ||||||
|  |                 ALIVE_startBehaviourChecker(&me->myChecker); // Start alive checker | ||||||
|  |             } | ||||||
|  |             break; | ||||||
|  |          | ||||||
|  |         case STST_WAIT: | ||||||
|  |             if (ev->id == evSTstart) { | ||||||
|  |                 me->state = STST_RUN; | ||||||
|  |             } | ||||||
|  | //            ALIVE_setAliveTime(&me->myChecker, KART_CST.STEERING_ALIVE_TIME); | ||||||
|  | //            ALIVE_emitBorn(&me->myChecker, 500, 0); | ||||||
|  | //            ALIVE_emitReady(&me->myChecker, 1000, 0); | ||||||
|  |             break; | ||||||
|  |          | ||||||
|  |         case STST_RUN: | ||||||
|  |             if (ev->id == evSTstop) { | ||||||
|  |                 me->state = STST_DEAD; | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if (ev->id == evSTpollDir) { | ||||||
|  |                 //if(drive()->state == STDR_RUN) { | ||||||
|  |                     CM_STEERING_SET(&eKart.position); | ||||||
|  |                 //} | ||||||
|  |             } | ||||||
|  |             break; | ||||||
|  |          | ||||||
|  |         case STST_DEAD: | ||||||
|  |             if (ev->id == evSTresurrect) { | ||||||
|  |                 me->state = STST_WAIT; | ||||||
|  |             } | ||||||
|  |             break; | ||||||
|  |     } | ||||||
|  |  | ||||||
|  |     if(oldState != me->state){ | ||||||
|  |         switch (oldState) {     // onExit | ||||||
|  |             case STST_INIT: | ||||||
|  |                 break; | ||||||
|  |              | ||||||
|  |             case STST_WAIT: | ||||||
|  |                 break; | ||||||
|  |              | ||||||
|  |             case STST_RUN: | ||||||
|  |                 break; | ||||||
|  |              | ||||||
|  |             case STST_DEAD: | ||||||
|  |                 break; | ||||||
|  |         } | ||||||
|  |  | ||||||
|  |         switch (me->state) {    // onEntry | ||||||
|  |             case STST_INIT: | ||||||
|  |                 break; | ||||||
|  |              | ||||||
|  |             case STST_WAIT: | ||||||
|  |                 if (me->wait.f != NULL) { | ||||||
|  |                     me->wait.f(me->wait.p); | ||||||
|  |                 } | ||||||
|  |                 ALIVE_setAliveTime(&me->myChecker, KART_CST.STEERING_ALIVE_TIME); | ||||||
|  |                 ALIVE_emitBorn(&me->myChecker, 500, 0); | ||||||
|  |                 break; | ||||||
|  |              | ||||||
|  |             case STST_RUN: | ||||||
|  |                 if (me->run.f != NULL) { | ||||||
|  |                     me->run.f(me->run.p); | ||||||
|  |                 } | ||||||
|  |                 break; | ||||||
|  |              | ||||||
|  |             case STST_DEAD: | ||||||
|  |                 if (me->dead.f != NULL) { | ||||||
|  |                     me->dead.f(me->dead.p); | ||||||
|  |                 } | ||||||
|  |                 break; | ||||||
|  |         } | ||||||
|  |  | ||||||
|  |         processed = true; | ||||||
|  |     } | ||||||
|  |     return processed; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | /************* | ||||||
|  |  * Callbacks * | ||||||
|  |  *************/ | ||||||
|  |  | ||||||
|  | void STEERING_onWait(STEERING* me, STEERING_CALLBACK_FUNCTION f, void* p) { | ||||||
|  |     me->wait.f = f; | ||||||
|  |     me->wait.p = p; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void STEERING_onRun(STEERING* me, STEERING_CALLBACK_FUNCTION f, void* p) { | ||||||
|  |     me->run.f = f; | ||||||
|  |     me->run.p = p; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void STEERING_onDead(STEERING* me, STEERING_CALLBACK_FUNCTION f, void* p) { | ||||||
|  |     me->dead.f = f; | ||||||
|  |     me->dead.p = p; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | /************ | ||||||
|  |  * EMITTERS * | ||||||
|  |  ************/ | ||||||
|  |  | ||||||
|  | void STEERING_emitStart(void* p) { | ||||||
|  |     STEERING* me = (STEERING*) p; | ||||||
|  |     POST(me, &STEERING_processEvent, evSTstart, 0, 0); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void STEERING_emitStop(void* p) { | ||||||
|  |     STEERING* me = (STEERING*) p; | ||||||
|  |     POST(me, &STEERING_processEvent, evSTstop, 0, 0); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void STEERING_emitResurrect(void* p) { | ||||||
|  |     STEERING* me = (STEERING*) p; | ||||||
|  |     POST(me, &STEERING_processEvent, evSTresurrect, 0, 0); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void STEERING_emitPollDir(void* p) { | ||||||
|  |     STEERING* me = (STEERING*) p; | ||||||
|  |     POST(me, &STEERING_processEvent, evSTpollDir, 0, 0); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | /*********** | ||||||
|  |  * SETTERS * | ||||||
|  |  ***********/ | ||||||
|  |  | ||||||
|  | void STEERING_setMyChecker(STEERING* me, ALIVE v) { | ||||||
|  |     me->myChecker = v; | ||||||
|  | } | ||||||
							
								
								
									
										124
									
								
								306-controller_interface.X/app/steering.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										124
									
								
								306-controller_interface.X/app/steering.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,124 @@ | |||||||
|  | /** | ||||||
|  |  * @author R<>mi Heredero | ||||||
|  |  * @version 1.0.0 | ||||||
|  |  * @date September 2023 | ||||||
|  |  * @file steering.h | ||||||
|  |  */ | ||||||
|  | #ifndef STEERING_H | ||||||
|  | #define STEERING_H | ||||||
|  |  | ||||||
|  | #include "../xf/xf.h" | ||||||
|  | #include "../middleware/alive.h" | ||||||
|  |  | ||||||
|  | typedef enum { | ||||||
|  |     STST_INIT = 110, | ||||||
|  |     STST_WAIT, | ||||||
|  |     STST_RUN, | ||||||
|  |     STST_DEAD | ||||||
|  | } STEERING_STATES; | ||||||
|  |  | ||||||
|  | typedef enum { | ||||||
|  |     evSTinit = 110, | ||||||
|  |     evSTstart, | ||||||
|  |     evSTstop, | ||||||
|  |     evSTresurrect, | ||||||
|  |     evSTpollDir | ||||||
|  | } STEERING_EVENTS; | ||||||
|  |  | ||||||
|  | typedef void (*STEERING_CALLBACK_FUNCTION)(void*); | ||||||
|  | typedef struct { | ||||||
|  |     STEERING_CALLBACK_FUNCTION f; // function | ||||||
|  |     void* p; // param(s) | ||||||
|  | } STEERING_CALLBACK; | ||||||
|  |  | ||||||
|  | typedef struct { | ||||||
|  |     STEERING_STATES state; | ||||||
|  |     ALIVE myChecker; | ||||||
|  |     STEERING_CALLBACK wait; | ||||||
|  |     STEERING_CALLBACK run; | ||||||
|  |     STEERING_CALLBACK dead; | ||||||
|  | } STEERING; | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Initialize the STEERING | ||||||
|  |  * @param me the STEERING itself | ||||||
|  |  */ | ||||||
|  | void STEERING_init(STEERING* me); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Start the STEERING state machine | ||||||
|  |  * @param me the STEERING itself | ||||||
|  |  */ | ||||||
|  | void STEERING_startBehaviour(STEERING* me); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Process the event | ||||||
|  |  * @param ev the event to process | ||||||
|  |  * @return true if the event is processed | ||||||
|  |  */ | ||||||
|  | bool STEERING_processEvent(Event* ev); | ||||||
|  |  | ||||||
|  | /************* | ||||||
|  |  * Callbacks * | ||||||
|  |  *************/ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Set the callback function to call when the STEERING is entering state wait | ||||||
|  |  * @param me the STEERING itself | ||||||
|  |  * @param f the function to call | ||||||
|  |  * @param p the param(s) to pass to the function | ||||||
|  |  */ | ||||||
|  | void STEERING_onWait(STEERING* me, STEERING_CALLBACK_FUNCTION f, void* p); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Set the callback function to call when the STEERING is entering state run | ||||||
|  |  * @param me the STEERING itself | ||||||
|  |  * @param f the function to call | ||||||
|  |  * @param p the param(s) to pass to the function | ||||||
|  |  */ | ||||||
|  | void STEERING_onRun(STEERING* me, STEERING_CALLBACK_FUNCTION f, void* p); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Set the callback function to call when the STEERING is entering state dead | ||||||
|  |  * @param me the STEERING itself | ||||||
|  |  * @param f the function to call | ||||||
|  |  * @param p the param(s) to pass to the function | ||||||
|  |  */ | ||||||
|  | void STEERING_onDead(STEERING* me, STEERING_CALLBACK_FUNCTION f, void* p); | ||||||
|  |  | ||||||
|  | /************ | ||||||
|  |  * EMITTERS * | ||||||
|  |  ************/ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Emit the start event | ||||||
|  |  * @param p the STEERING itself | ||||||
|  |  */ | ||||||
|  | void STEERING_emitStart(void* p); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Emit the stop event | ||||||
|  |  * @param p the STEERING itself | ||||||
|  |  */ | ||||||
|  | void STEERING_emitStop(void* p); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Emit the resurrect event | ||||||
|  |  * @param p the STEERING itself | ||||||
|  |  */ | ||||||
|  | void STEERING_emitResurrect(void* p); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Emit the pollDir event | ||||||
|  |  * @param me the STEERING itself | ||||||
|  |  * @param t time to wait in ms before triggering event | ||||||
|  |  * @param data data to put on the event for XF | ||||||
|  |  */ | ||||||
|  | void STEERING_emitPollDir(void* p); | ||||||
|  |  | ||||||
|  | /*********** | ||||||
|  |  * SETTERS * | ||||||
|  |  ***********/ | ||||||
|  |  | ||||||
|  |  | ||||||
|  | #endif | ||||||
							
								
								
									
										0
									
								
								306-controller_interface.X/defmplabxtrace.log
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										0
									
								
								306-controller_interface.X/defmplabxtrace.log
									
									
									
									
									
										Normal file
									
								
							
							
								
								
									
										
											BIN
										
									
								
								306-controller_interface.X/defmplabxtrace.log.inx
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										
											BIN
										
									
								
								306-controller_interface.X/defmplabxtrace.log.inx
									
									
									
									
									
										Normal file
									
								
							
										
											Binary file not shown.
										
									
								
							| @@ -2,38 +2,27 @@ | |||||||
| #include "xf/xf.h" | #include "xf/xf.h" | ||||||
| #include "app/factory/factory.h" | #include "app/factory/factory.h" | ||||||
|  |  | ||||||
| /* |  | ||||||
|  * the main function |  | ||||||
|  */ |  | ||||||
| void main(void) | void main(void) | ||||||
| { | { | ||||||
|     // Initialize the device |      | ||||||
|     SYSTEM_Initialize(); |     SYSTEM_Initialize(); | ||||||
|  |  | ||||||
|     // Enable the Global Interrupts |  | ||||||
|     INTERRUPT_GlobalInterruptEnable(); |  | ||||||
|  |  | ||||||
|     // Disable the Global Interrupts |  | ||||||
|     // INTERRUPT_GlobalInterruptDisable(); |  | ||||||
|      |  | ||||||
|     // initialize the XF |  | ||||||
|     XF_init(); |     XF_init(); | ||||||
|      |      | ||||||
|     // produce the system |  | ||||||
|     Factory_init(); |     Factory_init(); | ||||||
|     Factory_build(); |     Factory_build(); | ||||||
|     Factory_start(); |     Factory_start(); | ||||||
|  |     //WWDT_SoftEnable(); | ||||||
|      |      | ||||||
|     // let the XF timers handling become the TMR0 interrupt handler |  | ||||||
|     // this means that the XF timers are always decremented when the  |  | ||||||
|     // 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); |     TMR0_SetInterruptHandler(XF_decrementAndQueueTimers); | ||||||
|      |      | ||||||
|  |     INTERRUPT_GlobalInterruptEnable(); | ||||||
|  |  | ||||||
|     while (1) |     while (1) | ||||||
|     { |     { | ||||||
|         //handle the next event if there is any in the queue |          | ||||||
|  |         WWDT_TimerClear(); | ||||||
|         XF_executeOnce(); |         XF_executeOnce(); | ||||||
|         //maybe sleep a short while to save energy |          | ||||||
|     } |     } | ||||||
| } | } | ||||||
| @@ -14,7 +14,7 @@ | |||||||
|     This header file provides implementations for driver APIs for all modules selected in the GUI. |     This header file provides implementations for driver APIs for all modules selected in the GUI. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  2.00 |         Driver Version    :  2.00 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above or later |         Compiler          :  XC8 2.36 and above or later | ||||||
| @@ -73,8 +73,8 @@ | |||||||
| #pragma config XINST = OFF    // Extended Instruction Set Enable bit->Extended Instruction Set and Indexed Addressing Mode disabled | #pragma config XINST = OFF    // Extended Instruction Set Enable bit->Extended Instruction Set and Indexed Addressing Mode disabled | ||||||
|  |  | ||||||
| // CONFIG3L | // CONFIG3L | ||||||
| #pragma config WDTCPS = WDTCPS_31    // WDT Period selection bits->Divider ratio 1:65536; software control of WDTPS | #pragma config WDTCPS = WDTCPS_6    // WDT Period selection bits->Divider ratio 1:2048 | ||||||
| #pragma config WDTE = OFF    // WDT operating mode->WDT Disabled; SWDTEN is ignored | #pragma config WDTE = SWDTEN    // WDT operating mode->WDT enabled/disabled by SWDTEN bit | ||||||
|  |  | ||||||
| // CONFIG3H | // CONFIG3H | ||||||
| #pragma config WDTCWS = WDTCWS_7    // WDT Window Select bits->window always open (100%); software control; keyed access not required | #pragma config WDTCWS = WDTCWS_7    // WDT Window Select bits->window always open (100%); software control; keyed access not required | ||||||
|   | |||||||
| @@ -14,7 +14,7 @@ | |||||||
|     This header file provides implementations for driver APIs for all modules selected in the GUI. |     This header file provides implementations for driver APIs for all modules selected in the GUI. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  2.00 |         Driver Version    :  2.00 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above or later |         Compiler          :  XC8 2.36 and above or later | ||||||
|   | |||||||
| @@ -130,17 +130,21 @@ void ECAN_Initialize(void) | |||||||
|     /* |     /* | ||||||
|      * ENABLE FILTERS |      * ENABLE FILTERS | ||||||
|      *  |      *  | ||||||
|      * Filter 0 set on mask 0 |      * RXF7EN RXF6EN RXF5EN RXF4EN RXF3EN RXF2EN RXF1EN RXF0EN | ||||||
|      * Filter 1 set on mask 0 |      * 0b 00000111 | ||||||
|      * Filter 2 set on mask 1 |  | ||||||
|      */ |      */ | ||||||
|     RXFCON0 = 0x07; |     RXFCON0 = 0x07; | ||||||
|      |      | ||||||
|      |      | ||||||
|     /** |     /* | ||||||
|     Assign Filters to Masks |      * Assign Filters to Masks | ||||||
|     */ |      *  | ||||||
|     // Filter 0 & 1 assigned to mask 0 and filter 2 assigned to mask 1 |      * 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; |     MSEL0 = 0x10; | ||||||
|  |  | ||||||
|     /** |     /** | ||||||
|   | |||||||
| @@ -16,7 +16,7 @@ | |||||||
|     all modules selected in the GUI. |     all modules selected in the GUI. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  2.04 |         Driver Version    :  2.04 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above or later |         Compiler          :  XC8 2.36 and above or later | ||||||
|   | |||||||
| @@ -16,7 +16,7 @@ | |||||||
|     all modules selected in the GUI. |     all modules selected in the GUI. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  2.03 |         Driver Version    :  2.03 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above or later |         Compiler          :  XC8 2.36 and above or later | ||||||
|   | |||||||
| @@ -14,7 +14,7 @@ | |||||||
|     This header file provides implementations for driver APIs for all modules selected in the GUI. |     This header file provides implementations for driver APIs for all modules selected in the GUI. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  2.00 |         Driver Version    :  2.00 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above or later |         Compiler          :  XC8 2.36 and above or later | ||||||
| @@ -53,6 +53,7 @@ void SYSTEM_Initialize(void) | |||||||
|     PMD_Initialize(); |     PMD_Initialize(); | ||||||
|     PIN_MANAGER_Initialize(); |     PIN_MANAGER_Initialize(); | ||||||
|     OSCILLATOR_Initialize(); |     OSCILLATOR_Initialize(); | ||||||
|  |     WWDT_Initialize(); | ||||||
|     TMR0_Initialize(); |     TMR0_Initialize(); | ||||||
|     ECAN_Initialize(); |     ECAN_Initialize(); | ||||||
| } | } | ||||||
| @@ -92,6 +93,50 @@ void PMD_Initialize(void) | |||||||
| } | } | ||||||
|  |  | ||||||
|  |  | ||||||
|  | void WWDT_Initialize(void) | ||||||
|  | { | ||||||
|  |     // Initializes the WWDT to the default states configured in the MCC GUI | ||||||
|  |     WDTCON0 = WDTCPS; | ||||||
|  |     WDTCON1 = WDTCWS|WDTCCS; | ||||||
|  |      | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void WWDT_SoftEnable(void) | ||||||
|  | { | ||||||
|  |     // WWDT software enable.  | ||||||
|  |     WDTCON0bits.SEN=1; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void WWDT_SoftDisable(void) | ||||||
|  | { | ||||||
|  |     // WWDT software disable. | ||||||
|  |     WDTCON0bits.SEN=0; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool WWDT_TimeOutStatusGet(void) | ||||||
|  | { | ||||||
|  |     // Return the status of WWDT time out reset. | ||||||
|  |     return (PCON0bits.nRWDT); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool WWDT_WindowViolationStatusGet(void) | ||||||
|  | { | ||||||
|  |    // Return the status of WWDT window violation reset. | ||||||
|  |     return (PCON0bits.nWDTWV);  | ||||||
|  | }   | ||||||
|  |  | ||||||
|  | void WWDT_TimerClear(void) | ||||||
|  | { | ||||||
|  |     // Disable the interrupt,read back the WDTCON0 reg for arming,  | ||||||
|  |     // clearing the WWDT and enable the interrupt. | ||||||
|  |     uint8_t readBack=0; | ||||||
|  |      | ||||||
|  |     bool state = GIE; | ||||||
|  |     GIE = 0; | ||||||
|  |     readBack = WDTCON0; | ||||||
|  |     CLRWDT(); | ||||||
|  |     GIE = state; | ||||||
|  | } | ||||||
| /** | /** | ||||||
|  End of File |  End of File | ||||||
| */ | */ | ||||||
|   | |||||||
| @@ -14,7 +14,7 @@ | |||||||
|     This header file provides implementations for driver APIs for all modules selected in the GUI. |     This header file provides implementations for driver APIs for all modules selected in the GUI. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  2.00 |         Driver Version    :  2.00 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above or later |         Compiler          :  XC8 2.36 and above or later | ||||||
| @@ -57,6 +57,9 @@ | |||||||
| #include "tmr0.h" | #include "tmr0.h" | ||||||
| #include "ecan.h" | #include "ecan.h" | ||||||
|  |  | ||||||
|  | #define WDTCWS  7 | ||||||
|  | #define WDTCCS  48 | ||||||
|  | #define WDTCPS  12 | ||||||
|  |  | ||||||
|  |  | ||||||
| /** | /** | ||||||
| @@ -98,6 +101,84 @@ void OSCILLATOR_Initialize(void); | |||||||
|  */ |  */ | ||||||
| void PMD_Initialize(void); | void PMD_Initialize(void); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * @Param | ||||||
|  |     none | ||||||
|  |  * @Returns | ||||||
|  |     none | ||||||
|  |  * @Description | ||||||
|  |     Initializes the WWDT to the default states configured in the | ||||||
|  |  *                  MCC GUI | ||||||
|  |  * @Example | ||||||
|  |     WWDT_Initialize(); | ||||||
|  |  */ | ||||||
|  | void WWDT_Initialize(void); | ||||||
|  |  | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * @Param | ||||||
|  |     none | ||||||
|  |  * @Returns | ||||||
|  |     none | ||||||
|  |  * @Description | ||||||
|  |    Enable the WWDT by setting the SEN bit. | ||||||
|  |  * @Example | ||||||
|  |     WWDT_SoftEnable(); | ||||||
|  |  */ | ||||||
|  | void WWDT_SoftEnable(void); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * @Param | ||||||
|  |     none | ||||||
|  |  * @Returns | ||||||
|  |     none | ||||||
|  |  * @Description | ||||||
|  |    Disable the WWDT by clearing the SEN bit. | ||||||
|  |  * @Example | ||||||
|  |     WWDT_SoftDisable(); | ||||||
|  |  */ | ||||||
|  | void WWDT_SoftDisable(void); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * @Param | ||||||
|  |     none | ||||||
|  |  * @Returns | ||||||
|  |     none | ||||||
|  |  * @Description | ||||||
|  |    Disable the interrupt, arm the WWDT by reading back the WDTCON0 register | ||||||
|  |  * clear the WWDT and enable the interrupt. | ||||||
|  |  * @Example | ||||||
|  |     WWDT_TimerClear(); | ||||||
|  |  */ | ||||||
|  | void WWDT_TimerClear(void); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * @Param | ||||||
|  |     none | ||||||
|  |  * @Returns | ||||||
|  |    High --> WWDT reset has not occurred.  | ||||||
|  |  * Low  --> WWDT reset has  occurred. | ||||||
|  |  * @Description | ||||||
|  |     Returns the status of whether the WWDT reset has occurred or not. | ||||||
|  |  * @Example | ||||||
|  |     if(WWDT_TimeOutStatusGet()) | ||||||
|  |  */ | ||||||
|  | bool WWDT_TimeOutStatusGet(void); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * @Param | ||||||
|  |     none | ||||||
|  |  * @Returns | ||||||
|  |    High --> WWDT window violation reset has not occurred.  | ||||||
|  |  * Low  --> WWDT window violation reset has  occurred. | ||||||
|  |  * @Description | ||||||
|  |     Returns the status of, whether the WWDT window violation  | ||||||
|  |  *  reset has occurred or not. | ||||||
|  |  * @Example | ||||||
|  |     if(WWDT_WindowViolationStatusGet()) | ||||||
|  |  */ | ||||||
|  | bool WWDT_WindowViolationStatusGet(void); | ||||||
|  |        | ||||||
|  |  | ||||||
| #endif	/* MCC_H */ | #endif	/* MCC_H */ | ||||||
| /** | /** | ||||||
|   | |||||||
| @@ -14,7 +14,7 @@ | |||||||
|     This file provides implementations of driver APIs for MEMORY. |     This file provides implementations of driver APIs for MEMORY. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  2.1.3 |         Driver Version    :  2.1.3 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above |         Compiler          :  XC8 2.36 and above | ||||||
| @@ -198,7 +198,6 @@ uint8_t DATAEE_ReadByte(uint16_t bAdd) | |||||||
|  |  | ||||||
| void MEMORY_Tasks( void ) | void MEMORY_Tasks( void ) | ||||||
| { | { | ||||||
|     /* TODO : Add interrupt handling code */ |  | ||||||
|     PIR0bits.NVMIF = 0; |     PIR0bits.NVMIF = 0; | ||||||
| } | } | ||||||
| /** | /** | ||||||
|   | |||||||
| @@ -14,7 +14,7 @@ | |||||||
|     This header file provides APIs for driver for MEMORY. |     This header file provides APIs for driver for MEMORY. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  2.1.3 |         Driver Version    :  2.1.3 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above |         Compiler          :  XC8 2.36 and above | ||||||
| @@ -64,9 +64,9 @@ | |||||||
|   Section: Macro Declarations |   Section: Macro Declarations | ||||||
| */ | */ | ||||||
|  |  | ||||||
| #define WRITE_FLASH_BLOCKSIZE    64 | #define WRITE_FLASH_BLOCKSIZE    128 | ||||||
| #define ERASE_FLASH_BLOCKSIZE    64 | #define ERASE_FLASH_BLOCKSIZE    128 | ||||||
| #define END_FLASH                0x008000 | #define END_FLASH                0x010000 | ||||||
|  |  | ||||||
| /** | /** | ||||||
|   Section: Flash Module APIs |   Section: Flash Module APIs | ||||||
|   | |||||||
| @@ -14,7 +14,7 @@ | |||||||
|     This header file provides implementations for pin APIs for all pins selected in the GUI. |     This header file provides implementations for pin APIs for all pins selected in the GUI. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  2.11 |         Driver Version    :  2.11 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above |         Compiler          :  XC8 2.36 and above | ||||||
|   | |||||||
| @@ -14,7 +14,7 @@ | |||||||
|     This header file provides APIs for driver for . |     This header file provides APIs for driver for . | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  2.11 |         Driver Version    :  2.11 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above |         Compiler          :  XC8 2.36 and above | ||||||
|   | |||||||
| @@ -14,7 +14,7 @@ | |||||||
|     This source file provides APIs for TMR0. |     This source file provides APIs for TMR0. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  3.10 |         Driver Version    :  3.10 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above |         Compiler          :  XC8 2.36 and above | ||||||
|   | |||||||
| @@ -14,7 +14,7 @@ | |||||||
|     This header file provides APIs for TMR0. |     This header file provides APIs for TMR0. | ||||||
|     Generation Information : |     Generation Information : | ||||||
|         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 |         Product Revision  :  PIC10 / PIC12 / PIC16 / PIC18 MCUs - 1.81.8 | ||||||
|         Device            :  PIC18F25K83 |         Device            :  PIC18F26K83 | ||||||
|         Driver Version    :  3.10 |         Driver Version    :  3.10 | ||||||
|     The generated drivers are tested against the following: |     The generated drivers are tested against the following: | ||||||
|         Compiler          :  XC8 2.36 and above |         Compiler          :  XC8 2.36 and above | ||||||
|   | |||||||
							
								
								
									
										281
									
								
								306-controller_interface.X/middleware/alive.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										281
									
								
								306-controller_interface.X/middleware/alive.c
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,281 @@ | |||||||
|  | /** | ||||||
|  |  * @author R<>mi Heredero | ||||||
|  |  * @version 1.0.0 | ||||||
|  |  * @date August 2023 | ||||||
|  |  * @file alive.c | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #include "alive.h" | ||||||
|  |  | ||||||
|  | void ALIVE_init(ALIVE* me, uint8_t led){ | ||||||
|  |     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; | ||||||
|  |     LED_init(&me->debugLed, led); | ||||||
|  |     LED_initHW(&me->debugLed); | ||||||
|  |     BLINKER_init(&me->debugBlinker); | ||||||
|  |     BLINKER_setTimeOn(&me->debugBlinker, 50); | ||||||
|  |     BLINKER_setTimeOff(&me->debugBlinker, 50); | ||||||
|  |     BLINKER_onOn(&me->debugBlinker, LED_on, &me->debugLed); | ||||||
|  |     BLINKER_onOff(&me->debugBlinker, LED_off, &me->debugLed); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void ALIVE_startBehaviourChecker(ALIVE* me){ | ||||||
|  |     BLINKER_startBehaviour(&me->debugBlinker); | ||||||
|  |     POST(me, &ALIVE_processEvent, evALinitChecker, 10, 0); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void ALIVE_startBehaviourSender(ALIVE* me){ | ||||||
|  |     BLINKER_startBehaviour(&me->debugBlinker); | ||||||
|  |     POST(me, &ALIVE_processEvent, evALinitSender, 10, 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: | ||||||
|  |             LED_on(&me->debugLed); | ||||||
|  |             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*20, 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*20, 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*20, 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: | ||||||
|  |                 BLINKER_endBlink(&me->debugBlinker); | ||||||
|  |                 break; | ||||||
|  |              | ||||||
|  |             case STAL_DEAD: | ||||||
|  |                 break; | ||||||
|  |              | ||||||
|  |             case STAL_ALIVE: | ||||||
|  |                 BLINKER_endBlink(&me->debugBlinker); | ||||||
|  |                 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: | ||||||
|  |                 LED_off(&me->debugLed); | ||||||
|  |                 BLINKER_emitBlink(&me->debugBlinker, 0); | ||||||
|  |                 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: | ||||||
|  |                 LED_off(&me->debugLed); | ||||||
|  |                 BLINKER_emitBlink(&me->debugBlinker, 0); | ||||||
|  |                 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); | ||||||
|  | } | ||||||
							
								
								
									
										191
									
								
								306-controller_interface.X/middleware/alive.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										191
									
								
								306-controller_interface.X/middleware/alive.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,191 @@ | |||||||
|  | /** | ||||||
|  |  * @author R<>mi Heredero | ||||||
|  |  * @version 1.0.0 | ||||||
|  |  * @date August 2023 | ||||||
|  |  * @file alive.h | ||||||
|  |  */ | ||||||
|  | #ifndef ALIVE_H | ||||||
|  | #define ALIVE_H | ||||||
|  |  | ||||||
|  | #include "../xf/xf.h" | ||||||
|  | #include "../board/led/led.h" | ||||||
|  | #include "../middleware/blinker.h" | ||||||
|  |  | ||||||
|  | typedef enum { | ||||||
|  |     STAL_INIT = 20, | ||||||
|  |     STAL_SETUP, | ||||||
|  |     STAL_BORN, | ||||||
|  |     STAL_WAIT, | ||||||
|  |     STAL_DEAD, | ||||||
|  |     STAL_ALIVE, | ||||||
|  |     STAL_BREAK | ||||||
|  | } ALIVE_STATES; | ||||||
|  |  | ||||||
|  | typedef enum { | ||||||
|  |     evALinitChecker = 20, | ||||||
|  |     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; | ||||||
|  |     LED debugLed; | ||||||
|  |     BLINKER debugBlinker; | ||||||
|  |     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, uint8_t led); | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * 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 | ||||||
| @@ -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; |  | ||||||
|                 } |  | ||||||
|             } |  | ||||||
|             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: |  | ||||||
|                 me->isAlive = false; |  | ||||||
|                 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->aliveTime = v; |  | ||||||
| } |  | ||||||
|  |  | ||||||
| void ALIVE_CHECKER_ISALIVE(ALIVE_CHECKER* me) { |  | ||||||
|     ALIVE_CHECKER_setIsAlive(me, true); |  | ||||||
| } |  | ||||||
| @@ -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 |  | ||||||
							
								
								
									
										189
									
								
								306-controller_interface.X/middleware/blinker.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										189
									
								
								306-controller_interface.X/middleware/blinker.c
									
									
									
									
									
										Normal file
									
								
							| @@ -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 = (me->remainBlinks) - 1; | ||||||
|  |             } | ||||||
|  |             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; | ||||||
|  | } | ||||||
							
								
								
									
										167
									
								
								306-controller_interface.X/middleware/blinker.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										167
									
								
								306-controller_interface.X/middleware/blinker.h
									
									
									
									
									
										Normal file
									
								
							| @@ -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 | ||||||
| @@ -1,5 +1,5 @@ | |||||||
| /** | /** | ||||||
|  * @author R<>mi Heredero |  * @author R<>mi Heredero | ||||||
|  * @version 1.0.0 |  * @version 1.0.0 | ||||||
|  * @date August 2023 |  * @date August 2023 | ||||||
|  * @file can_interface.c |  * @file can_interface.c | ||||||
| @@ -34,12 +34,11 @@ typedef union { | |||||||
|         uint8_t byte2; |         uint8_t byte2; | ||||||
|         uint8_t byte3; |         uint8_t byte3; | ||||||
|     } separate; |     } separate; | ||||||
|     struct { |     uint32_t full; | ||||||
|         uint32_t bytes; |  | ||||||
|     } full; |  | ||||||
| } CAN_4_BYTES; | } CAN_4_BYTES; | ||||||
|  |  | ||||||
| void CAN_init(){ | void CAN_init(){ | ||||||
|  |     CAN_myself.state = STCA_INIT; | ||||||
|     CAN_myself.receiveCan = NULL; |     CAN_myself.receiveCan = NULL; | ||||||
|     CAN_myself.sender = 0; |     CAN_myself.sender = 0; | ||||||
| } | } | ||||||
| @@ -55,6 +54,12 @@ bool CAN_processEvent(Event* ev) { | |||||||
|     evIDT evid = Event_getId(ev); |     evIDT evid = Event_getId(ev); | ||||||
|      |      | ||||||
|     uint64_t data = Event_getData(ev); |     uint64_t data = Event_getData(ev); | ||||||
|  |     CAN_4_BYTES tmpData; | ||||||
|  |     uCAN_MSG canMsg; | ||||||
|  |     uint32_t canData = (uint32_t) data; | ||||||
|  |     uint8_t idMsg; | ||||||
|  |     uint8_t idRecipient; | ||||||
|  |     uint8_t idSender; | ||||||
|      |      | ||||||
|          |          | ||||||
|     switch (me->state) {        // onState |     switch (me->state) {        // onState | ||||||
| @@ -69,37 +74,115 @@ bool CAN_processEvent(Event* ev) { | |||||||
|             // New message arrive |             // New message arrive | ||||||
|             if (ev->id == evCAnewMsg) { |             if (ev->id == evCAnewMsg) { | ||||||
|                 if (me->receiveCan != NULL) { |                 if (me->receiveCan != NULL) { | ||||||
|                     uint32_t canData = (uint32_t) data; |  | ||||||
|                     data = data>>32; |                     data = data>>32; | ||||||
|  |  | ||||||
|                     CAN_4_BYTES tmpData; |                     tmpData.full = data; | ||||||
|                     tmpData.full.bytes = data; |                     idMsg = tmpData.separate.byte0; | ||||||
|                     uint8_t idMsg = tmpData.separate.byte0; |  | ||||||
|                     idMsg = idMsg >> 4; |                     idMsg = idMsg >> 4; | ||||||
|                     idMsg = idMsg & 0xF; |                     idMsg = idMsg & 0xF; | ||||||
|                     uint8_t idRecipient = tmpData.separate.byte1; |                     idRecipient = tmpData.separate.byte1; | ||||||
|                     idRecipient = idRecipient & 0xF; |                     idRecipient = idRecipient & 0xF; | ||||||
|                     uint8_t idSender = tmpData.separate.byte1; |                     idSender = tmpData.separate.byte1; | ||||||
|                     idSender = idSender >> 4; |                     idSender = idSender >> 4; | ||||||
|  |  | ||||||
|                     me->receiveCan(idSender, idMsg, canData); |                     me->receiveCan(idSender, idMsg, false, canData); | ||||||
|  |                 } | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if (ev->id == evCAnewRTR) { | ||||||
|  |                 if (me->receiveCan != NULL) { | ||||||
|  |                     data = data>>32; | ||||||
|  |  | ||||||
|  |                     tmpData.full = data; | ||||||
|  |                     idMsg = tmpData.separate.byte0; | ||||||
|  |                     idMsg = idMsg >> 4; | ||||||
|  |                     idMsg = idMsg & 0xF; | ||||||
|  |                     idRecipient = tmpData.separate.byte1; | ||||||
|  |                     idRecipient = idRecipient & 0xF; | ||||||
|  |                     idSender = tmpData.separate.byte1; | ||||||
|  |                     idSender = idSender >> 4; | ||||||
|  |  | ||||||
|  |                     me->receiveCan(idSender, idMsg, true, canData); | ||||||
|                 } |                 } | ||||||
|             } |             } | ||||||
|              |              | ||||||
|             // Send a message |             // Send a message | ||||||
|             if (ev->id == evCAsend) { |             if (ev->id == evCAsend4) { | ||||||
|                 uCAN_MSG canMsg; |  | ||||||
|                 canMsg.frame.idType = dSTANDARD_CAN_MSG_ID_2_0B;    // standard |                 canMsg.frame.idType = dSTANDARD_CAN_MSG_ID_2_0B;    // standard | ||||||
|                 canMsg.frame.dlc = 4;                               // 4 bytes to send |                 canMsg.frame.dlc = 4;                               // 4 bytes to send | ||||||
|                 canMsg.frame.rtr = 0;                               // no remote frame |                 canMsg.frame.rtr = 0;                               // no remote frame | ||||||
|                 canMsg.frame.data3 = (uint8_t) data; |                 canMsg.frame.data0 = (uint8_t) data; | ||||||
|                 data = data >> 8; |  | ||||||
|                 canMsg.frame.data2 = (uint8_t) data; |  | ||||||
|                 data = data >> 8; |                 data = data >> 8; | ||||||
|                 canMsg.frame.data1 = (uint8_t) data; |                 canMsg.frame.data1 = (uint8_t) data; | ||||||
|                 data = data >> 8; |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data2 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data3 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.id = (uint32_t) data; | ||||||
|  |                 CAN_transmit(&canMsg); | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if (ev->id == evCAsend2) { | ||||||
|  |                 canMsg.frame.idType = dSTANDARD_CAN_MSG_ID_2_0B;    // standard | ||||||
|  |                 canMsg.frame.dlc = 2;                               // 4 bytes to send | ||||||
|  |                 canMsg.frame.rtr = 0;                               // no remote frame | ||||||
|                 canMsg.frame.data0 = (uint8_t) data; |                 canMsg.frame.data0 = (uint8_t) data; | ||||||
|                 data = data >> 8; |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data1 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data2 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data3 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.id = (uint32_t) data; | ||||||
|  |                 CAN_transmit(&canMsg); | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if (ev->id == evCAsend1) { | ||||||
|  |                 canMsg.frame.idType = dSTANDARD_CAN_MSG_ID_2_0B;    // standard | ||||||
|  |                 canMsg.frame.dlc = 1;                               // 4 bytes to send | ||||||
|  |                 canMsg.frame.rtr = 0;                               // no remote frame | ||||||
|  |                 canMsg.frame.data0 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data1 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data2 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data3 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.id = (uint32_t) data; | ||||||
|  |                 CAN_transmit(&canMsg); | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if (ev->id == evCAsend0) { | ||||||
|  |                 canMsg.frame.idType = dSTANDARD_CAN_MSG_ID_2_0B;    // standard | ||||||
|  |                 canMsg.frame.dlc = 0;                               // 4 bytes to send | ||||||
|  |                 canMsg.frame.rtr = 0;                               // no remote frame | ||||||
|  |                 canMsg.frame.data0 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data1 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data2 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data3 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.id = (uint32_t) data; | ||||||
|  |                 CAN_transmit(&canMsg); | ||||||
|  |             } | ||||||
|  |              | ||||||
|  |             if (ev->id == evCAsendRTR) { | ||||||
|  |                 canMsg.frame.idType = dSTANDARD_CAN_MSG_ID_2_0B;    // standard | ||||||
|  |                 canMsg.frame.dlc = 0;                               // 4 bytes to send | ||||||
|  |                 canMsg.frame.rtr = 1;                               // no remote frame | ||||||
|  |                 canMsg.frame.data0 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data1 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data2 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|  |                 canMsg.frame.data3 = (uint8_t) data; | ||||||
|  |                 data = data >> 8; | ||||||
|                 canMsg.frame.id = (uint32_t) data; |                 canMsg.frame.id = (uint32_t) data; | ||||||
|                 CAN_transmit(&canMsg); |                 CAN_transmit(&canMsg); | ||||||
|             } |             } | ||||||
| @@ -146,14 +229,18 @@ void CAN_newMsg() { | |||||||
|     CAN_receive(&canMsg); |     CAN_receive(&canMsg); | ||||||
|     data = canMsg.frame.id; |     data = canMsg.frame.id; | ||||||
|     data = data<<12; |     data = data<<12; | ||||||
|     data = data | canMsg.frame.data0; |     data = data | canMsg.frame.data3; | ||||||
|     data = data<<8; |  | ||||||
|     data = data | canMsg.frame.data1; |  | ||||||
|     data = data<<8; |     data = data<<8; | ||||||
|     data = data | canMsg.frame.data2; |     data = data | canMsg.frame.data2; | ||||||
|     data = data<<8; |     data = data<<8; | ||||||
|     data = data | canMsg.frame.data3; |     data = data | canMsg.frame.data1; | ||||||
|     POST(&CAN_myself, &CAN_processEvent, evCAnewMsg, 0, data); |     data = data<<8; | ||||||
|  |     data = data | canMsg.frame.data0; | ||||||
|  |     if(canMsg.frame.rtr) { | ||||||
|  |         POST(&CAN_myself, &CAN_processEvent, evCAnewRTR, 0, data); | ||||||
|  |     } else { | ||||||
|  |         POST(&CAN_myself, &CAN_processEvent, evCAnewMsg, 0, data); | ||||||
|  |     } | ||||||
| } | } | ||||||
|  |  | ||||||
| void CAN_Send(uint8_t idRecipient, uint8_t idMsg, uint32_t data) { | void CAN_Send(uint8_t idRecipient, uint8_t idMsg, uint32_t data) { | ||||||
| @@ -161,7 +248,50 @@ void CAN_Send(uint8_t idRecipient, uint8_t idMsg, uint32_t data) { | |||||||
|     tmpData = (tmpData<<4) | idRecipient; |     tmpData = (tmpData<<4) | idRecipient; | ||||||
|     tmpData = (tmpData<<4) | idMsg; |     tmpData = (tmpData<<4) | idMsg; | ||||||
|     tmpData = (tmpData<<32) | data; |     tmpData = (tmpData<<32) | data; | ||||||
|     POST(&CAN_myself, &CAN_processEvent, evCAsend, 0, tmpData); |     POST(&CAN_myself, &CAN_processEvent, evCAsend4, 0, tmpData); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void CAN_send_4_bytes(uint8_t idRecipient, uint8_t idMsg, uint8_t byte0, uint8_t byte1, uint8_t byte2, uint8_t byte3) { | ||||||
|  |     uint64_t tmpData = CAN_myself.sender; | ||||||
|  |     tmpData = (tmpData<<4) | idRecipient; | ||||||
|  |     tmpData = (tmpData<<4) | idMsg; | ||||||
|  |     tmpData = (tmpData<<8) | byte3; | ||||||
|  |     tmpData = (tmpData<<8) | byte2; | ||||||
|  |     tmpData = (tmpData<<8) | byte1; | ||||||
|  |     tmpData = (tmpData<<8) | byte0; | ||||||
|  |     POST(&CAN_myself, &CAN_processEvent, evCAsend4, 0, tmpData); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void CAN_send_2_bytes(uint8_t idRecipient, uint8_t idMsg, uint16_t data) { | ||||||
|  |     uint64_t tmpData = CAN_myself.sender; | ||||||
|  |     tmpData = (tmpData<<4) | idRecipient; | ||||||
|  |     tmpData = (tmpData<<4) | idMsg; | ||||||
|  |     tmpData = (tmpData<<32) | data; | ||||||
|  |     POST(&CAN_myself, &CAN_processEvent, evCAsend2, 0, tmpData); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void CAN_send_1_byte(uint8_t idRecipient, uint8_t idMsg, uint8_t data) { | ||||||
|  |     uint64_t tmpData = CAN_myself.sender; | ||||||
|  |     tmpData = (tmpData<<4) | idRecipient; | ||||||
|  |     tmpData = (tmpData<<4) | idMsg; | ||||||
|  |     tmpData = (tmpData<<32) | data; | ||||||
|  |     POST(&CAN_myself, &CAN_processEvent, evCAsend1, 0, tmpData); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void CAN_send_0_byte(uint8_t idRecipient, uint8_t idMsg) { | ||||||
|  |     uint64_t tmpData = CAN_myself.sender; | ||||||
|  |     tmpData = (tmpData<<4) | idRecipient; | ||||||
|  |     tmpData = (tmpData<<4) | idMsg; | ||||||
|  |     tmpData = tmpData<<32; | ||||||
|  |     POST(&CAN_myself, &CAN_processEvent, evCAsend0, 0, tmpData); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void CAN_send_rtr(uint8_t idRecipient, uint8_t idMsg) { | ||||||
|  |     uint64_t tmpData = CAN_myself.sender; | ||||||
|  |     tmpData = (tmpData<<4) | idRecipient; | ||||||
|  |     tmpData = (tmpData<<4) | idMsg; | ||||||
|  |     tmpData = tmpData<<32; | ||||||
|  |     POST(&CAN_myself, &CAN_processEvent, evCAsendRTR, 0, tmpData); | ||||||
| } | } | ||||||
|  |  | ||||||
| /*********** | /*********** | ||||||
|   | |||||||
| @@ -10,17 +10,22 @@ | |||||||
| #include "../xf/xf.h" | #include "../xf/xf.h" | ||||||
|  |  | ||||||
| typedef enum { | typedef enum { | ||||||
|     STCA_INIT, |     STCA_INIT = 10, | ||||||
|     STCA_PROCESS |     STCA_PROCESS | ||||||
| } CAN_STATES; | } CAN_STATES; | ||||||
|  |  | ||||||
| typedef enum { | typedef enum { | ||||||
|     evCAinit = 10, |     evCAinit = 10, | ||||||
|     evCAnewMsg, |     evCAnewMsg, | ||||||
|     evCAsend |     evCAnewRTR, | ||||||
|  |     evCAsend4, | ||||||
|  |     evCAsend2, | ||||||
|  |     evCAsend1, | ||||||
|  |     evCAsend0, | ||||||
|  |     evCAsendRTR | ||||||
| } CAN_EVENTS; | } CAN_EVENTS; | ||||||
|  |  | ||||||
| typedef void (*CAN_CALLBACK)(uint8_t, uint8_t, uint32_t); | typedef void (*CAN_CALLBACK)(uint8_t, uint8_t, bool, uint32_t); | ||||||
|  |  | ||||||
| typedef struct { | typedef struct { | ||||||
|     CAN_STATES state; |     CAN_STATES state; | ||||||
| @@ -78,6 +83,12 @@ void CAN_newMsg(); | |||||||
|  */ |  */ | ||||||
| void CAN_Send(uint8_t idRecipient, uint8_t idMsg, uint32_t data); | void CAN_Send(uint8_t idRecipient, uint8_t idMsg, uint32_t data); | ||||||
|  |  | ||||||
|  | void CAN_send_4_bytes(uint8_t idRecipient, uint8_t idMsg, uint8_t byte0, uint8_t byte1, uint8_t byte2, uint8_t byte3); | ||||||
|  | void CAN_send_2_bytes(uint8_t idRecipient, uint8_t idMsg, uint16_t data); | ||||||
|  | void CAN_send_1_byte(uint8_t idRecipient, uint8_t idMsg, uint8_t data); | ||||||
|  | void CAN_send_0_byte(uint8_t idRecipient, uint8_t idMsg); | ||||||
|  | void CAN_send_rtr(uint8_t idRecipient, uint8_t idMsg); | ||||||
|  |  | ||||||
| /*********** | /*********** | ||||||
|  * SETTERS * |  * SETTERS * | ||||||
|  ***********/ |  ***********/ | ||||||
|   | |||||||
							
								
								
									
										460
									
								
								306-controller_interface.X/nbproject/Makefile-default.mk
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										460
									
								
								306-controller_interface.X/nbproject/Makefile-default.mk
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,460 @@ | |||||||
|  | # | ||||||
|  | # 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 app/steering.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}/app/steering.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}/app/steering.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}/app/steering.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 app/steering.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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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}/app/steering.p1: app/steering.c  nbproject/Makefile-${CND_CONF}.mk  | ||||||
|  | 	@${MKDIR} "${OBJECTDIR}/app"  | ||||||
|  | 	@${RM} ${OBJECTDIR}/app/steering.p1.d  | ||||||
|  | 	@${RM} ${OBJECTDIR}/app/steering.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=reentrant:auto:auto:auto     -o ${OBJECTDIR}/app/steering.p1 app/steering.c  | ||||||
|  | 	@-${MV} ${OBJECTDIR}/app/steering.d ${OBJECTDIR}/app/steering.p1.d  | ||||||
|  | 	@${FIXDEPS} ${OBJECTDIR}/app/steering.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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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}/app/steering.p1: app/steering.c  nbproject/Makefile-${CND_CONF}.mk  | ||||||
|  | 	@${MKDIR} "${OBJECTDIR}/app"  | ||||||
|  | 	@${RM} ${OBJECTDIR}/app/steering.p1.d  | ||||||
|  | 	@${RM} ${OBJECTDIR}/app/steering.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=reentrant:auto:auto:auto     -o ${OBJECTDIR}/app/steering.p1 app/steering.c  | ||||||
|  | 	@-${MV} ${OBJECTDIR}/app/steering.d ${OBJECTDIR}/app/steering.p1.d  | ||||||
|  | 	@${FIXDEPS} ${OBJECTDIR}/app/steering.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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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=reentrant: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 | ||||||
							
								
								
									
										69
									
								
								306-controller_interface.X/nbproject/Makefile-impl.mk
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										69
									
								
								306-controller_interface.X/nbproject/Makefile-impl.mk
									
									
									
									
									
										Normal file
									
								
							| @@ -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 | ||||||
| @@ -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:/Program Files/Microchip/MPLABX/v6.15/packs/Microchip/PIC18F-K_DFP/1.11.281 | ||||||
							
								
								
									
										10
									
								
								306-controller_interface.X/nbproject/Makefile-variables.mk
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										10
									
								
								306-controller_interface.X/nbproject/Makefile-variables.mk
									
									
									
									
									
										Normal file
									
								
							| @@ -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 | ||||||
| @@ -7,6 +7,11 @@ | |||||||
|       <logicalFolder name="app" displayName="app" projectFiles="true"> |       <logicalFolder name="app" displayName="app" projectFiles="true"> | ||||||
|         <itemPath>app/factory/factory.h</itemPath> |         <itemPath>app/factory/factory.h</itemPath> | ||||||
|         <itemPath>app/car.h</itemPath> |         <itemPath>app/car.h</itemPath> | ||||||
|  |         <itemPath>app/can_message.h</itemPath> | ||||||
|  |         <itemPath>app/kartculator.h</itemPath> | ||||||
|  |         <itemPath>app/eeprom.h</itemPath> | ||||||
|  |         <itemPath>app/drive.h</itemPath> | ||||||
|  |         <itemPath>app/steering.h</itemPath> | ||||||
|       </logicalFolder> |       </logicalFolder> | ||||||
|       <logicalFolder name="board" displayName="board" projectFiles="true"> |       <logicalFolder name="board" displayName="board" projectFiles="true"> | ||||||
|         <itemPath>board/led/led.h</itemPath> |         <itemPath>board/led/led.h</itemPath> | ||||||
| @@ -24,7 +29,8 @@ | |||||||
|       </logicalFolder> |       </logicalFolder> | ||||||
|       <logicalFolder name="middleware" displayName="middleware" projectFiles="true"> |       <logicalFolder name="middleware" displayName="middleware" projectFiles="true"> | ||||||
|         <itemPath>middleware/can_interface.h</itemPath> |         <itemPath>middleware/can_interface.h</itemPath> | ||||||
|         <itemPath>middleware/alive_checker.h</itemPath> |         <itemPath>middleware/alive.h</itemPath> | ||||||
|  |         <itemPath>middleware/blinker.h</itemPath> | ||||||
|       </logicalFolder> |       </logicalFolder> | ||||||
|       <logicalFolder name="xf" displayName="xf" projectFiles="true"> |       <logicalFolder name="xf" displayName="xf" projectFiles="true"> | ||||||
|         <itemPath>xf/event.h</itemPath> |         <itemPath>xf/event.h</itemPath> | ||||||
| @@ -41,6 +47,11 @@ | |||||||
|                    projectFiles="true"> |                    projectFiles="true"> | ||||||
|       <logicalFolder name="app" displayName="app" projectFiles="true"> |       <logicalFolder name="app" displayName="app" projectFiles="true"> | ||||||
|         <itemPath>app/factory/factory.c</itemPath> |         <itemPath>app/factory/factory.c</itemPath> | ||||||
|  |         <itemPath>app/can_message.c</itemPath> | ||||||
|  |         <itemPath>app/kartculator.c</itemPath> | ||||||
|  |         <itemPath>app/eeprom.c</itemPath> | ||||||
|  |         <itemPath>app/drive.c</itemPath> | ||||||
|  |         <itemPath>app/steering.c</itemPath> | ||||||
|       </logicalFolder> |       </logicalFolder> | ||||||
|       <logicalFolder name="board" displayName="board" projectFiles="true"> |       <logicalFolder name="board" displayName="board" projectFiles="true"> | ||||||
|         <itemPath>board/led/led.c</itemPath> |         <itemPath>board/led/led.c</itemPath> | ||||||
| @@ -58,7 +69,8 @@ | |||||||
|       </logicalFolder> |       </logicalFolder> | ||||||
|       <logicalFolder name="middleware" displayName="middleware" projectFiles="true"> |       <logicalFolder name="middleware" displayName="middleware" projectFiles="true"> | ||||||
|         <itemPath>middleware/can_interface.c</itemPath> |         <itemPath>middleware/can_interface.c</itemPath> | ||||||
|         <itemPath>middleware/alive_checker.c</itemPath> |         <itemPath>middleware/alive.c</itemPath> | ||||||
|  |         <itemPath>middleware/blinker.c</itemPath> | ||||||
|       </logicalFolder> |       </logicalFolder> | ||||||
|       <logicalFolder name="xf" displayName="xf" projectFiles="true"> |       <logicalFolder name="xf" displayName="xf" projectFiles="true"> | ||||||
|         <itemPath>xf/event.c</itemPath> |         <itemPath>xf/event.c</itemPath> | ||||||
| @@ -82,7 +94,7 @@ | |||||||
|     <conf name="default" type="2"> |     <conf name="default" type="2"> | ||||||
|       <toolsSet> |       <toolsSet> | ||||||
|         <developmentServer>localhost</developmentServer> |         <developmentServer>localhost</developmentServer> | ||||||
|         <targetDevice>PIC18F25K83</targetDevice> |         <targetDevice>PIC18F26K83</targetDevice> | ||||||
|         <targetHeader></targetHeader> |         <targetHeader></targetHeader> | ||||||
|         <targetPluginBoard></targetPluginBoard> |         <targetPluginBoard></targetPluginBoard> | ||||||
|         <platformTool>PICkit3PlatformTool</platformTool> |         <platformTool>PICkit3PlatformTool</platformTool> | ||||||
| @@ -91,7 +103,7 @@ | |||||||
|         <platform>3</platform> |         <platform>3</platform> | ||||||
|       </toolsSet> |       </toolsSet> | ||||||
|       <packs> |       <packs> | ||||||
|         <pack name="PIC18F-K_DFP" vendor="Microchip" version="1.5.114"/> |         <pack name="PIC18F-K_DFP" vendor="Microchip" version="1.11.281"/> | ||||||
|       </packs> |       </packs> | ||||||
|       <ScriptingSettings> |       <ScriptingSettings> | ||||||
|       </ScriptingSettings> |       </ScriptingSettings> | ||||||
| @@ -210,8 +222,10 @@ | |||||||
|         <property key="debugoptions.debug-startup" value="Use system settings"/> |         <property key="debugoptions.debug-startup" value="Use system settings"/> | ||||||
|         <property key="debugoptions.reset-behaviour" value="Use system settings"/> |         <property key="debugoptions.reset-behaviour" value="Use system settings"/> | ||||||
|         <property key="debugoptions.useswbreakpoints" value="false"/> |         <property key="debugoptions.useswbreakpoints" value="false"/> | ||||||
|         <property key="firmware.download.all" value="false"/> |         <property key="event.recorder.enabled" value="false"/> | ||||||
|  |         <property key="event.recorder.scvd.files" value=""/> | ||||||
|         <property key="hwtoolclock.frcindebug" value="false"/> |         <property key="hwtoolclock.frcindebug" value="false"/> | ||||||
|  |         <property key="lastid" value=""/> | ||||||
|         <property key="memories.aux" value="false"/> |         <property key="memories.aux" value="false"/> | ||||||
|         <property key="memories.bootflash" value="true"/> |         <property key="memories.bootflash" value="true"/> | ||||||
|         <property key="memories.configurationmemory" value="true"/> |         <property key="memories.configurationmemory" value="true"/> | ||||||
| @@ -241,7 +255,7 @@ | |||||||
|         <property key="programoptions.programcalmem" value="false"/> |         <property key="programoptions.programcalmem" value="false"/> | ||||||
|         <property key="programoptions.programuserotp" value="false"/> |         <property key="programoptions.programuserotp" value="false"/> | ||||||
|         <property key="programoptions.testmodeentrymethod" value="VDDFirst"/> |         <property key="programoptions.testmodeentrymethod" value="VDDFirst"/> | ||||||
|         <property key="programoptions.usehighvoltageonmclr" value="true"/> |         <property key="programoptions.usehighvoltageonmclr" value="false"/> | ||||||
|         <property key="programoptions.uselvpprogramming" value="false"/> |         <property key="programoptions.uselvpprogramming" value="false"/> | ||||||
|         <property key="voltagevalue" value="5.0"/> |         <property key="voltagevalue" value="5.0"/> | ||||||
|       </PICkit3PlatformTool> |       </PICkit3PlatformTool> | ||||||
| @@ -255,8 +269,11 @@ | |||||||
|         <property key="debugoptions.debug-startup" value="Use system settings"/> |         <property key="debugoptions.debug-startup" value="Use system settings"/> | ||||||
|         <property key="debugoptions.reset-behaviour" value="Use system settings"/> |         <property key="debugoptions.reset-behaviour" value="Use system settings"/> | ||||||
|         <property key="debugoptions.useswbreakpoints" value="false"/> |         <property key="debugoptions.useswbreakpoints" value="false"/> | ||||||
|  |         <property key="event.recorder.enabled" value="false"/> | ||||||
|  |         <property key="event.recorder.scvd.files" value=""/> | ||||||
|         <property key="firmware.download.all" value="false"/> |         <property key="firmware.download.all" value="false"/> | ||||||
|         <property key="hwtoolclock.frcindebug" value="false"/> |         <property key="hwtoolclock.frcindebug" value="false"/> | ||||||
|  |         <property key="lastid" value=""/> | ||||||
|         <property key="memories.aux" value="false"/> |         <property key="memories.aux" value="false"/> | ||||||
|         <property key="memories.bootflash" value="true"/> |         <property key="memories.bootflash" value="true"/> | ||||||
|         <property key="memories.configurationmemory" value="true"/> |         <property key="memories.configurationmemory" value="true"/> | ||||||
| @@ -286,7 +303,7 @@ | |||||||
|         <property key="programoptions.programcalmem" value="false"/> |         <property key="programoptions.programcalmem" value="false"/> | ||||||
|         <property key="programoptions.programuserotp" value="false"/> |         <property key="programoptions.programuserotp" value="false"/> | ||||||
|         <property key="programoptions.testmodeentrymethod" value="VDDFirst"/> |         <property key="programoptions.testmodeentrymethod" value="VDDFirst"/> | ||||||
|         <property key="programoptions.usehighvoltageonmclr" value="true"/> |         <property key="programoptions.usehighvoltageonmclr" value="false"/> | ||||||
|         <property key="programoptions.uselvpprogramming" value="false"/> |         <property key="programoptions.uselvpprogramming" value="false"/> | ||||||
|         <property key="voltagevalue" value="5.0"/> |         <property key="voltagevalue" value="5.0"/> | ||||||
|       </Tool> |       </Tool> | ||||||
| @@ -296,16 +313,19 @@ | |||||||
|       </XC8-CO> |       </XC8-CO> | ||||||
|       <XC8-config-global> |       <XC8-config-global> | ||||||
|         <property key="advanced-elf" value="true"/> |         <property key="advanced-elf" value="true"/> | ||||||
|  |         <property key="constdata-progmem" value="true"/> | ||||||
|         <property key="gcc-opt-driver-new" value="true"/> |         <property key="gcc-opt-driver-new" value="true"/> | ||||||
|         <property key="gcc-opt-std" value="-std=c99"/> |         <property key="gcc-opt-std" value="-std=c99"/> | ||||||
|         <property key="gcc-output-file-format" value="dwarf-3"/> |         <property key="gcc-output-file-format" value="dwarf-3"/> | ||||||
|  |         <property key="mapped-progmem" value="false"/> | ||||||
|         <property key="omit-pack-options" value="false"/> |         <property key="omit-pack-options" value="false"/> | ||||||
|         <property key="omit-pack-options-new" value="1"/> |         <property key="omit-pack-options-new" value="1"/> | ||||||
|         <property key="output-file-format" value="-mcof,+elf"/> |         <property key="output-file-format" value="-mcof,+elf"/> | ||||||
|  |         <property key="smart-io-format" value=""/> | ||||||
|         <property key="stack-size-high" value="auto"/> |         <property key="stack-size-high" value="auto"/> | ||||||
|         <property key="stack-size-low" value="auto"/> |         <property key="stack-size-low" value="auto"/> | ||||||
|         <property key="stack-size-main" value="auto"/> |         <property key="stack-size-main" value="auto"/> | ||||||
|         <property key="stack-type" value="compiled"/> |         <property key="stack-type" value="reentrant"/> | ||||||
|         <property key="user-pack-device-support" value=""/> |         <property key="user-pack-device-support" value=""/> | ||||||
|         <property key="wpo-lto" value="false"/> |         <property key="wpo-lto" value="false"/> | ||||||
|       </XC8-config-global> |       </XC8-config-global> | ||||||
|   | |||||||
							
								
								
									
										0
									
								
								306-controller_interface.X/queuelogs/debugtool
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										0
									
								
								306-controller_interface.X/queuelogs/debugtool
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because one or more lines are too long
											
										
									
								
							
							
								
								
									
										17224
									
								
								306-controller_interface.X/ss22ep.mc3.bak0
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										17224
									
								
								306-controller_interface.X/ss22ep.mc3.bak0
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because one or more lines are too long
											
										
									
								
							| @@ -27,8 +27,8 @@ typedef struct Timer_        // timer structure | |||||||
| /*----------------------------------------------------------------------------*/ | /*----------------------------------------------------------------------------*/ | ||||||
| /* depending on usage, change MAXTIMER and MAXEVENT                           */ | /* depending on usage, change MAXTIMER and MAXEVENT                           */ | ||||||
| /*----------------------------------------------------------------------------*/ | /*----------------------------------------------------------------------------*/ | ||||||
| #define MAXTIMER 8          // number of timers in our system | #define MAXTIMER 25          // number of timers in our system | ||||||
| #define MAXEVENT 12         // number of events in our system  | #define MAXEVENT 20         // number of events in our system  | ||||||
|  |  | ||||||
| #define NULLTIMER 0         // no value for time | #define NULLTIMER 0         // no value for time | ||||||
| #define TICKINTERVAL 10     // this is the ticktimers duration | #define TICKINTERVAL 10     // this is the ticktimers duration | ||||||
|   | |||||||
							
								
								
									
										
											BIN
										
									
								
								UML/alive.pdf
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										
											BIN
										
									
								
								UML/alive.pdf
									
									
									
									
									
										Normal file
									
								
							
										
											Binary file not shown.
										
									
								
							
							
								
								
									
										285
									
								
								UML/alive.uxf
									
									
									
									
									
								
							
							
						
						
									
										285
									
								
								UML/alive.uxf
									
									
									
									
									
								
							| @@ -4,10 +4,10 @@ | |||||||
|   <element> |   <element> | ||||||
|     <id>UMLSpecialState</id> |     <id>UMLSpecialState</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>266</x> |       <x>714</x> | ||||||
|       <y>98</y> |       <y>28</y> | ||||||
|       <w>28</w> |       <w>56</w> | ||||||
|       <h>28</h> |       <h>56</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>type=initial</panel_attributes> |     <panel_attributes>type=initial</panel_attributes> | ||||||
|     <additional_attributes/> |     <additional_attributes/> | ||||||
| @@ -15,164 +15,257 @@ | |||||||
|   <element> |   <element> | ||||||
|     <id>Relation</id> |     <id>Relation</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>266</x> |       <x>462</x> | ||||||
|       <y>112</y> |       <y>70</y> | ||||||
|       <w>112</w> |       <w>308</w> | ||||||
|       <h>98</h> |       <h>154</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>lt=-> |     <panel_attributes>lt=-> | ||||||
| evACinit</panel_attributes> | evInitChecker</panel_attributes> | ||||||
|     <additional_attributes>10.0;10.0;10.0;50.0</additional_attributes> |     <additional_attributes>200.0;10.0;200.0;50.0;10.0;50.0;10.0;90.0</additional_attributes> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>UMLState</id> |     <id>UMLState</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>210</x> |       <x>350</x> | ||||||
|       <y>182</y> |       <y>196</y> | ||||||
|       <w>140</w> |       <w>266</w> | ||||||
|       <h>56</h> |       <h>112</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>STAC_SETUP</panel_attributes> |     <panel_attributes>SETUP | ||||||
|     <additional_attributes/> | -- | ||||||
|   </element> | /entry: sendParamsOnCan | ||||||
|   <element> | /entry: checker = true</panel_attributes> | ||||||
|     <id>UMLNote</id> |  | ||||||
|     <coordinates> |  | ||||||
|       <x>434</x> |  | ||||||
|       <y>182</y> |  | ||||||
|       <w>140</w> |  | ||||||
|       <h>42</h> |  | ||||||
|     </coordinates> |  | ||||||
|     <panel_attributes>Send params</panel_attributes> |  | ||||||
|     <additional_attributes/> |     <additional_attributes/> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>Relation</id> |     <id>Relation</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>266</x> |       <x>462</x> | ||||||
|       <y>224</y> |       <y>294</y> | ||||||
|       <w>126</w> |       <w>98</w> | ||||||
|       <h>98</h> |       <h>98</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>lt=-> |     <panel_attributes>lt=-> | ||||||
| evACborn</panel_attributes> | m1=evBorn</panel_attributes> | ||||||
|     <additional_attributes>10.0;10.0;10.0;50.0</additional_attributes> |     <additional_attributes>10.0;10.0;10.0;50.0</additional_attributes> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>UMLState</id> |     <id>UMLState</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>210</x> |       <x>350</x> | ||||||
|       <y>294</y> |       <y>364</y> | ||||||
|       <w>140</w> |       <w>266</w> | ||||||
|       <h>56</h> |  | ||||||
|     </coordinates> |  | ||||||
|     <panel_attributes>STAC_BORN</panel_attributes> |  | ||||||
|     <additional_attributes/> |  | ||||||
|   </element> |  | ||||||
|   <element> |  | ||||||
|     <id>UMLState</id> |  | ||||||
|     <coordinates> |  | ||||||
|       <x>168</x> |  | ||||||
|       <y>406</y> |  | ||||||
|       <w>224</w> |  | ||||||
|       <h>84</h> |       <h>84</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>STAC_WAIT |     <panel_attributes>BORN | ||||||
| -- | -- | ||||||
| /entry: isAlive = false</panel_attributes> | /entry: init</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>350</x> | ||||||
|  |       <y>504</y> | ||||||
|  |       <w>266</w> | ||||||
|  |       <h>112</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>WAIT | ||||||
|  | -- | ||||||
|  | /entry: start children class | ||||||
|  | -- | ||||||
|  | isAlive = false</panel_attributes> | ||||||
|     <additional_attributes/> |     <additional_attributes/> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>Relation</id> |     <id>Relation</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>266</x> |       <x>462</x> | ||||||
|       <y>336</y> |       <y>434</y> | ||||||
|       <w>140</w> |       <w>112</w> | ||||||
|       <h>98</h> |       <h>98</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>lt=-> |     <panel_attributes>lt=-> | ||||||
| evACready</panel_attributes> | m1=evReady</panel_attributes> | ||||||
|     <additional_attributes>10.0;10.0;10.0;50.0</additional_attributes> |     <additional_attributes>10.0;10.0;10.0;50.0</additional_attributes> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>UMLState</id> |     <id>UMLState</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>210</x> |       <x>350</x> | ||||||
|       <y>658</y> |       <y>784</y> | ||||||
|       <w>140</w> |       <w>266</w> | ||||||
|       <h>56</h> |       <h>84</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>STAC_DEAD</panel_attributes> |     <panel_attributes>DEAD | ||||||
|  | -- | ||||||
|  | </panel_attributes> | ||||||
|     <additional_attributes/> |     <additional_attributes/> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>Relation</id> |     <id>Relation</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>266</x> |       <x>280</x> | ||||||
|       <y>476</y> |  | ||||||
|       <w>112</w> |  | ||||||
|       <h>98</h> |  | ||||||
|     </coordinates> |  | ||||||
|     <panel_attributes>lt=-> |  | ||||||
| evACpoll</panel_attributes> |  | ||||||
|     <additional_attributes>10.0;10.0;10.0;50.0</additional_attributes> |  | ||||||
|   </element> |  | ||||||
|   <element> |  | ||||||
|     <id>UMLSpecialState</id> |  | ||||||
|     <coordinates> |  | ||||||
|       <x>252</x> |  | ||||||
|       <y>546</y> |       <y>546</y> | ||||||
|       <w>56</w> |       <w>210</w> | ||||||
|       <h>56</h> |       <h>182</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>type=decision</panel_attributes> |     <panel_attributes>lt=-> | ||||||
|     <additional_attributes/> | m1=evPoll\n[isAlive]</panel_attributes> | ||||||
|  |     <additional_attributes>80.0;50.0;80.0;110.0;10.0;110.0;10.0;10.0;50.0;10.0</additional_attributes> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>Relation</id> |     <id>Relation</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>266</x> |       <x>224</x> | ||||||
|       <y>588</y> |       <y>252</y> | ||||||
|       <w>84</w> |       <w>378</w> | ||||||
|       <h>98</h> |       <h>700</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>lt=-> |     <panel_attributes>lt=-> | ||||||
| m1=[else]</panel_attributes> | m1=evResurrect</panel_attributes> | ||||||
|     <additional_attributes>10.0;10.0;10.0;50.0</additional_attributes> |     <additional_attributes>180.0;440.0;180.0;480.0;10.0;480.0;10.0;10.0;90.0;10.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>462</x> | ||||||
|  |       <y>602</y> | ||||||
|  |       <w>112</w> | ||||||
|  |       <h>210</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1=evPoll\n[default]</panel_attributes> | ||||||
|  |     <additional_attributes>10.0;10.0;10.0;130.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>728</x> | ||||||
|  |       <y>70</y> | ||||||
|  |       <w>308</w> | ||||||
|  |       <h>154</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | evInitSender</panel_attributes> | ||||||
|  |     <additional_attributes>10.0;10.0;10.0;50.0;200.0;50.0;200.0;90.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>784</x> | ||||||
|  |       <y>252</y> | ||||||
|  |       <w>224</w> | ||||||
|  |       <h>140</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1=evPoll\n[else]</panel_attributes> | ||||||
|  |     <additional_attributes>100.0;40.0;100.0;70.0;10.0;70.0;10.0;10.0;60.0;10.0</additional_attributes> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>UMLNote</id> |     <id>UMLNote</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>434</x> |       <x>784</x> | ||||||
|       <y>294</y> |       <y>28</y> | ||||||
|       <w>140</w> |       <w>140</w> | ||||||
|       <h>42</h> |       <h>56</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>Reset / Init</panel_attributes> |     <panel_attributes>read time on | ||||||
|  | EPROM</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>868</x> | ||||||
|  |       <y>196</y> | ||||||
|  |       <w>266</w> | ||||||
|  |       <h>112</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>ALIVE | ||||||
|  | -- | ||||||
|  | \entry: sender = true | ||||||
|  | -- | ||||||
|  | sendAliveOnCan</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>868</x> | ||||||
|  |       <y>518</y> | ||||||
|  |       <w>266</w> | ||||||
|  |       <h>84</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=.. | ||||||
|  | BREAK | ||||||
|  | -.. | ||||||
|  | </panel_attributes> | ||||||
|     <additional_attributes/> |     <additional_attributes/> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>Relation</id> |     <id>Relation</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>294</x> |       <x>994</x> | ||||||
|       <y>420</y> |       <y>294</y> | ||||||
|       <w>182</w> |       <w>210</w> | ||||||
|       <h>196</h> |       <h>252</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>lt=-> |     <panel_attributes>lt=..> | ||||||
| m1=[alive]</panel_attributes> | m1=evPoll\n[time==0]\n[haveBreak]</panel_attributes> | ||||||
|     <additional_attributes>10.0;110.0;110.0;110.0;110.0;10.0;70.0;10.0</additional_attributes> |     <additional_attributes>60.0;10.0;60.0;110.0;10.0;110.0;10.0;160.0</additional_attributes> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>Relation</id> |     <id>Relation</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>140</x> |       <x>560</x> | ||||||
|       <y>308</y> |       <y>546</y> | ||||||
|       <w>168</w> |       <w>336</w> | ||||||
|       <h>490</h> |       <h>182</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>lt=-> |     <panel_attributes>lt=..> | ||||||
| evACborn</panel_attributes> | m1=evPoll\n[time==0]\n[haveBreak]</panel_attributes> | ||||||
|     <additional_attributes>100.0;290.0;100.0;330.0;10.0;330.0;10.0;10.0;50.0;10.0</additional_attributes> |     <additional_attributes>10.0;50.0;10.0;110.0;90.0;110.0;170.0;10.0;220.0;10.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>602</x> | ||||||
|  |       <y>546</y> | ||||||
|  |       <w>420</w> | ||||||
|  |       <h>182</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=..> | ||||||
|  | m1=evStart\n[checker]</panel_attributes> | ||||||
|  |     <additional_attributes>220.0;40.0;220.0;110.0;140.0;110.0;60.0;10.0;10.0;10.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>1078</x> | ||||||
|  |       <y>252</y> | ||||||
|  |       <w>182</w> | ||||||
|  |       <h>476</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=..> | ||||||
|  | m1=evStart\n[sender]</panel_attributes> | ||||||
|  |     <additional_attributes>10.0;250.0;10.0;320.0;110.0;320.0;110.0;10.0;40.0;10.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLNote</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>868</x> | ||||||
|  |       <y>728</y> | ||||||
|  |       <w>266</w> | ||||||
|  |       <h>154</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=.. | ||||||
|  | break part can be disable | ||||||
|  | with setHaveBreak(false) | ||||||
|  |  | ||||||
|  | not all childrens have a break | ||||||
|  | for time at 0</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|   </element> |   </element> | ||||||
| </diagram> | </diagram> | ||||||
|   | |||||||
							
								
								
									
										
											BIN
										
									
								
								UML/can.pdf
									
									
									
									
									
								
							
							
						
						
									
										
											BIN
										
									
								
								UML/can.pdf
									
									
									
									
									
								
							
										
											Binary file not shown.
										
									
								
							
							
								
								
									
										29
									
								
								UML/can.puml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										29
									
								
								UML/can.puml
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,29 @@ | |||||||
|  | @startuml | ||||||
|  |  | ||||||
|  | actor CAN_BUS as bus | ||||||
|  | participant interrupt as ISR | ||||||
|  | queue XF as xf | ||||||
|  | participant ecan as ecan | ||||||
|  | participant canInterface as can | ||||||
|  | control canMessageController as msg | ||||||
|  |  | ||||||
|  |  | ||||||
|  | bus -\\ ISR ++  : can message | ||||||
|  | ISR -> can : newMsg | ||||||
|  | can -> ecan : read | ||||||
|  | ecan --> can : message | ||||||
|  | can -> xf : POST XF | ||||||
|  | destroy ISR | ||||||
|  |     group TICK XF | ||||||
|  | xf o-> can : receiveCan() | ||||||
|  | can -> msg : processIncoming() | ||||||
|  | msg -> can : create message | ||||||
|  | can -> xf : POST XF | ||||||
|  |     end | ||||||
|  |     group TICK XF | ||||||
|  | xf o-> can : sendCan() | ||||||
|  | can -> ecan : write | ||||||
|  | ecan -\\ bus : can message | ||||||
|  |     end | ||||||
|  |  | ||||||
|  | @enduml | ||||||
							
								
								
									
										47
									
								
								UML/can.uxf
									
									
									
									
									
								
							
							
						
						
									
										47
									
								
								UML/can.uxf
									
									
									
									
									
								
							| @@ -5,9 +5,9 @@ | |||||||
|     <id>UMLNote</id> |     <id>UMLNote</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>645</x> |       <x>645</x> | ||||||
|       <y>255</y> |       <y>75</y> | ||||||
|       <w>675</w> |       <w>750</w> | ||||||
|       <h>525</h> |       <h>765</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>_*How to use CAN interface*_ |     <panel_attributes>_*How to use CAN interface*_ | ||||||
|  |  | ||||||
| @@ -23,19 +23,30 @@ CAN_setSender(idSender); | |||||||
| CAN_startBehaviour(); | CAN_startBehaviour(); | ||||||
|  |  | ||||||
| *Somewhere for process input can message:* | *Somewhere for process input can message:* | ||||||
| void receiveCan(uint8_t idSender, uint8_t idMsg, uint32_t canData) { | void receiveCan(uint8_t idSender, uint8_t idMsg, bool rtr, uint32_t canData) { | ||||||
|     ..... |     ..... | ||||||
| } | } | ||||||
|  |  | ||||||
| *For send can message: * | *For send can message: * | ||||||
| CAN_sendCanMsg(uint8_t idRecipient, uint8_t idMsg, uint32_t data);</panel_attributes> | CAN_Send(uint8_t idRecipient, uint8_t idMsg, uint32_t data); | ||||||
|  | CAN_send_4_bytes( | ||||||
|  |         uint8_t idRecipient, | ||||||
|  |         uint8_t idMsg, | ||||||
|  |         uint8_t byte0, | ||||||
|  |         uint8_t byte1, | ||||||
|  |         uint8_t byte2, | ||||||
|  |         uint8_t byte3); | ||||||
|  | CAN_send_2_bytes(uint8_t idRecipient, uint8_t idMsg, uint16_t data); | ||||||
|  | CAN_send_1_byte(uint8_t idRecipient, uint8_t idMsg, uint8_t data); | ||||||
|  | CAN_send_0_byte(uint8_t idRecipient, uint8_t idMsg); | ||||||
|  | CAN_send_rtr(uint8_t idRecipient, uint8_t idMsg);</panel_attributes> | ||||||
|     <additional_attributes/> |     <additional_attributes/> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>Relation</id> |     <id>Relation</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>360</x> |       <x>375</x> | ||||||
|       <y>330</y> |       <y>255</y> | ||||||
|       <w>90</w> |       <w>90</w> | ||||||
|       <h>135</h> |       <h>135</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
| @@ -47,8 +58,8 @@ evInit | |||||||
|   <element> |   <element> | ||||||
|     <id>UMLSpecialState</id> |     <id>UMLSpecialState</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>360</x> |       <x>375</x> | ||||||
|       <y>315</y> |       <y>240</y> | ||||||
|       <w>30</w> |       <w>30</w> | ||||||
|       <h>30</h> |       <h>30</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
| @@ -58,37 +69,37 @@ evInit | |||||||
|   <element> |   <element> | ||||||
|     <id>UMLState</id> |     <id>UMLState</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>240</x> |       <x>255</x> | ||||||
|       <y>435</y> |       <y>360</y> | ||||||
|       <w>270</w> |       <w>270</w> | ||||||
|       <h>90</h> |       <h>90</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>STCA_PROCESS</panel_attributes> |     <panel_attributes>PROCESS</panel_attributes> | ||||||
|     <additional_attributes/> |     <additional_attributes/> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>Relation</id> |     <id>Relation</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>450</x> |       <x>465</x> | ||||||
|       <y>465</y> |       <y>390</y> | ||||||
|       <w>180</w> |       <w>180</w> | ||||||
|       <h>180</h> |       <h>180</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>lt=-> |     <panel_attributes>lt=-> | ||||||
| m1=evCAsend | m1=evSend | ||||||
| m1=\n/sendCan()</panel_attributes> | m1=\n/sendCan()</panel_attributes> | ||||||
|     <additional_attributes>10.0;40.0;10.0;100.0;100.0;100.0;100.0;10.0;40.0;10.0</additional_attributes> |     <additional_attributes>10.0;40.0;10.0;100.0;100.0;100.0;100.0;10.0;40.0;10.0</additional_attributes> | ||||||
|   </element> |   </element> | ||||||
|   <element> |   <element> | ||||||
|     <id>Relation</id> |     <id>Relation</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>135</x> |       <x>150</x> | ||||||
|       <y>465</y> |       <y>390</y> | ||||||
|       <w>300</w> |       <w>300</w> | ||||||
|       <h>180</h> |       <h>180</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>lt=-> |     <panel_attributes>lt=-> | ||||||
| m1= evCAnewMsg | m1= evNewMsg | ||||||
| m1= \n/receiveCan() | m1= \n/receiveCan() | ||||||
| </panel_attributes> | </panel_attributes> | ||||||
|     <additional_attributes>100.0;40.0;100.0;100.0;10.0;100.0;10.0;10.0;70.0;10.0</additional_attributes> |     <additional_attributes>100.0;40.0;100.0;100.0;10.0;100.0;10.0;10.0;70.0;10.0</additional_attributes> | ||||||
|   | |||||||
							
								
								
									
										
											BIN
										
									
								
								UML/can_sequence.png
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										
											BIN
										
									
								
								UML/can_sequence.png
									
									
									
									
									
										Normal file
									
								
							
										
											Binary file not shown.
										
									
								
							| After Width: | Height: | Size: 32 KiB | 
| @@ -1,13 +1,13 @@ | |||||||
| <?xml version="1.0" encoding="UTF-8" standalone="no"?> | <?xml version="1.0" encoding="UTF-8" standalone="no"?> | ||||||
| <diagram program="umlet" version="15.0.0"> | <diagram program="umlet" version="15.0.0"> | ||||||
|   <zoom_level>7</zoom_level> |   <zoom_level>10</zoom_level> | ||||||
|   <element> |   <element> | ||||||
|     <id>UMLClass</id> |     <id>UMLClass</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>105</x> |       <x>80</x> | ||||||
|       <y>77</y> |       <y>100</y> | ||||||
|       <w>301</w> |       <w>430</w> | ||||||
|       <h>126</h> |       <h>180</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>CAN_INTERFACE |     <panel_attributes>CAN_INTERFACE | ||||||
| -- | -- | ||||||
| @@ -28,10 +28,10 @@ CAN_setSender(idSender: uint8_t): void</panel_attributes> | |||||||
|   <element> |   <element> | ||||||
|     <id>UMLClass</id> |     <id>UMLClass</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>315</x> |       <x>0</x> | ||||||
|       <y>350</y> |       <y>390</y> | ||||||
|       <w>301</w> |       <w>430</w> | ||||||
|       <h>126</h> |       <h>180</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>JOYSTICK |     <panel_attributes>JOYSTICK | ||||||
| -- | -- | ||||||
| @@ -51,10 +51,33 @@ CAN_setSender(idSender: uint8_t): void</panel_attributes> | |||||||
|   <element> |   <element> | ||||||
|     <id>UMLClass</id> |     <id>UMLClass</id> | ||||||
|     <coordinates> |     <coordinates> | ||||||
|       <x>812</x> |       <x>580</x> | ||||||
|       <y>154</y> |       <y>370</y> | ||||||
|       <w>322</w> |       <w>490</w> | ||||||
|       <h>504</h> |       <h>210</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>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</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLClass</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>1140</x> | ||||||
|  |       <y>40</y> | ||||||
|  |       <w>460</w> | ||||||
|  |       <h>720</h> | ||||||
|     </coordinates> |     </coordinates> | ||||||
|     <panel_attributes>MEMORY_CST |     <panel_attributes>MEMORY_CST | ||||||
| -- | -- | ||||||
|   | |||||||
							
								
								
									
										
											BIN
										
									
								
								UML/drive.pdf
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										
											BIN
										
									
								
								UML/drive.pdf
									
									
									
									
									
										Normal file
									
								
							
										
											Binary file not shown.
										
									
								
							
							
								
								
									
										137
									
								
								UML/drive.uxf
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										137
									
								
								UML/drive.uxf
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,137 @@ | |||||||
|  | <?xml version="1.0" encoding="UTF-8" standalone="no"?> | ||||||
|  | <diagram program="umlet" version="15.0.0"> | ||||||
|  |   <zoom_level>15</zoom_level> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>660</x> | ||||||
|  |       <y>90</y> | ||||||
|  |       <w>210</w> | ||||||
|  |       <h>120</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | evInit | ||||||
|  | /startAliveChecker | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>10.0;10.0;10.0;60.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLSpecialState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>660</x> | ||||||
|  |       <y>75</y> | ||||||
|  |       <w>30</w> | ||||||
|  |       <h>30</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>type=initial</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>540</x> | ||||||
|  |       <y>405</y> | ||||||
|  |       <w>270</w> | ||||||
|  |       <h>105</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>RUN | ||||||
|  | -- | ||||||
|  | /entry: LED ON | ||||||
|  | -- | ||||||
|  | emitPollTorqueEv</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>735</x> | ||||||
|  |       <y>450</y> | ||||||
|  |       <w>195</w> | ||||||
|  |       <h>270</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1= evPollTorque\n/sendTorque | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>10.0;100.0;10.0;160.0;110.0;160.0;110.0;10.0;50.0;10.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>495</x> | ||||||
|  |       <y>180</y> | ||||||
|  |       <w>360</w> | ||||||
|  |       <h>135</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>WAIT | ||||||
|  | -- | ||||||
|  | ALIVE_emitBorn(ALdrive(), 0, 0); | ||||||
|  | ALIVE_emitReady(ALdrive(), 100, 0); | ||||||
|  | setAliveTime</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>660</x> | ||||||
|  |       <y>300</y> | ||||||
|  |       <w>120</w> | ||||||
|  |       <h>135</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1=evStart\n(onWait) | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>10.0;10.0;10.0;70.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>735</x> | ||||||
|  |       <y>450</y> | ||||||
|  |       <w>195</w> | ||||||
|  |       <h>180</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1= evPollSpeed\n/sendSpeed | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>10.0;40.0;10.0;100.0;110.0;100.0;110.0;10.0;50.0;10.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>390</x> | ||||||
|  |       <y>240</y> | ||||||
|  |       <w>345</w> | ||||||
|  |       <h>555</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1= evResurrect\n(onBorn) | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>130.0;300.0;130.0;350.0;10.0;350.0;10.0;10.0;70.0;10.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>450</x> | ||||||
|  |       <y>600</y> | ||||||
|  |       <w>270</w> | ||||||
|  |       <h>90</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>DEAD | ||||||
|  | -- | ||||||
|  | /entry: LED OFF</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>570</x> | ||||||
|  |       <y>495</y> | ||||||
|  |       <w>135</w> | ||||||
|  |       <h>135</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1=evStop\n(onDead) | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>10.0;10.0;10.0;70.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  | </diagram> | ||||||
							
								
								
									
										124
									
								
								UML/steering.uxf
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										124
									
								
								UML/steering.uxf
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,124 @@ | |||||||
|  | <?xml version="1.0" encoding="UTF-8" standalone="no"?> | ||||||
|  | <diagram program="umlet" version="15.0.0"> | ||||||
|  |   <zoom_level>15</zoom_level> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>660</x> | ||||||
|  |       <y>90</y> | ||||||
|  |       <w>210</w> | ||||||
|  |       <h>120</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | evInit | ||||||
|  | /startAliveChecker | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>10.0;10.0;10.0;60.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLSpecialState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>660</x> | ||||||
|  |       <y>75</y> | ||||||
|  |       <w>30</w> | ||||||
|  |       <h>30</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>type=initial</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>540</x> | ||||||
|  |       <y>405</y> | ||||||
|  |       <w>270</w> | ||||||
|  |       <h>105</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>RUN | ||||||
|  | -- | ||||||
|  | /entry: LED ON | ||||||
|  | -- | ||||||
|  | emitPollDirEv</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>480</x> | ||||||
|  |       <y>180</y> | ||||||
|  |       <w>390</w> | ||||||
|  |       <h>135</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>WAIT | ||||||
|  | -- | ||||||
|  | ALIVE_emitBorn(ALsteering(), 0, 0); | ||||||
|  | ALIVE_emitReady(ALsteering(), 100, 0); | ||||||
|  | setAliveTime</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>660</x> | ||||||
|  |       <y>300</y> | ||||||
|  |       <w>120</w> | ||||||
|  |       <h>135</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1=evStart\n(onWait) | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>10.0;10.0;10.0;70.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>735</x> | ||||||
|  |       <y>450</y> | ||||||
|  |       <w>195</w> | ||||||
|  |       <h>180</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1= evPollDir\n/sendDir | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>10.0;40.0;10.0;100.0;110.0;100.0;110.0;10.0;50.0;10.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>390</x> | ||||||
|  |       <y>240</y> | ||||||
|  |       <w>345</w> | ||||||
|  |       <h>555</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1= evResurrect\n(onBorn) | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>130.0;300.0;130.0;350.0;10.0;350.0;10.0;10.0;60.0;10.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>450</x> | ||||||
|  |       <y>600</y> | ||||||
|  |       <w>270</w> | ||||||
|  |       <h>90</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>DEAD | ||||||
|  | -- | ||||||
|  | /entry: LED OFF</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>570</x> | ||||||
|  |       <y>495</y> | ||||||
|  |       <w>135</w> | ||||||
|  |       <h>135</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1=evStop\n(onDead) | ||||||
|  | </panel_attributes> | ||||||
|  |     <additional_attributes>10.0;10.0;10.0;70.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  | </diagram> | ||||||
							
								
								
									
										74
									
								
								UML/watchdog.uxf
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										74
									
								
								UML/watchdog.uxf
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,74 @@ | |||||||
|  | <?xml version="1.0" encoding="UTF-8" standalone="no"?> | ||||||
|  | <diagram program="umlet" version="15.0.0"> | ||||||
|  |   <zoom_level>15</zoom_level> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLSpecialState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>315</x> | ||||||
|  |       <y>270</y> | ||||||
|  |       <w>30</w> | ||||||
|  |       <h>30</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>type=initial</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>315</x> | ||||||
|  |       <y>285</y> | ||||||
|  |       <w>120</w> | ||||||
|  |       <h>105</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | evWDinit</panel_attributes> | ||||||
|  |     <additional_attributes>10.0;10.0;10.0;50.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLState</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>255</x> | ||||||
|  |       <y>360</y> | ||||||
|  |       <w>150</w> | ||||||
|  |       <h>60</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>STWD_ALIVE</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>Relation</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>180</x> | ||||||
|  |       <y>375</y> | ||||||
|  |       <w>270</w> | ||||||
|  |       <h>135</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>lt=-> | ||||||
|  | m1=evWDpoll</panel_attributes> | ||||||
|  |     <additional_attributes>100.0;30.0;100.0;70.0;10.0;70.0;10.0;10.0;50.0;10.0</additional_attributes> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLNote</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>480</x> | ||||||
|  |       <y>360</y> | ||||||
|  |       <w>150</w> | ||||||
|  |       <h>60</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>send alive | ||||||
|  | by CAN</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  |   <element> | ||||||
|  |     <id>UMLNote</id> | ||||||
|  |     <coordinates> | ||||||
|  |       <x>375</x> | ||||||
|  |       <y>225</y> | ||||||
|  |       <w>150</w> | ||||||
|  |       <h>60</h> | ||||||
|  |     </coordinates> | ||||||
|  |     <panel_attributes>read time on | ||||||
|  | EPROM</panel_attributes> | ||||||
|  |     <additional_attributes/> | ||||||
|  |   </element> | ||||||
|  | </diagram> | ||||||
							
								
								
									
										2842
									
								
								binary_files/v1_0_0.hex
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2842
									
								
								binary_files/v1_0_0.hex
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2842
									
								
								binary_files/v1_0_1.hex
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2842
									
								
								binary_files/v1_0_1.hex
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2843
									
								
								binary_files/v1_0_2-without_set_center.hex
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2843
									
								
								binary_files/v1_0_2-without_set_center.hex
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2853
									
								
								binary_files/v1_1_0-controller_alive_and_wait_604-no_curves.hex
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2853
									
								
								binary_files/v1_1_0-controller_alive_and_wait_604-no_curves.hex
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2974
									
								
								binary_files/v1_2_0-curve_and_headlights.hex
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2974
									
								
								binary_files/v1_2_0-curve_and_headlights.hex
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2972
									
								
								binary_files/v1_2_1-led.hex
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2972
									
								
								binary_files/v1_2_1-led.hex
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2985
									
								
								binary_files/v1_3_0-boost_by_pb.hex
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2985
									
								
								binary_files/v1_3_0-boost_by_pb.hex
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										981
									
								
								busmaster_config.cfx
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										981
									
								
								busmaster_config.cfx
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,981 @@ | |||||||
|  | <?xml version="1.0" encoding="UTF-8"?> | ||||||
|  | <BUSMASTER_CONFIGURATION> | ||||||
|  |   <Global_Configuration> | ||||||
|  |     <BUSMASTER_Version>3.2.2</BUSMASTER_Version> | ||||||
|  |     <IsMsgFilterEnabled>FALSE</IsMsgFilterEnabled> | ||||||
|  |     <IsMsgFilterEnabledLin>FALSE</IsMsgFilterEnabledLin> | ||||||
|  |     <IsReplayFilterEnabled>FALSE</IsReplayFilterEnabled> | ||||||
|  |     <IsLogFilterEnabled>FALSE</IsLogFilterEnabled> | ||||||
|  |     <IsLogFilterLINEnabled>FALSE</IsLogFilterLINEnabled> | ||||||
|  |     <IsLoggingEnabled>FALSE</IsLoggingEnabled> | ||||||
|  |     <IsMsgIntepretationEnabled>TRUE</IsMsgIntepretationEnabled> | ||||||
|  |     <IsOverWriteEnabled>TRUE</IsOverWriteEnabled> | ||||||
|  |     <DisplayTimeMode>SYSTEM</DisplayTimeMode> | ||||||
|  |     <DisplayNumericMode>FALSE</DisplayNumericMode> | ||||||
|  |     <LogOnConnect_CAN>FALSE</LogOnConnect_CAN> | ||||||
|  |     <LogOnConnect_J1939>FALSE</LogOnConnect_J1939> | ||||||
|  |     <LogOnConnect_LIN>FALSE</LogOnConnect_LIN> | ||||||
|  |     <Window_Position> | ||||||
|  |       <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |       <WindowPlacement>HIDE</WindowPlacement> | ||||||
|  |       <Top>765</Top> | ||||||
|  |       <Left>0</Left> | ||||||
|  |       <Bottom>874</Bottom> | ||||||
|  |       <Right>1532</Right> | ||||||
|  |     </Window_Position> | ||||||
|  |   </Global_Configuration> | ||||||
|  |   <Module_Configuration> | ||||||
|  |     <CAN_Database_Files> | ||||||
|  |       <FilePath>threewheeler.DBF</FilePath> | ||||||
|  |     </CAN_Database_Files> | ||||||
|  |     <Bus_Statistics> | ||||||
|  |       <CAN_Statistics> | ||||||
|  |         <COLUMN> | ||||||
|  |           <ID>Parameter</ID> | ||||||
|  |           <Order>1</Order> | ||||||
|  |           <Width>200</Width> | ||||||
|  |           <IsVisible>1</IsVisible> | ||||||
|  |         </COLUMN> | ||||||
|  |         <COLUMN> | ||||||
|  |           <ID>Channel 1</ID> | ||||||
|  |           <Order>2</Order> | ||||||
|  |           <Width>90</Width> | ||||||
|  |           <IsVisible>1</IsVisible> | ||||||
|  |         </COLUMN> | ||||||
|  |       </CAN_Statistics> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement> | ||||||
|  |         <Top>291</Top> | ||||||
|  |         <Left>403</Left> | ||||||
|  |         <Bottom>788</Bottom> | ||||||
|  |         <Right>825</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |     </Bus_Statistics> | ||||||
|  |     <J1939_Database_Files/> | ||||||
|  |     <CAN_DIL_Section> | ||||||
|  |       <DriverName>MHS Tiny-CAN</DriverName> | ||||||
|  |       <ControllerMode>Unknown</ControllerMode> | ||||||
|  |       <ControllerSettings> | ||||||
|  |         <Channel> | ||||||
|  |           <BaudRate>250</BaudRate> | ||||||
|  |           <CNF1>7</CNF1> | ||||||
|  |           <CNF2>B8</CNF2> | ||||||
|  |           <CNF3>5</CNF3> | ||||||
|  |           <BTR0>00</BTR0> | ||||||
|  |           <BTR1>1C</BTR1> | ||||||
|  |           <Clock>16</Clock> | ||||||
|  |           <SamplePerc>75</SamplePerc> | ||||||
|  |           <Sampling>1</Sampling> | ||||||
|  |           <BTLCycles>10</BTLCycles> | ||||||
|  |           <Warning_Limit>96</Warning_Limit> | ||||||
|  |           <Propagation_Delay>ALL</Propagation_Delay> | ||||||
|  |           <SJW>4</SJW> | ||||||
|  |           <AccCodeByte1_0>0</AccCodeByte1_0> | ||||||
|  |           <AccCodeByte1_1>0</AccCodeByte1_1> | ||||||
|  |           <AccCodeByte2_0>0</AccCodeByte2_0> | ||||||
|  |           <AccCodeByte2_1>0</AccCodeByte2_1> | ||||||
|  |           <AccCodeByte3_0>0</AccCodeByte3_0> | ||||||
|  |           <AccCodeByte3_1>0</AccCodeByte3_1> | ||||||
|  |           <AccCodeByte4_0>0</AccCodeByte4_0> | ||||||
|  |           <AccCodeByte4_1>0</AccCodeByte4_1> | ||||||
|  |           <AccMaskByte1_0>FF</AccMaskByte1_0> | ||||||
|  |           <AccMaskByte1_1>FF</AccMaskByte1_1> | ||||||
|  |           <AccMaskByte2_0>FF</AccMaskByte2_0> | ||||||
|  |           <AccMaskByte2_1>FF</AccMaskByte2_1> | ||||||
|  |           <AccMaskByte3_0>FF</AccMaskByte3_0> | ||||||
|  |           <AccMaskByte3_1>FF</AccMaskByte3_1> | ||||||
|  |           <AccMaskByte4_0>FF</AccMaskByte4_0> | ||||||
|  |           <AccMaskByte4_1>FF</AccMaskByte4_1> | ||||||
|  |           <HardwareDesc>Simulation</HardwareDesc> | ||||||
|  |           <ItemUnderFocus>64</ItemUnderFocus> | ||||||
|  |           <BTR0BTR1>0</BTR0BTR1> | ||||||
|  |           <AccFilterMode>0</AccFilterMode> | ||||||
|  |           <ControllerMode>1</ControllerMode> | ||||||
|  |           <SelfReception>1</SelfReception> | ||||||
|  |           <HWFilterType_0>0</HWFilterType_0> | ||||||
|  |           <HWFilterType_1>0</HWFilterType_1> | ||||||
|  |           <Debug>0</Debug> | ||||||
|  |           <PassiveMode>0</PassiveMode> | ||||||
|  |           <HWTimestamps>0</HWTimestamps> | ||||||
|  |           <Location/> | ||||||
|  |           <LowSpeed>0</LowSpeed> | ||||||
|  |           <CANFD_BaudRate>2000000</CANFD_BaudRate> | ||||||
|  |           <CANFD_SamplePoint>70</CANFD_SamplePoint> | ||||||
|  |           <CANFD_BTLCycles>10</CANFD_BTLCycles> | ||||||
|  |           <CANFD_SJW>3</CANFD_SJW> | ||||||
|  |           <CANFD_TxDelayCompensation>0</CANFD_TxDelayCompensation> | ||||||
|  |           <CANFD_TxSecondarySamplePoint>0</CANFD_TxSecondarySamplePoint> | ||||||
|  |         </Channel> | ||||||
|  |       </ControllerSettings> | ||||||
|  |     </CAN_DIL_Section> | ||||||
|  |     <CAN_Filters> | ||||||
|  |       <Filter> | ||||||
|  |         <Name>display</Name> | ||||||
|  |         <Type>PASS</Type> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>306</IdFrom> | ||||||
|  |           <IdTo>306</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>307</IdFrom> | ||||||
|  |           <IdTo>307</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>48</IdFrom> | ||||||
|  |           <IdTo>48</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>799</IdFrom> | ||||||
|  |           <IdTo>799</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>1585</IdFrom> | ||||||
|  |           <IdTo>1585</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>1586</IdFrom> | ||||||
|  |           <IdTo>1586</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>1587</IdFrom> | ||||||
|  |           <IdTo>1587</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |       </Filter> | ||||||
|  |       <Filter> | ||||||
|  |         <Name>drive</Name> | ||||||
|  |         <Type>PASS</Type> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>320</IdFrom> | ||||||
|  |           <IdTo>320</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>321</IdFrom> | ||||||
|  |           <IdTo>321</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>1040</IdFrom> | ||||||
|  |           <IdTo>1040</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>1055</IdFrom> | ||||||
|  |           <IdTo>1055</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |       </Filter> | ||||||
|  |       <Filter> | ||||||
|  |         <Name>joy</Name> | ||||||
|  |         <Type>PASS</Type> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>288</IdFrom> | ||||||
|  |           <IdTo>288</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>529</IdFrom> | ||||||
|  |           <IdTo>529</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>543</IdFrom> | ||||||
|  |           <IdTo>543</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |       </Filter> | ||||||
|  |       <Filter> | ||||||
|  |         <Name>noAlive</Name> | ||||||
|  |         <Type>STOP</Type> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>271</IdFrom> | ||||||
|  |           <IdTo>271</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>543</IdFrom> | ||||||
|  |           <IdTo>543</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>799</IdFrom> | ||||||
|  |           <IdTo>799</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>1055</IdFrom> | ||||||
|  |           <IdTo>1055</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>1311</IdFrom> | ||||||
|  |           <IdTo>1311</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |       </Filter> | ||||||
|  |       <Filter> | ||||||
|  |         <Name>steering</Name> | ||||||
|  |         <Type>PASS</Type> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>336</IdFrom> | ||||||
|  |           <IdTo>336</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>337</IdFrom> | ||||||
|  |           <IdTo>337</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>1298</IdFrom> | ||||||
|  |           <IdTo>1298</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>1311</IdFrom> | ||||||
|  |           <IdTo>1311</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |         <FilterMessage> | ||||||
|  |           <IdFrom>82</IdFrom> | ||||||
|  |           <IdTo>82</IdTo> | ||||||
|  |           <Direction>ALL</Direction> | ||||||
|  |           <IDType>ALL</IDType> | ||||||
|  |           <MsgType>ALL</MsgType> | ||||||
|  |           <Channel>0</Channel> | ||||||
|  |         </FilterMessage> | ||||||
|  |       </Filter> | ||||||
|  |     </CAN_Filters> | ||||||
|  |     <CAN_Signal_Watch> | ||||||
|  |       <Message> | ||||||
|  |         <Id>529</Id> | ||||||
|  |         <Signal>posX</Signal> | ||||||
|  |         <Signal>posY</Signal> | ||||||
|  |       </Message> | ||||||
|  |       <Message> | ||||||
|  |         <Id>1040</Id> | ||||||
|  |         <Signal>Speed</Signal> | ||||||
|  |       </Message> | ||||||
|  |       <Message> | ||||||
|  |         <Id>321</Id> | ||||||
|  |         <Signal>Power</Signal> | ||||||
|  |       </Message> | ||||||
|  |       <Message> | ||||||
|  |         <Id>306</Id> | ||||||
|  |         <Signal>Vehiclespeed</Signal> | ||||||
|  |       </Message> | ||||||
|  |       <Message> | ||||||
|  |         <Id>337</Id> | ||||||
|  |         <Signal>SteeringPosition</Signal> | ||||||
|  |       </Message> | ||||||
|  |       <Message> | ||||||
|  |         <Id>1311</Id> | ||||||
|  |       </Message> | ||||||
|  |       <Message> | ||||||
|  |         <Id>1294</Id> | ||||||
|  |         <Signal>brake</Signal> | ||||||
|  |       </Message> | ||||||
|  |       <Message> | ||||||
|  |         <Id>1540</Id> | ||||||
|  |       </Message> | ||||||
|  |       <Message> | ||||||
|  |         <Id>260</Id> | ||||||
|  |         <Signal>headlights</Signal> | ||||||
|  |       </Message> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>HIDE</WindowPlacement> | ||||||
|  |         <Top>186</Top> | ||||||
|  |         <Left>513</Left> | ||||||
|  |         <Right>960</Right> | ||||||
|  |         <Bottom>747</Bottom> | ||||||
|  |       </Window_Position> | ||||||
|  |       <COLUMN_WIDTH> | ||||||
|  |         <MESSAGE_COLUMN>86</MESSAGE_COLUMN> | ||||||
|  |         <Raw_Val_Column>86</Raw_Val_Column> | ||||||
|  |         <Physical_Val_Column>172</Physical_Val_Column> | ||||||
|  |         <Signal_Column>86</Signal_Column> | ||||||
|  |       </COLUMN_WIDTH> | ||||||
|  |     </CAN_Signal_Watch> | ||||||
|  |     <J1939_Signal_Watch> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>HIDE</WindowPlacement> | ||||||
|  |         <Top>70</Top> | ||||||
|  |         <Left>10</Left> | ||||||
|  |         <Right>500</Right> | ||||||
|  |         <Bottom>300</Bottom> | ||||||
|  |       </Window_Position> | ||||||
|  |       <COLUMN_WIDTH> | ||||||
|  |         <MESSAGE_COLUMN>94</MESSAGE_COLUMN> | ||||||
|  |         <Raw_Val_Column>94</Raw_Val_Column> | ||||||
|  |         <Physical_Val_Column>189</Physical_Val_Column> | ||||||
|  |         <Signal_Column>94</Signal_Column> | ||||||
|  |       </COLUMN_WIDTH> | ||||||
|  |     </J1939_Signal_Watch> | ||||||
|  |     <LIN_Signal_Watch> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>HIDE</WindowPlacement> | ||||||
|  |         <Top>70</Top> | ||||||
|  |         <Left>10</Left> | ||||||
|  |         <Right>500</Right> | ||||||
|  |         <Bottom>300</Bottom> | ||||||
|  |       </Window_Position> | ||||||
|  |       <COLUMN_WIDTH> | ||||||
|  |         <MESSAGE_COLUMN>94</MESSAGE_COLUMN> | ||||||
|  |         <Raw_Val_Column>94</Raw_Val_Column> | ||||||
|  |         <Physical_Val_Column>189</Physical_Val_Column> | ||||||
|  |         <Signal_Column>94</Signal_Column> | ||||||
|  |       </COLUMN_WIDTH> | ||||||
|  |     </LIN_Signal_Watch> | ||||||
|  |     <CAN_Signal_Graph> | ||||||
|  |       <GRAPH_PARAMETERS> | ||||||
|  |         <Buffer_Size>5000</Buffer_Size> | ||||||
|  |         <Refresh_Rate>1000</Refresh_Rate> | ||||||
|  |         <Frame_Color>21760</Frame_Color> | ||||||
|  |         <Frame_Style>1</Frame_Style> | ||||||
|  |         <Plot_Area_Color>0</Plot_Area_Color> | ||||||
|  |         <Grid_Color>12632256</Grid_Color> | ||||||
|  |         <Axis_Color>255</Axis_Color> | ||||||
|  |         <X_Grid_Lines>10</X_Grid_Lines> | ||||||
|  |         <Y_Grid_Lines>5</Y_Grid_Lines> | ||||||
|  |         <Active_Axis>2</Active_Axis> | ||||||
|  |         <Selected_Action>0</Selected_Action> | ||||||
|  |         <Show_Grid>TRUE</Show_Grid> | ||||||
|  |         <Display_Type>NORMAL</Display_Type> | ||||||
|  |       </GRAPH_PARAMETERS> | ||||||
|  |       <GRAPH_ELEMENT> | ||||||
|  |         <Message_ID>1586</Message_ID> | ||||||
|  |         <Message_Name>DISPLAY_CURRENT</Message_Name> | ||||||
|  |         <Frame_Format/> | ||||||
|  |         <Element_Name>BatteryCurrent</Element_Name> | ||||||
|  |         <Value_Type>Physical</Value_Type> | ||||||
|  |         <Line_Type>SOLID</Line_Type> | ||||||
|  |         <Line_Color>65280</Line_Color> | ||||||
|  |         <Point_Type>2</Point_Type> | ||||||
|  |         <Point_Color>8421376</Point_Color> | ||||||
|  |         <Visibility>TRUE</Visibility> | ||||||
|  |         <Enable>TRUE</Enable> | ||||||
|  |         <Display_Type>NORMAL</Display_Type> | ||||||
|  |       </GRAPH_ELEMENT> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <Window_Position>HIDE</Window_Position> | ||||||
|  |         <Top>39</Top> | ||||||
|  |         <Left>74</Left> | ||||||
|  |         <Bottom>586</Bottom> | ||||||
|  |         <Right>1399</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |       <Splitter_Window_Col_0> | ||||||
|  |         <CxIdeal>479</CxIdeal> | ||||||
|  |         <CxMin>0</CxMin> | ||||||
|  |       </Splitter_Window_Col_0> | ||||||
|  |       <Splitter_Window_Col_1> | ||||||
|  |         <CxIdeal>819</CxIdeal> | ||||||
|  |         <CxMin>0</CxMin> | ||||||
|  |       </Splitter_Window_Col_1> | ||||||
|  |       <Splitter_Window_Row_0> | ||||||
|  |         <CxIdeal>275</CxIdeal> | ||||||
|  |         <CxMin>0</CxMin> | ||||||
|  |       </Splitter_Window_Row_0> | ||||||
|  |       <Splitter_Window_Row_1> | ||||||
|  |         <CxIdeal>222</CxIdeal> | ||||||
|  |         <CxMin>0</CxMin> | ||||||
|  |       </Splitter_Window_Row_1> | ||||||
|  |     </CAN_Signal_Graph> | ||||||
|  |     <CAN_Log> | ||||||
|  |       <LogOnConnect>0</LogOnConnect> | ||||||
|  |     </CAN_Log> | ||||||
|  |     <J1939_Log> | ||||||
|  |       <LogOnConnect>0</LogOnConnect> | ||||||
|  |     </J1939_Log> | ||||||
|  |     <LIN_Log> | ||||||
|  |       <LogOnConnect>0</LogOnConnect> | ||||||
|  |     </LIN_Log> | ||||||
|  |     <CAN_Simulated_Systems> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement> | ||||||
|  |         <Top>0</Top> | ||||||
|  |         <Left>0</Left> | ||||||
|  |         <Bottom>577</Bottom> | ||||||
|  |         <Right>423</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |     </CAN_Simulated_Systems> | ||||||
|  |     <J1939_Simulated_Systems> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>HIDE</Visibility> | ||||||
|  |         <WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement> | ||||||
|  |         <Top>0</Top> | ||||||
|  |         <Left>0</Left> | ||||||
|  |         <Bottom>0</Bottom> | ||||||
|  |         <Right>0</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |     </J1939_Simulated_Systems> | ||||||
|  |     <CAN_Replay/> | ||||||
|  |     <CAN_Message_Window> | ||||||
|  |       <Append_Buffer_Size>1474521904</Append_Buffer_Size> | ||||||
|  |       <Overwrite_Buffer_Size>23911192</Overwrite_Buffer_Size> | ||||||
|  |       <Display_Update_Time>1474521876</Display_Update_Time> | ||||||
|  |       <Filter IsEnabled="0">display</Filter> | ||||||
|  |       <Filter IsEnabled="0">drive</Filter> | ||||||
|  |       <Filter IsEnabled="0">joy</Filter> | ||||||
|  |       <Filter IsEnabled="1">noAlive</Filter> | ||||||
|  |       <Filter IsEnabled="0">steering</Filter> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID/> | ||||||
|  |         <Order>5</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>19</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Time</ID> | ||||||
|  |         <Order>4</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>129</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Tx/Rx</ID> | ||||||
|  |         <Order>1</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>53</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Channel</ID> | ||||||
|  |         <Order>2</Order> | ||||||
|  |         <IsVisible>0</IsVisible> | ||||||
|  |         <Width>0</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Msg Type</ID> | ||||||
|  |         <Order>3</Order> | ||||||
|  |         <IsVisible>0</IsVisible> | ||||||
|  |         <Width>0</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>ID</ID> | ||||||
|  |         <Order>6</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>69</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Message</ID> | ||||||
|  |         <Order>7</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>143</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>DLC</ID> | ||||||
|  |         <Order>8</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>38</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Data Byte(s)</ID> | ||||||
|  |         <Order>9</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>139</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <IsHex>1</IsHex> | ||||||
|  |       <IsAppend>0</IsAppend> | ||||||
|  |       <IsInterpret>1</IsInterpret> | ||||||
|  |       <Time_Mode>SYSTEM</Time_Mode> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>SETMINPOSITION</WindowPlacement> | ||||||
|  |         <Top>3</Top> | ||||||
|  |         <Left>0</Left> | ||||||
|  |         <Bottom>627</Bottom> | ||||||
|  |         <Right>606</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |       <Interpretation_Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement> | ||||||
|  |         <Top>181</Top> | ||||||
|  |         <Left>12</Left> | ||||||
|  |         <Bottom>459</Bottom> | ||||||
|  |         <Right>361</Right> | ||||||
|  |       </Interpretation_Window_Position> | ||||||
|  |     </CAN_Message_Window> | ||||||
|  |     <J1939_Message_Window> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID/> | ||||||
|  |         <Order>1</Order> | ||||||
|  |         <IsVisible>0</IsVisible> | ||||||
|  |         <Width>0</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Time</ID> | ||||||
|  |         <Order>2</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>91</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Channel</ID> | ||||||
|  |         <Order>3</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>88</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>CAN ID</ID> | ||||||
|  |         <Order>4</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>88</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>PGN</ID> | ||||||
|  |         <Order>5</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>84</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>PGN Name</ID> | ||||||
|  |         <Order>6</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>118</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Type</ID> | ||||||
|  |         <Order>7</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>75</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Src</ID> | ||||||
|  |         <Order>8</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>60</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Dest</ID> | ||||||
|  |         <Order>9</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>57</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Priority</ID> | ||||||
|  |         <Order>10</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>74</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Tx/Rx</ID> | ||||||
|  |         <Order>11</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>73</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>DLC</ID> | ||||||
|  |         <Order>12</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>70</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Data Byte(s)</ID> | ||||||
|  |         <Order>13</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>662</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <IsHex>1</IsHex> | ||||||
|  |       <IsAppend>1</IsAppend> | ||||||
|  |       <IsInterpret>0</IsInterpret> | ||||||
|  |       <Time_Mode>SYSTEM</Time_Mode> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>SETMINPOSITION</WindowPlacement> | ||||||
|  |         <Top>0</Top> | ||||||
|  |         <Left>0</Left> | ||||||
|  |         <Bottom>549</Bottom> | ||||||
|  |         <Right>1556</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |       <Interpretation_Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement> | ||||||
|  |         <Top>181</Top> | ||||||
|  |         <Left>12</Left> | ||||||
|  |         <Bottom>459</Bottom> | ||||||
|  |         <Right>361</Right> | ||||||
|  |       </Interpretation_Window_Position> | ||||||
|  |     </J1939_Message_Window> | ||||||
|  |     <LIN_Message_Window> | ||||||
|  |       <Append_Buffer_Size>5000</Append_Buffer_Size> | ||||||
|  |       <Overwrite_Buffer_Size>2000</Overwrite_Buffer_Size> | ||||||
|  |       <Display_Update_Time>100</Display_Update_Time> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID/> | ||||||
|  |         <Order>1</Order> | ||||||
|  |         <IsVisible>0</IsVisible> | ||||||
|  |         <Width>0</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Time</ID> | ||||||
|  |         <Order>2</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>95</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Message</ID> | ||||||
|  |         <Order>3</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>99</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Message Type</ID> | ||||||
|  |         <Order>4</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>135</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Tx/Rx</ID> | ||||||
|  |         <Order>5</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>85</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Channel</ID> | ||||||
|  |         <Order>6</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>80</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>DLC</ID> | ||||||
|  |         <Order>7</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>70</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>ID</ID> | ||||||
|  |         <Order>8</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>65</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Data Byte(s)</ID> | ||||||
|  |         <Order>9</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>235</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <COLUMN> | ||||||
|  |         <ID>Checksum</ID> | ||||||
|  |         <Order>10</Order> | ||||||
|  |         <IsVisible>1</IsVisible> | ||||||
|  |         <Width>676</Width> | ||||||
|  |       </COLUMN> | ||||||
|  |       <IsHex>1</IsHex> | ||||||
|  |       <IsAppend>1</IsAppend> | ||||||
|  |       <IsInterpret>0</IsInterpret> | ||||||
|  |       <Time_Mode>SYSTEM</Time_Mode> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>SETMINPOSITION</WindowPlacement> | ||||||
|  |         <Top>0</Top> | ||||||
|  |         <Left>0</Left> | ||||||
|  |         <Bottom>549</Bottom> | ||||||
|  |         <Right>1556</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |       <Interpretation_Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement> | ||||||
|  |         <Top>181</Top> | ||||||
|  |         <Left>12</Left> | ||||||
|  |         <Bottom>459</Bottom> | ||||||
|  |         <Right>361</Right> | ||||||
|  |       </Interpretation_Window_Position> | ||||||
|  |     </LIN_Message_Window> | ||||||
|  |     <CAN_Tx_Window> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>SETMINPOSITION</WindowPlacement> | ||||||
|  |         <Top>4</Top> | ||||||
|  |         <Left>648</Left> | ||||||
|  |         <Bottom>659</Bottom> | ||||||
|  |         <Right>1508</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |       <Message_List> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>16</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,0,0,10</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>17</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,1,178,7</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>18</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,0,39,16</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>19</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,85,115,240</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>20</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>2</DLC> | ||||||
|  |           <DataBytes>0,0</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>21</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,250,0,0</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>22</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,5,1,250</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>23</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,0,0,0</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>24</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,0,0,0</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>1540</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>0</DLC> | ||||||
|  |           <DataBytes>0</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>1298</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,0,0,0</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>337</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,0,78,32</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |         <Message> | ||||||
|  |           <Channel>1</Channel> | ||||||
|  |           <Message_ID>336</Message_ID> | ||||||
|  |           <IsExtended>FALSE</IsExtended> | ||||||
|  |           <IsRtr>FALSE</IsRtr> | ||||||
|  |           <DLC>4</DLC> | ||||||
|  |           <DataBytes>0,1,0,0</DataBytes> | ||||||
|  |           <Repetion>10</Repetion> | ||||||
|  |           <Repetition_Enabled>FALSE</Repetition_Enabled> | ||||||
|  |           <Key_Value>a</Key_Value> | ||||||
|  |           <Key_Enabled>FALSE</Key_Enabled> | ||||||
|  |         </Message> | ||||||
|  |       </Message_List> | ||||||
|  |     </CAN_Tx_Window> | ||||||
|  |     <CAN_Wave_Form_Genarator> | ||||||
|  |       <Default_Sampling_Period>125</Default_Sampling_Period> | ||||||
|  |       <SignalDefiner_AutoCorrect>1</SignalDefiner_AutoCorrect> | ||||||
|  |     </CAN_Wave_Form_Genarator> | ||||||
|  |     <LIN_Simulated_Systems> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>HIDE</Visibility> | ||||||
|  |         <WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement> | ||||||
|  |         <Top>0</Top> | ||||||
|  |         <Left>0</Left> | ||||||
|  |         <Bottom>0</Bottom> | ||||||
|  |         <Right>0</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |     </LIN_Simulated_Systems> | ||||||
|  |     <LIN_Cluster_Config> | ||||||
|  |       <CHANNEL> | ||||||
|  |         <Index>0</Index> | ||||||
|  |         <HWUri>Hardware</HWUri> | ||||||
|  |         <BaudRate>19200</BaudRate> | ||||||
|  |         <ProtocolVersion>LIN 2.0</ProtocolVersion> | ||||||
|  |         <Overwrite_Settings>1</Overwrite_Settings> | ||||||
|  |         <MasterMode>0</MasterMode> | ||||||
|  |         <ECU/> | ||||||
|  |       </CHANNEL> | ||||||
|  |     </LIN_Cluster_Config> | ||||||
|  |     <LIN_Tx_Window> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>SETMINPOSITION</WindowPlacement> | ||||||
|  |         <Top>1</Top> | ||||||
|  |         <Left>4</Left> | ||||||
|  |         <Bottom>661</Bottom> | ||||||
|  |         <Right>864</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |       <Message_List/> | ||||||
|  |     </LIN_Tx_Window> | ||||||
|  |     <LIN_Schedule_Table> | ||||||
|  |       <Window_Position> | ||||||
|  |         <Visibility>SHOWNORMAL</Visibility> | ||||||
|  |         <WindowPlacement>SETMINPOSITION</WindowPlacement> | ||||||
|  |         <Top>183</Top> | ||||||
|  |         <Left>535</Left> | ||||||
|  |         <Bottom>716</Bottom> | ||||||
|  |         <Right>1185</Right> | ||||||
|  |       </Window_Position> | ||||||
|  |       <Channel> | ||||||
|  |         <Index>1</Index> | ||||||
|  |       </Channel> | ||||||
|  |     </LIN_Schedule_Table> | ||||||
|  |   </Module_Configuration> | ||||||
|  | </BUSMASTER_CONFIGURATION> | ||||||
| @@ -6,7 +6,7 @@ | |||||||
|  |  | ||||||
| [BUSMASTER_VERSION] [3.2.2] | [BUSMASTER_VERSION] [3.2.2] | ||||||
|  |  | ||||||
| [NUMBER_OF_MESSAGES] 25 | [NUMBER_OF_MESSAGES] 33 | ||||||
|  |  | ||||||
| [START_MSG] JOY_MEASURE,529,3,3,1,S | [START_MSG] JOY_MEASURE,529,3,3,1,S | ||||||
| [START_SIGNALS] posX,8,1,0,I,127,-128,1,0.000000,1.000000,%, | [START_SIGNALS] posX,8,1,0,I,127,-128,1,0.000000,1.000000,%, | ||||||
| @@ -38,10 +38,11 @@ | |||||||
| [VALUE_DESCRIPTION] RACE,2 | [VALUE_DESCRIPTION] RACE,2 | ||||||
| [END_MSG] | [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, | [START_SIGNALS] AliveTime,8,4,0,U,255,0,1,0.000000,10.000000,mS, | ||||||
| [VALUE_DESCRIPTION] No alive message,0 | [VALUE_DESCRIPTION] No alive message,0 | ||||||
| [START_SIGNALS] STEERING_MODE,1,1,0,B,1,0,1,0.000000,1.000000,, | [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] | [END_MSG] | ||||||
|  |  | ||||||
| [START_MSG] CONTROL_SPEED_FACTOR,17,4,1,1,S | [START_MSG] CONTROL_SPEED_FACTOR,17,4,1,1,S | ||||||
| @@ -71,7 +72,7 @@ | |||||||
| [VALUE_DESCRIPTION] No alive message,0 | [VALUE_DESCRIPTION] No alive message,0 | ||||||
| [END_MSG] | [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, | [START_SIGNALS] AliveTime,8,4,0,U,255,0,1,0.000000,10.000000,ms, | ||||||
| [END_MSG] | [END_MSG] | ||||||
|  |  | ||||||
| @@ -151,3 +152,42 @@ | |||||||
| [START_MSG] STEERING_GET_POS,1298,4,1,1,S | [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, | [START_SIGNALS] POSITION,32,4,0,I,2147483647,-2147483648,0,0.000000,1.000000,qc, | ||||||
| [END_MSG] | [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] | ||||||
|  |  | ||||||
|  | [START_MSG] BRAKE,1294,1,1,1,S | ||||||
|  | [START_SIGNALS] brake,1,1,0,B,1,0,1,0.000000,1.000000,, | ||||||
|  | [END_MSG] | ||||||
|  |  | ||||||
|  | [START_MSG] SUPPLY_48V_READY,1540,0,0,1,S | ||||||
|  | [END_MSG] | ||||||
|  |  | ||||||
|  | [START_MSG] HEADLIGHTS,260,1,1,1,S | ||||||
|  | [START_SIGNALS] headlights,1,1,0,B,1,0,1,0.000000,1.000000,, | ||||||
|  | [END_MSG] | ||||||
|  |  | ||||||
|  | [START_MSG] SUPPLY_ALIVE,1551,0,0,1,S | ||||||
|  | [END_MSG] | ||||||
		Reference in New Issue
	
	Block a user