add watchdog system
This commit is contained in:
commit
70127bbb8d
99
306-controller_interface.X/app/can_message.c
Normal file
99
306-controller_interface.X/app/can_message.c
Normal file
@ -0,0 +1,99 @@
|
||||
/**
|
||||
* @author Rémi Heredero
|
||||
* @version 1.0.0
|
||||
* @date August 2023
|
||||
* @file can_message.c
|
||||
*/
|
||||
|
||||
#include "../middleware/can_interface.h"
|
||||
#include "car.h"
|
||||
#include "../app/factory/factory.h"
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t byte0;
|
||||
uint8_t byte1;
|
||||
uint8_t byte2;
|
||||
uint8_t byte3;
|
||||
} separate;
|
||||
struct {
|
||||
uint32_t bytes;
|
||||
} full;
|
||||
} BYTES_4;
|
||||
|
||||
void CM_processIncome(uint8_t idSender, uint8_t idMsg, uint32_t data){
|
||||
switch(idSender){
|
||||
case 0: // Broadcast / Debug
|
||||
break;
|
||||
|
||||
case 2: // Joystick
|
||||
if(idMsg == 0x1) { // JOY_MESURE
|
||||
|
||||
}
|
||||
|
||||
if(idMsg == 0xF) { // JOY_ALIVE
|
||||
ALIVE_CHECKER_ISALIVE(ACjoy());
|
||||
}
|
||||
break;
|
||||
|
||||
case 3: // Display
|
||||
break;
|
||||
|
||||
case 4: // Drive
|
||||
break;
|
||||
|
||||
case 5: // Steering
|
||||
break;
|
||||
|
||||
case 6: // Supply
|
||||
break;
|
||||
|
||||
case 7: // Undefined
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void CM_CONTROLLER_ALIVE(void* p) {
|
||||
CAN_Send(0x0, 0xF, 0);
|
||||
}
|
||||
|
||||
void CM_JOY_SETUP(void* p) {
|
||||
BYTES_4 joy;
|
||||
joy.separate.byte0 = CAR_CST.JOYSTICK_MODE;
|
||||
joy.separate.byte1 = CAR_CST.JOYSTICK_PARAM1;
|
||||
joy.separate.byte2 = CAR_CST.JOYSTICK_PARAM2;
|
||||
joy.separate.byte3 = CAR_CST.JOYSTICK_ALIVE_TIME;
|
||||
CAN_Send(2, 0, joy.full.bytes);
|
||||
|
||||
}
|
||||
void CM_DISPLAY_SETUP(void* p) {
|
||||
|
||||
}
|
||||
|
||||
void CM_DISPLAY_SPEED(void* p) {
|
||||
|
||||
}
|
||||
|
||||
void CM_DISPLAY_DIRECTION(void* p) {
|
||||
|
||||
}
|
||||
|
||||
void CM_DRIVE_SETUP(void* p) {
|
||||
|
||||
}
|
||||
|
||||
void CM_DRIVE_POWER(void* p) {
|
||||
|
||||
}
|
||||
|
||||
void CM_STEERING_SETUP(void* p) {
|
||||
|
||||
}
|
||||
|
||||
void CM_STEERING_SET(void* p) {
|
||||
|
||||
}
|
||||
|
||||
void CM_SETUP_CONTROL(void* p) {
|
||||
|
||||
}
|
40
306-controller_interface.X/app/can_message.h
Normal file
40
306-controller_interface.X/app/can_message.h
Normal file
@ -0,0 +1,40 @@
|
||||
/**
|
||||
* @author Rémi Heredero
|
||||
* @version 1.0.0
|
||||
* @date August 2023
|
||||
* @file can_message.h
|
||||
*/
|
||||
|
||||
#ifndef CAN_MESSAGE_H
|
||||
#define CAN_MESSAGE_H
|
||||
|
||||
|
||||
/*
|
||||
S R M
|
||||
1 0 F CONTROL_ALIVE - - - -
|
||||
1 2 0 JOY_SETUP Mode Param1 Param2 aliveTime
|
||||
1 3 0 DISPLAY_SETUP reset - - aliveTime
|
||||
1 3 2 DISPLAY_SPEED valH valL - -
|
||||
1 3 3 DISPLAY_DIRECTION direction - - -
|
||||
1 4 0 DRIVE_SETUP Reset/init speedTime stopTime aliveTime
|
||||
1 4 1 DRIVE_POWER valH valL - -
|
||||
1 5 0 STEERING_SETUP Reset/init homing setCenter aliveTime
|
||||
1 5 1 STEERING_SET valHH valH valL valLL
|
||||
1 6 0 SETUP_CONTROL batteryVoltTime batteryCurrentTime batteryEnergyTime aliveTime
|
||||
*/
|
||||
|
||||
void CM_processIncome(uint8_t idSender, uint8_t idMsg, uint32_t data);
|
||||
void CM_CONTROLLER_ALIVE(void* p);
|
||||
void CM_JOY_SETUP(void* p);
|
||||
void CM_DISPLAY_SETUP(void* p);
|
||||
void CM_DISPLAY_SPEED(void* p);
|
||||
void CM_DISPLAY_DIRECTION(void* p);
|
||||
void CM_DRIVE_SETUP(void* p);
|
||||
void CM_DRIVE_POWER(void* p);
|
||||
void CM_STEERING_SETUP(void* p);
|
||||
void CM_STEERING_SET(void* p);
|
||||
void CM_SETUP_CONTROL(void* p);
|
||||
|
||||
|
||||
#endif /* CAN_MESSAGE_H */
|
||||
|
@ -23,20 +23,23 @@
|
||||
/*******************
|
||||
* MEMORY ADRESSES *
|
||||
*******************/
|
||||
#define MEMADD_CONTROL_STEERING_MODE 0x00
|
||||
#define MEMADD_CONTROL_ALIVE_TIME 0x01
|
||||
#define MEMADD_CONTROL_SPEED_FACTOR 0x02
|
||||
#define MEMADD_CONTROL_POWER_FACTOR 0x06
|
||||
#define MEMADD_CONTROL_STEERING_FACTOR 0x0A
|
||||
#define MEMADD_CONTROL_MAX_SPEED_FW 0x0E
|
||||
#define MEMADD_CONTROL_MAX_SPEED_BW 0x0F
|
||||
#define MEMADD_JOYSTICK_ALIVE_TIME 0x10
|
||||
#define MEMADD_DISPLAY_ALIVE_TIME 0x11
|
||||
#define MEMADD_DRIVE_SPEED_TIME 0x12
|
||||
#define MEMADD_DRIVE_STOP_TIME 0x13
|
||||
#define MEMADD_DRIVE_ALIVE_TIME 0x14
|
||||
#define MEMADD_STEERING_ALIVE_TIME 0x15
|
||||
#define MEMADD_BATTERY_ALIVE_TIME 0x16
|
||||
#define MEMADD_CONTROL_STEERING_MODE 0x01
|
||||
#define MEMADD_CONTROL_ALIVE_TIME 0x02
|
||||
#define MEMADD_CONTROL_SPEED_FACTOR 0x03
|
||||
#define MEMADD_CONTROL_POWER_FACTOR 0x07
|
||||
#define MEMADD_CONTROL_STEERING_FACTOR 0x0B
|
||||
#define MEMADD_CONTROL_MAX_SPEED_FW 0x0F
|
||||
#define MEMADD_CONTROL_MAX_SPEED_BW 0x10
|
||||
#define MEMADD_JOYSTICK_MODE 0x11
|
||||
#define MEMADD_JOYSTICK_PARAM1 0x12
|
||||
#define MEMADD_JOYSTICK_PARAM2 0x13
|
||||
#define MEMADD_JOYSTICK_ALIVE_TIME 0x14
|
||||
#define MEMADD_DISPLAY_ALIVE_TIME 0x
|
||||
#define MEMADD_DRIVE_SPEED_TIME 0x
|
||||
#define MEMADD_DRIVE_STOP_TIME 0x
|
||||
#define MEMADD_DRIVE_ALIVE_TIME 0x
|
||||
#define MEMADD_STEERING_ALIVE_TIME 0x
|
||||
#define MEMADD_BATTERY_ALIVE_TIME 0x
|
||||
|
||||
typedef struct {
|
||||
uint8_t CONTROL_STEERING_MODE;
|
||||
@ -46,6 +49,10 @@ typedef struct {
|
||||
uint32_t CONTROL_STEERING_FACTOR;
|
||||
uint8_t CONTROL_MAX_SPEED_FW;
|
||||
uint8_t CONTROL_MAX_SPEED_BW;
|
||||
|
||||
uint8_t JOYSTICK_MODE;
|
||||
uint8_t JOYSTICK_PARAM1;
|
||||
uint8_t JOYSTICK_PARAM2;
|
||||
uint8_t JOYSTICK_ALIVE_TIME;
|
||||
uint8_t DISPLAY_ALIVE_TIME;
|
||||
uint8_t DRIVE_SPEED_TIME;
|
||||
|
@ -30,6 +30,14 @@ LED* l8() {
|
||||
return &theFactory.l8_;
|
||||
}
|
||||
|
||||
WATCHDOG* WDcontroller(){
|
||||
return &theFactory.WDcontroller_;
|
||||
}
|
||||
|
||||
ALIVE_CHECKER* ACjoy() {
|
||||
return &theFactory.ACjoy_;
|
||||
}
|
||||
|
||||
|
||||
//initialize all objects
|
||||
void Factory_init() {
|
||||
@ -54,24 +62,41 @@ void Factory_init() {
|
||||
CAN_init();
|
||||
CAN_setSender(1);
|
||||
LED_off(l1());
|
||||
}
|
||||
|
||||
void foo(uint8_t a, uint8_t b, uint32_t c){
|
||||
if(b){
|
||||
LED_on(l1());
|
||||
} else {
|
||||
LED_off(l1());
|
||||
}
|
||||
CAN_Send(a, b, c);
|
||||
|
||||
// TODO init EPROM interface
|
||||
|
||||
// TODO init watchdog with EPROM CST
|
||||
WATCHDOG_init(WDcontroller());
|
||||
CAR_CST.CONTROL_ALIVE_TIME = 100;
|
||||
WATCHDOG_setTime(WDcontroller(), CAR_CST.CONTROL_ALIVE_TIME);
|
||||
|
||||
// TODO init ALIVE CHECKER with EPROM CST
|
||||
CAR_CST.JOYSTICK_MODE = 0;
|
||||
CAR_CST.JOYSTICK_PARAM1 = 100;
|
||||
CAR_CST.JOYSTICK_PARAM2 = 1;
|
||||
CAR_CST.JOYSTICK_ALIVE_TIME = 10;
|
||||
ALIVE_CHECKER_init(ACjoy());
|
||||
}
|
||||
|
||||
//connect objects if required
|
||||
void Factory_build() {
|
||||
ECAN_SetRXBnInterruptHandler(CAN_newMsg);
|
||||
CAN_onReceiveCan(foo);
|
||||
CAN_onReceiveCan(CM_processIncome);
|
||||
|
||||
WATCHDOG_onAlive(WDcontroller(), CM_CONTROLLER_ALIVE, NULL);
|
||||
ALIVE_CHECKER_onSetup(ACjoy(), CM_JOY_SETUP, NULL);
|
||||
ALIVE_CHECKER_setAliveTime(ACjoy(), CAR_CST.JOYSTICK_ALIVE_TIME);
|
||||
ALIVE_CHECKER_onBorn(ACjoy(), LED_on, l1());
|
||||
ALIVE_CHECKER_onDead(ACjoy(), LED_off, l1());
|
||||
|
||||
}
|
||||
|
||||
//start all state machines
|
||||
void Factory_start() {
|
||||
CAN_startBehaviour();
|
||||
WATCHDOG_startBehaviour(WDcontroller());
|
||||
ALIVE_CHECKER_startBehaviour(ACjoy());
|
||||
ALIVE_CHECKER_emitBorn(ACjoy(), 100, 0);
|
||||
ALIVE_CHECKER_emitReady(ACjoy(), 200, 0);
|
||||
|
||||
}
|
||||
|
@ -12,9 +12,13 @@
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "../car.h"
|
||||
#include "../can_message.h"
|
||||
#include "../../board/led/led.h"
|
||||
#include "../../board/button/button.h"
|
||||
#include "../../middleware/alive_checker.h"
|
||||
#include "../../middleware/can_interface.h"
|
||||
#include "../../middleware/watchdog.h"
|
||||
|
||||
|
||||
typedef struct {
|
||||
@ -26,6 +30,9 @@ typedef struct {
|
||||
LED l6_;
|
||||
LED l7_;
|
||||
LED l8_;
|
||||
|
||||
WATCHDOG WDcontroller_;
|
||||
ALIVE_CHECKER ACjoy_;
|
||||
|
||||
} Factory;
|
||||
|
||||
@ -44,5 +51,8 @@ LED* l6();
|
||||
LED* l7();
|
||||
LED* l8();
|
||||
|
||||
WATCHDOG* WDcontroller();
|
||||
ALIVE_CHECKER* ACjoy();
|
||||
|
||||
|
||||
#endif
|
@ -56,6 +56,7 @@ bool ALIVE_CHECKER_processEvent(Event* ev) {
|
||||
} else {
|
||||
me->state = STAC_DEAD;
|
||||
}
|
||||
me->isAlive = false;
|
||||
}
|
||||
break;
|
||||
|
||||
@ -101,7 +102,6 @@ bool ALIVE_CHECKER_processEvent(Event* ev) {
|
||||
break;
|
||||
|
||||
case STAC_WAIT:
|
||||
me->isAlive = false;
|
||||
if (me->wait.f != NULL) {
|
||||
me->wait.f(me->wait.p);
|
||||
}
|
||||
@ -168,7 +168,7 @@ void ALIVE_CHECKER_setAliveTime(ALIVE_CHECKER* me, uint8_t v) {
|
||||
}
|
||||
|
||||
void ALIVE_CHECKER_setIsAlive(ALIVE_CHECKER* me, bool v) {
|
||||
me->aliveTime = v;
|
||||
me->isAlive = v;
|
||||
}
|
||||
|
||||
void ALIVE_CHECKER_ISALIVE(ALIVE_CHECKER* me) {
|
||||
|
@ -92,13 +92,13 @@ bool CAN_processEvent(Event* ev) {
|
||||
canMsg.frame.idType = dSTANDARD_CAN_MSG_ID_2_0B; // standard
|
||||
canMsg.frame.dlc = 4; // 4 bytes to send
|
||||
canMsg.frame.rtr = 0; // no remote frame
|
||||
canMsg.frame.data3 = (uint8_t) data;
|
||||
data = data >> 8;
|
||||
canMsg.frame.data2 = (uint8_t) data;
|
||||
canMsg.frame.data0 = (uint8_t) data;
|
||||
data = data >> 8;
|
||||
canMsg.frame.data1 = (uint8_t) data;
|
||||
data = data >> 8;
|
||||
canMsg.frame.data0 = (uint8_t) data;
|
||||
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);
|
||||
|
90
306-controller_interface.X/middleware/watchdog.c
Normal file
90
306-controller_interface.X/middleware/watchdog.c
Normal file
@ -0,0 +1,90 @@
|
||||
/**
|
||||
* @author Rémi Heredero
|
||||
* @version 1.0.0
|
||||
* @date August 2023
|
||||
* @file watchdog.c
|
||||
*/
|
||||
|
||||
#include "watchdog.h"
|
||||
|
||||
void WATCHDOG_init(WATCHDOG* me){
|
||||
me->state = STWD_INIT;
|
||||
me->time = 10;
|
||||
me->alive.f = NULL;
|
||||
}
|
||||
|
||||
void WATCHDOG_startBehaviour(WATCHDOG* me){
|
||||
POST(me, &WATCHDOG_processEvent, evWDinit, 0, 0);
|
||||
}
|
||||
|
||||
bool WATCHDOG_processEvent(Event* ev) {
|
||||
bool processed = false;
|
||||
WATCHDOG* me = (WATCHDOG*)Event_getTarget(ev);
|
||||
WATCHDOG_STATES oldState = me->state;
|
||||
evIDT evid = Event_getId(ev);
|
||||
uint64_t data = Event_getData(ev);
|
||||
|
||||
switch (me->state) { // onState
|
||||
case STWD_INIT:
|
||||
if (ev->id == evWDinit) {
|
||||
me->state = STWD_ALIVE;
|
||||
WATCHDOG_emitPoll(me, 10*me->time, 0);
|
||||
}
|
||||
break;
|
||||
|
||||
case STWD_ALIVE:
|
||||
if (ev->id == evWDpoll) {
|
||||
WATCHDOG_emitPoll(me, 10*me->time, 0);
|
||||
if (me->alive.f != NULL) {
|
||||
me->alive.f(me->alive.p);
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
if(oldState != me->state){
|
||||
switch (oldState) { // onExit
|
||||
case STWD_INIT:
|
||||
break;
|
||||
|
||||
case STWD_ALIVE:
|
||||
break;
|
||||
}
|
||||
|
||||
switch (me->state) { // onEntry
|
||||
case STWD_INIT:
|
||||
break;
|
||||
|
||||
case STWD_ALIVE:
|
||||
break;
|
||||
}
|
||||
|
||||
processed = true;
|
||||
}
|
||||
return processed;
|
||||
}
|
||||
|
||||
/*************
|
||||
* Callbacks *
|
||||
*************/
|
||||
|
||||
void WATCHDOG_onAlive(WATCHDOG* me, WATCHDOG_CALLBACK_FUNCTION f, void* p) {
|
||||
me->alive.f = f;
|
||||
me->alive.p = p;
|
||||
}
|
||||
|
||||
/************
|
||||
* EMITTERS *
|
||||
************/
|
||||
|
||||
void WATCHDOG_emitPoll(WATCHDOG* me, uint16_t t, int64_t data) {
|
||||
POST(me, &WATCHDOG_processEvent, evWDpoll, t, data);
|
||||
}
|
||||
|
||||
/***********
|
||||
* SETTERS *
|
||||
***********/
|
||||
|
||||
void WATCHDOG_setTime(WATCHDOG* me, uint8_t v) {
|
||||
me->time = v;
|
||||
}
|
83
306-controller_interface.X/middleware/watchdog.h
Normal file
83
306-controller_interface.X/middleware/watchdog.h
Normal file
@ -0,0 +1,83 @@
|
||||
/**
|
||||
* @author Rémi Heredero
|
||||
* @version 1.0.0
|
||||
* @date August 2023
|
||||
* @file watchdog.h
|
||||
*/
|
||||
#ifndef WATCHDOG_H
|
||||
#define WATCHDOG_H
|
||||
|
||||
#include "../xf/xf.h"
|
||||
|
||||
typedef enum {
|
||||
STWD_INIT,
|
||||
STWD_ALIVE
|
||||
} WATCHDOG_STATES;
|
||||
|
||||
typedef enum {
|
||||
evWDinit = 20,
|
||||
evWDpoll
|
||||
} WATCHDOG_EVENTS;
|
||||
|
||||
typedef void (*WATCHDOG_CALLBACK_FUNCTION)(void*);
|
||||
typedef struct {
|
||||
WATCHDOG_CALLBACK_FUNCTION f; // function
|
||||
void* p; // param(s)
|
||||
} WATCHDOG_CALLBACK;
|
||||
|
||||
typedef struct {
|
||||
WATCHDOG_STATES state;
|
||||
uint8_t time;
|
||||
WATCHDOG_CALLBACK alive;
|
||||
} WATCHDOG;
|
||||
|
||||
/**
|
||||
* Initialize the WATCHDOG
|
||||
* @param me the WATCHDOG itself
|
||||
*/
|
||||
void WATCHDOG_init(WATCHDOG* me);
|
||||
|
||||
/**
|
||||
* Start the WATCHDOG state machine
|
||||
* @param me the WATCHDOG itself
|
||||
*/
|
||||
void WATCHDOG_startBehaviour(WATCHDOG* me);
|
||||
|
||||
/**
|
||||
* Process the event
|
||||
* @param ev the event to process
|
||||
* @return true if the event is processed
|
||||
*/
|
||||
bool WATCHDOG_processEvent(Event* ev);
|
||||
|
||||
/*************
|
||||
* Callbacks *
|
||||
*************/
|
||||
|
||||
/**
|
||||
* Set the callback function to call when the WATCHDOG is entering state alive
|
||||
* @param me the WATCHDOG itself
|
||||
* @param f the function to call
|
||||
* @param p the param(s) to pass to the function
|
||||
*/
|
||||
void WATCHDOG_onAlive(WATCHDOG* me, WATCHDOG_CALLBACK_FUNCTION f, void* p);
|
||||
|
||||
/************
|
||||
* EMITTERS *
|
||||
************/
|
||||
|
||||
/**
|
||||
* Emit the poll event
|
||||
* @param me the WATCHDOG itself
|
||||
* @param t time to wait in ms before triggering event
|
||||
* @param data data to put on the event for XF
|
||||
*/
|
||||
void WATCHDOG_emitPoll(WATCHDOG* me, uint16_t t, int64_t data);
|
||||
|
||||
/***********
|
||||
* SETTERS *
|
||||
***********/
|
||||
|
||||
void WATCHDOG_setTime(WATCHDOG* me, uint8_t v);
|
||||
|
||||
#endif
|
@ -7,6 +7,7 @@
|
||||
<logicalFolder name="app" displayName="app" projectFiles="true">
|
||||
<itemPath>app/factory/factory.h</itemPath>
|
||||
<itemPath>app/car.h</itemPath>
|
||||
<itemPath>app/can_message.h</itemPath>
|
||||
</logicalFolder>
|
||||
<logicalFolder name="board" displayName="board" projectFiles="true">
|
||||
<itemPath>board/led/led.h</itemPath>
|
||||
@ -25,6 +26,7 @@
|
||||
<logicalFolder name="middleware" displayName="middleware" projectFiles="true">
|
||||
<itemPath>middleware/can_interface.h</itemPath>
|
||||
<itemPath>middleware/alive_checker.h</itemPath>
|
||||
<itemPath>middleware/watchdog.h</itemPath>
|
||||
</logicalFolder>
|
||||
<logicalFolder name="xf" displayName="xf" projectFiles="true">
|
||||
<itemPath>xf/event.h</itemPath>
|
||||
@ -41,6 +43,7 @@
|
||||
projectFiles="true">
|
||||
<logicalFolder name="app" displayName="app" projectFiles="true">
|
||||
<itemPath>app/factory/factory.c</itemPath>
|
||||
<itemPath>app/can_message.c</itemPath>
|
||||
</logicalFolder>
|
||||
<logicalFolder name="board" displayName="board" projectFiles="true">
|
||||
<itemPath>board/led/led.c</itemPath>
|
||||
@ -59,6 +62,7 @@
|
||||
<logicalFolder name="middleware" displayName="middleware" projectFiles="true">
|
||||
<itemPath>middleware/can_interface.c</itemPath>
|
||||
<itemPath>middleware/alive_checker.c</itemPath>
|
||||
<itemPath>middleware/watchdog.c</itemPath>
|
||||
</logicalFolder>
|
||||
<logicalFolder name="xf" displayName="xf" projectFiles="true">
|
||||
<itemPath>xf/event.c</itemPath>
|
||||
@ -91,7 +95,7 @@
|
||||
<platform>3</platform>
|
||||
</toolsSet>
|
||||
<packs>
|
||||
<pack name="PIC18F-K_DFP" vendor="Microchip" version="1.5.114"/>
|
||||
<pack name="PIC18F-K_DFP" vendor="Microchip" version="1.7.134"/>
|
||||
</packs>
|
||||
<ScriptingSettings>
|
||||
</ScriptingSettings>
|
||||
@ -210,7 +214,6 @@
|
||||
<property key="debugoptions.debug-startup" value="Use system settings"/>
|
||||
<property key="debugoptions.reset-behaviour" value="Use system settings"/>
|
||||
<property key="debugoptions.useswbreakpoints" value="false"/>
|
||||
<property key="firmware.download.all" value="false"/>
|
||||
<property key="hwtoolclock.frcindebug" value="false"/>
|
||||
<property key="memories.aux" value="false"/>
|
||||
<property key="memories.bootflash" value="true"/>
|
||||
@ -296,12 +299,15 @@
|
||||
</XC8-CO>
|
||||
<XC8-config-global>
|
||||
<property key="advanced-elf" value="true"/>
|
||||
<property key="constdata-progmem" value="true"/>
|
||||
<property key="gcc-opt-driver-new" value="true"/>
|
||||
<property key="gcc-opt-std" value="-std=c99"/>
|
||||
<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-new" value="1"/>
|
||||
<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-low" value="auto"/>
|
||||
<property key="stack-size-main" value="auto"/>
|
||||
|
File diff suppressed because one or more lines are too long
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>
|
588
busmaster_config.cfx
Normal file
588
busmaster_config.cfx
Normal file
@ -0,0 +1,588 @@
|
||||
<?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>FALSE</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>655</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>
|
||||
<J1939_Database_Files/>
|
||||
<CAN_DIL_Section>
|
||||
<DriverName>MHS Tiny-CAN</DriverName>
|
||||
<ControllerMode>Bus Off</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_Signal_Watch>
|
||||
<Message>
|
||||
<Id>288</Id>
|
||||
<Signal>DeltaY</Signal>
|
||||
<Signal>aliveTime</Signal>
|
||||
<Signal>timeMeasureOrDeltaX</Signal>
|
||||
<Signal>mode</Signal>
|
||||
</Message>
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>HIDE</WindowPlacement>
|
||||
<Top>622</Top>
|
||||
<Left>86</Left>
|
||||
<Right>816</Right>
|
||||
<Bottom>998</Bottom>
|
||||
</Window_Position>
|
||||
<COLUMN_WIDTH>
|
||||
<MESSAGE_COLUMN>142</MESSAGE_COLUMN>
|
||||
<Raw_Val_Column>174</Raw_Val_Column>
|
||||
<Physical_Val_Column>285</Physical_Val_Column>
|
||||
<Signal_Column>142</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>87</MESSAGE_COLUMN>
|
||||
<Raw_Val_Column>87</Raw_Val_Column>
|
||||
<Physical_Val_Column>174</Physical_Val_Column>
|
||||
<Signal_Column>87</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>87</MESSAGE_COLUMN>
|
||||
<Raw_Val_Column>87</Raw_Val_Column>
|
||||
<Physical_Val_Column>174</Physical_Val_Column>
|
||||
<Signal_Column>87</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>
|
||||
<Window_Position>
|
||||
<Visibility>HIDE</Visibility>
|
||||
<Window_Position>HIDE</Window_Position>
|
||||
<Top>-1</Top>
|
||||
<Left>0</Left>
|
||||
<Bottom>0</Bottom>
|
||||
<Right>0</Right>
|
||||
</Window_Position>
|
||||
<Splitter_Window_Col_0>
|
||||
<CxIdeal>-1</CxIdeal>
|
||||
<CxMin>0</CxMin>
|
||||
</Splitter_Window_Col_0>
|
||||
<Splitter_Window_Col_1>
|
||||
<CxIdeal>0</CxIdeal>
|
||||
<CxMin>0</CxMin>
|
||||
</Splitter_Window_Col_1>
|
||||
<Splitter_Window_Row_0>
|
||||
<CxIdeal>0</CxIdeal>
|
||||
<CxMin>0</CxMin>
|
||||
</Splitter_Window_Row_0>
|
||||
<Splitter_Window_Row_1>
|
||||
<CxIdeal>0</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>HIDE</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>0</Top>
|
||||
<Left>0</Left>
|
||||
<Bottom>0</Bottom>
|
||||
<Right>0</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>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>138</Width>
|
||||
</COLUMN>
|
||||
<COLUMN>
|
||||
<ID>Tx/Rx</ID>
|
||||
<Order>3</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>85</Width>
|
||||
</COLUMN>
|
||||
<COLUMN>
|
||||
<ID>Channel</ID>
|
||||
<Order>4</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>92</Width>
|
||||
</COLUMN>
|
||||
<COLUMN>
|
||||
<ID>Msg Type</ID>
|
||||
<Order>5</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>71</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>174</Width>
|
||||
</COLUMN>
|
||||
<COLUMN>
|
||||
<ID>DLC</ID>
|
||||
<Order>8</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>75</Width>
|
||||
</COLUMN>
|
||||
<COLUMN>
|
||||
<ID>Data Byte(s)</ID>
|
||||
<Order>9</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>198</Width>
|
||||
</COLUMN>
|
||||
<IsHex>1</IsHex>
|
||||
<IsAppend>0</IsAppend>
|
||||
<IsInterpret>0</IsInterpret>
|
||||
<Time_Mode>SYSTEM</Time_Mode>
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>0</Top>
|
||||
<Left>0</Left>
|
||||
<Bottom>295</Bottom>
|
||||
<Right>909</Right>
|
||||
</Window_Position>
|
||||
<Interpretation_Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>271</Top>
|
||||
<Left>879</Left>
|
||||
<Bottom>958</Bottom>
|
||||
<Right>1552</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>720</Width>
|
||||
</COLUMN>
|
||||
<IsHex>1</IsHex>
|
||||
<IsAppend>0</IsAppend>
|
||||
<IsInterpret>0</IsInterpret>
|
||||
<Time_Mode>SYSTEM</Time_Mode>
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>0</Top>
|
||||
<Left>0</Left>
|
||||
<Bottom>543</Bottom>
|
||||
<Right>1614</Right>
|
||||
</Window_Position>
|
||||
<Interpretation_Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>179</Top>
|
||||
<Left>10</Left>
|
||||
<Bottom>457</Bottom>
|
||||
<Right>359</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>734</Width>
|
||||
</COLUMN>
|
||||
<IsHex>1</IsHex>
|
||||
<IsAppend>0</IsAppend>
|
||||
<IsInterpret>0</IsInterpret>
|
||||
<Time_Mode>SYSTEM</Time_Mode>
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>0</Top>
|
||||
<Left>0</Left>
|
||||
<Bottom>543</Bottom>
|
||||
<Right>1614</Right>
|
||||
</Window_Position>
|
||||
<Interpretation_Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>179</Top>
|
||||
<Left>10</Left>
|
||||
<Bottom>457</Bottom>
|
||||
<Right>359</Right>
|
||||
</Interpretation_Window_Position>
|
||||
</LIN_Message_Window>
|
||||
<CAN_Tx_Window>
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>SETMINPOSITION</WindowPlacement>
|
||||
<Top>12</Top>
|
||||
<Left>989</Left>
|
||||
<Bottom>667</Bottom>
|
||||
<Right>1849</Right>
|
||||
</Window_Position>
|
||||
<Message_List>
|
||||
<Message>
|
||||
<Channel>1</Channel>
|
||||
<Message_ID>528</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>529</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>288</Message_ID>
|
||||
<IsExtended>FALSE</IsExtended>
|
||||
<IsRtr>FALSE</IsRtr>
|
||||
<DLC>4</DLC>
|
||||
<DataBytes>0,255,1,5</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>543</Message_ID>
|
||||
<IsExtended>FALSE</IsExtended>
|
||||
<IsRtr>FALSE</IsRtr>
|
||||
<DLC>1</DLC>
|
||||
<DataBytes>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>
|
Reference in New Issue
Block a user