Compare commits
9 Commits
4d10355dd4
...
10de77fbb0
Author | SHA1 | Date | |
---|---|---|---|
10de77fbb0 | |||
a04b19b081 | |||
df63ece978 | |||
3777d8bd12 | |||
c2c1104297 | |||
73b5594786 | |||
09fb1d10da | |||
c7c67d2931 | |||
1fa34dea8a |
@ -196,8 +196,10 @@ void CM_processIncome(uint8_t idSender, uint8_t idMsg, bool rtr, uint32_t data){
|
||||
// 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
|
||||
@ -226,7 +228,8 @@ void CM_processIncome(uint8_t idSender, uint8_t idMsg, bool rtr, uint32_t data){
|
||||
// TODO display say ALIVE
|
||||
eKart.powerMode = incomeData.separate.byte0;
|
||||
if (eKart.powerMode == 0) {
|
||||
CM_HEADLIGHTS(&ALWAYSFALSE);
|
||||
// CM_HEADLIGHTS(&ALWAYSFALSE);
|
||||
CM_HEADLIGHTS(&ALWAYSTRUE);
|
||||
} else {
|
||||
CM_HEADLIGHTS(&ALWAYSTRUE);
|
||||
}
|
||||
@ -303,6 +306,10 @@ void CM_processIncome(uint8_t idSender, uint8_t idMsg, bool rtr, uint32_t data){
|
||||
* SUPPLY *
|
||||
**********/
|
||||
case 6:
|
||||
if(idMsg == 0x1) {
|
||||
eKart.batteryVoltage = incomeData.full;
|
||||
}
|
||||
|
||||
if(idMsg == 0x4) {
|
||||
DRIVE_startBehaviour(drive());
|
||||
STEERING_startBehaviour(steering());
|
||||
|
@ -84,22 +84,11 @@ 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
|
||||
*
|
||||
*
|
||||
*/
|
||||
uint8_t powerMode;
|
||||
uint16_t batteryVoltage;
|
||||
} KART_VAR_TYPE;
|
||||
KART_VAR_TYPE eKart;
|
||||
|
||||
|
@ -24,7 +24,7 @@ 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 = 50; // should be 50
|
||||
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
|
||||
|
@ -42,7 +42,7 @@ void Factory_init() {
|
||||
MEM_init();
|
||||
initRamp();
|
||||
|
||||
ALIVE_init(ALcontroller(), 6);
|
||||
ALIVE_init(ALcontroller(), 5);
|
||||
ALIVE_setAliveTime(ALcontroller(), KART_CST.CONTROL_ALIVE_TIME);
|
||||
|
||||
ALIVE_init(ALjoy(), 1);
|
||||
|
@ -1,5 +1,5 @@
|
||||
/**
|
||||
* @author Rémi Heredero
|
||||
* @author R<EFBFBD>mi Heredero
|
||||
* @version. 0.0.0
|
||||
* @date August 2023
|
||||
* @file kartculator.c
|
||||
@ -237,6 +237,16 @@ void calcTorque(uint8_t joy_pos) {
|
||||
|
||||
calcTorque *= KART_CST.CONTROL_POWER_FACTOR; // convert by power factor
|
||||
calcTorque /= 1000; // torque define by joystick
|
||||
|
||||
if(eKart.button) {
|
||||
calcTorque *= 1150;
|
||||
calcTorque /= 1000;
|
||||
}
|
||||
|
||||
if(eKart.batteryVoltage <= 18750) {
|
||||
calcTorque = 0;
|
||||
}
|
||||
|
||||
eKart.torque = (int16_t) calcTorque;
|
||||
}
|
||||
|
||||
|
@ -124,8 +124,8 @@ void ECAN_Initialize(void)
|
||||
// filter 1 is message for controller
|
||||
convertCANid2Reg(0x010, dSTANDARD_CAN_MSG_ID_2_0B, &RXF1EIDH, &RXF1EIDL, &RXF1SIDH, &RXF1SIDL);
|
||||
|
||||
// filter 2 is message for recipient n°7, not yet defined
|
||||
convertCANid2Reg(0x070, dSTANDARD_CAN_MSG_ID_2_0B, &RXF2EIDH, &RXF2EIDL, &RXF2SIDH, &RXF2SIDL);
|
||||
// filter 2 is message for display (yes i want the message from the display)
|
||||
convertCANid2Reg(0x060, dSTANDARD_CAN_MSG_ID_2_0B, &RXF2EIDH, &RXF2EIDL, &RXF2SIDH, &RXF2SIDL);
|
||||
|
||||
/*
|
||||
* ENABLE FILTERS
|
||||
|
@ -454,7 +454,7 @@ endif
|
||||
# Enable dependency checking
|
||||
.dep.inc: .depcheck-impl
|
||||
|
||||
DEPFILES=$(wildcard ${POSSIBLE_DEPFILES})
|
||||
DEPFILES=$(shell mplabwildcard ${POSSIBLE_DEPFILES})
|
||||
ifneq (${DEPFILES},)
|
||||
include ${DEPFILES}
|
||||
endif
|
||||
|
@ -15,11 +15,11 @@
|
||||
# $ 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/
|
||||
PATH_TO_IDE_BIN=C:/Program Files/Microchip/MPLABX/v6.05/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:=C:/Program Files/Microchip/MPLABX/v6.05/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/"
|
||||
MP_JAVA_PATH="C:\Program Files\Microchip\MPLABX\v6.05\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
|
||||
@ -27,11 +27,11 @@ MP_CC="C:\Program Files\Microchip\xc8\v2.41\bin\xc8-cc.exe"
|
||||
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"
|
||||
DEP_GEN=${MP_JAVA_PATH}java -jar "C:/Program Files/Microchip/MPLABX/v6.05/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
|
||||
DFP_DIR=C:/Users/remi/.mchp_packs/Microchip/PIC18F-K_DFP/1.11.281
|
||||
|
@ -247,7 +247,7 @@
|
||||
<property key="programoptions.preservedataflash" value="false"/>
|
||||
<property key="programoptions.preservedataflash.ranges"
|
||||
value="${programoptions.preservedataflash.ranges}"/>
|
||||
<property key="programoptions.preserveeeprom" value="true"/>
|
||||
<property key="programoptions.preserveeeprom" value="false"/>
|
||||
<property key="programoptions.preserveeeprom.ranges" value="310000-3103ff"/>
|
||||
<property key="programoptions.preserveprogram.ranges" value=""/>
|
||||
<property key="programoptions.preserveprogramrange" value="false"/>
|
||||
@ -295,7 +295,7 @@
|
||||
<property key="programoptions.preservedataflash" value="false"/>
|
||||
<property key="programoptions.preservedataflash.ranges"
|
||||
value="${programoptions.preservedataflash.ranges}"/>
|
||||
<property key="programoptions.preserveeeprom" value="true"/>
|
||||
<property key="programoptions.preserveeeprom" value="false"/>
|
||||
<property key="programoptions.preserveeeprom.ranges" value="310000-3103ff"/>
|
||||
<property key="programoptions.preserveprogram.ranges" value=""/>
|
||||
<property key="programoptions.preserveprogramrange" value="false"/>
|
||||
|
25
UML/full_sequence.puml
Normal file
25
UML/full_sequence.puml
Normal file
@ -0,0 +1,25 @@
|
||||
@startuml
|
||||
'https://plantuml.com/sequence-diagram
|
||||
|
||||
actor User as usr
|
||||
participant can_message as can
|
||||
control kartculator as kc
|
||||
queue XF as xf
|
||||
entity Drive as drive
|
||||
entity Steering as steering
|
||||
|
||||
usr -\ xf : set message "move"
|
||||
xf -> can : new value on joystick
|
||||
|
||||
== If X axis change value ==
|
||||
can -> kc : calculate new position
|
||||
kc -> can : build message
|
||||
can -> steering : set new position
|
||||
|
||||
== If Y axis change value ==
|
||||
can -> kc : calculate new torque
|
||||
kc -> can : build message
|
||||
can -> xf : set message "torque"
|
||||
xf -> drive : set new torque
|
||||
|
||||
@enduml
|
Before Width: | Height: | Size: 32 KiB After Width: | Height: | Size: 32 KiB |
BIN
UML/pdf-png/cas de test.pdf
Normal file
BIN
UML/pdf-png/cas de test.pdf
Normal file
Binary file not shown.
BIN
UML/pdf-png/full_sequence.png
Normal file
BIN
UML/pdf-png/full_sequence.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 29 KiB |
BIN
UML/pdf-png/session de test.pdf
Normal file
BIN
UML/pdf-png/session de test.pdf
Normal file
Binary file not shown.
BIN
UML/pdf-png/steering.pdf
Normal file
BIN
UML/pdf-png/steering.pdf
Normal file
Binary file not shown.
@ -1,74 +0,0 @@
|
||||
<?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>
|
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
@ -2,14 +2,14 @@
|
||||
<BUSMASTER_CONFIGURATION>
|
||||
<Global_Configuration>
|
||||
<BUSMASTER_Version>3.2.2</BUSMASTER_Version>
|
||||
<IsMsgFilterEnabled>TRUE</IsMsgFilterEnabled>
|
||||
<IsMsgFilterEnabled>FALSE</IsMsgFilterEnabled>
|
||||
<IsMsgFilterEnabledLin>FALSE</IsMsgFilterEnabledLin>
|
||||
<IsReplayFilterEnabled>FALSE</IsReplayFilterEnabled>
|
||||
<IsLogFilterEnabled>FALSE</IsLogFilterEnabled>
|
||||
<IsLogFilterLINEnabled>FALSE</IsLogFilterLINEnabled>
|
||||
<IsLoggingEnabled>FALSE</IsLoggingEnabled>
|
||||
<IsMsgIntepretationEnabled>TRUE</IsMsgIntepretationEnabled>
|
||||
<IsOverWriteEnabled>FALSE</IsOverWriteEnabled>
|
||||
<IsOverWriteEnabled>TRUE</IsOverWriteEnabled>
|
||||
<DisplayTimeMode>SYSTEM</DisplayTimeMode>
|
||||
<DisplayNumericMode>FALSE</DisplayNumericMode>
|
||||
<LogOnConnect_CAN>FALSE</LogOnConnect_CAN>
|
||||
@ -46,10 +46,10 @@
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>195</Top>
|
||||
<Left>426</Left>
|
||||
<Bottom>692</Bottom>
|
||||
<Right>848</Right>
|
||||
<Top>291</Top>
|
||||
<Left>403</Left>
|
||||
<Bottom>788</Bottom>
|
||||
<Right>825</Right>
|
||||
</Window_Position>
|
||||
</Bus_Statistics>
|
||||
<J1939_Database_Files/>
|
||||
@ -326,8 +326,8 @@
|
||||
<CAN_Signal_Watch>
|
||||
<Message>
|
||||
<Id>529</Id>
|
||||
<Signal>posX</Signal>
|
||||
<Signal>posY</Signal>
|
||||
<Signal>posX</Signal>
|
||||
</Message>
|
||||
<Message>
|
||||
<Id>1040</Id>
|
||||
@ -345,8 +345,14 @@
|
||||
<Id>337</Id>
|
||||
<Signal>SteeringPosition</Signal>
|
||||
</Message>
|
||||
<Message>
|
||||
<Id>1585</Id>
|
||||
<Signal>BatteryVoltage</Signal>
|
||||
</Message>
|
||||
<Message>
|
||||
<Id>1311</Id>
|
||||
<Signal>STAT_HOMING_ATTAINED</Signal>
|
||||
<Signal>STAT_HOMING_ERROR</Signal>
|
||||
</Message>
|
||||
<Message>
|
||||
<Id>1294</Id>
|
||||
@ -355,19 +361,23 @@
|
||||
<Message>
|
||||
<Id>1540</Id>
|
||||
</Message>
|
||||
<Message>
|
||||
<Id>260</Id>
|
||||
<Signal>headlights</Signal>
|
||||
</Message>
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<Visibility>SHOWMINIMIZED</Visibility>
|
||||
<WindowPlacement>HIDE</WindowPlacement>
|
||||
<Top>170</Top>
|
||||
<Left>421</Left>
|
||||
<Right>868</Right>
|
||||
<Bottom>731</Bottom>
|
||||
<Top>161</Top>
|
||||
<Left>610</Left>
|
||||
<Right>1057</Right>
|
||||
<Bottom>722</Bottom>
|
||||
</Window_Position>
|
||||
<COLUMN_WIDTH>
|
||||
<MESSAGE_COLUMN>144</MESSAGE_COLUMN>
|
||||
<Raw_Val_Column>86</Raw_Val_Column>
|
||||
<Physical_Val_Column>172</Physical_Val_Column>
|
||||
<Signal_Column>86</Signal_Column>
|
||||
<MESSAGE_COLUMN>0</MESSAGE_COLUMN>
|
||||
<Raw_Val_Column>0</Raw_Val_Column>
|
||||
<Physical_Val_Column>0</Physical_Val_Column>
|
||||
<Signal_Column>0</Signal_Column>
|
||||
</COLUMN_WIDTH>
|
||||
</CAN_Signal_Watch>
|
||||
<J1939_Signal_Watch>
|
||||
@ -413,17 +423,17 @@
|
||||
<Axis_Color>255</Axis_Color>
|
||||
<X_Grid_Lines>10</X_Grid_Lines>
|
||||
<Y_Grid_Lines>5</Y_Grid_Lines>
|
||||
<Active_Axis>2</Active_Axis>
|
||||
<Active_Axis>1</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>
|
||||
<Message_ID>1585</Message_ID>
|
||||
<Message_Name>DISPLAY_VOLTAGE</Message_Name>
|
||||
<Frame_Format/>
|
||||
<Element_Name>BatteryCurrent</Element_Name>
|
||||
<Value_Type>Physical</Value_Type>
|
||||
<Element_Name>BatteryVoltage</Element_Name>
|
||||
<Value_Type>Raw</Value_Type>
|
||||
<Line_Type>SOLID</Line_Type>
|
||||
<Line_Color>65280</Line_Color>
|
||||
<Point_Type>2</Point_Type>
|
||||
@ -435,10 +445,10 @@
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<Window_Position>HIDE</Window_Position>
|
||||
<Top>39</Top>
|
||||
<Left>74</Left>
|
||||
<Bottom>586</Bottom>
|
||||
<Right>1399</Right>
|
||||
<Top>11</Top>
|
||||
<Left>290</Left>
|
||||
<Bottom>558</Bottom>
|
||||
<Right>1615</Right>
|
||||
</Window_Position>
|
||||
<Splitter_Window_Col_0>
|
||||
<CxIdeal>479</CxIdeal>
|
||||
@ -498,19 +508,19 @@
|
||||
<Filter IsEnabled="0">steering</Filter>
|
||||
<COLUMN>
|
||||
<ID/>
|
||||
<Order>1</Order>
|
||||
<IsVisible>0</IsVisible>
|
||||
<Width>0</Width>
|
||||
<Order>5</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>19</Width>
|
||||
</COLUMN>
|
||||
<COLUMN>
|
||||
<ID>Time</ID>
|
||||
<Order>5</Order>
|
||||
<Order>4</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>129</Width>
|
||||
</COLUMN>
|
||||
<COLUMN>
|
||||
<ID>Tx/Rx</ID>
|
||||
<Order>4</Order>
|
||||
<Order>1</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>53</Width>
|
||||
</COLUMN>
|
||||
@ -548,11 +558,11 @@
|
||||
<ID>Data Byte(s)</ID>
|
||||
<Order>9</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>158</Width>
|
||||
<Width>139</Width>
|
||||
</COLUMN>
|
||||
<IsHex>1</IsHex>
|
||||
<IsAppend>1</IsAppend>
|
||||
<IsInterpret>0</IsInterpret>
|
||||
<IsAppend>0</IsAppend>
|
||||
<IsInterpret>1</IsInterpret>
|
||||
<Time_Mode>SYSTEM</Time_Mode>
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
@ -565,18 +575,18 @@
|
||||
<Interpretation_Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>181</Top>
|
||||
<Left>12</Left>
|
||||
<Bottom>459</Bottom>
|
||||
<Right>361</Right>
|
||||
<Top>179</Top>
|
||||
<Left>10</Left>
|
||||
<Bottom>457</Bottom>
|
||||
<Right>359</Right>
|
||||
</Interpretation_Window_Position>
|
||||
</CAN_Message_Window>
|
||||
<J1939_Message_Window>
|
||||
<COLUMN>
|
||||
<ID/>
|
||||
<Order>1</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>19</Width>
|
||||
<IsVisible>0</IsVisible>
|
||||
<Width>0</Width>
|
||||
</COLUMN>
|
||||
<COLUMN>
|
||||
<ID>Time</ID>
|
||||
@ -648,11 +658,11 @@
|
||||
<ID>Data Byte(s)</ID>
|
||||
<Order>13</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>643</Width>
|
||||
<Width>662</Width>
|
||||
</COLUMN>
|
||||
<IsHex>1</IsHex>
|
||||
<IsAppend>0</IsAppend>
|
||||
<IsInterpret>1</IsInterpret>
|
||||
<IsAppend>1</IsAppend>
|
||||
<IsInterpret>0</IsInterpret>
|
||||
<Time_Mode>SYSTEM</Time_Mode>
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
@ -665,10 +675,10 @@
|
||||
<Interpretation_Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>181</Top>
|
||||
<Left>12</Left>
|
||||
<Bottom>459</Bottom>
|
||||
<Right>361</Right>
|
||||
<Top>179</Top>
|
||||
<Left>10</Left>
|
||||
<Bottom>457</Bottom>
|
||||
<Right>359</Right>
|
||||
</Interpretation_Window_Position>
|
||||
</J1939_Message_Window>
|
||||
<LIN_Message_Window>
|
||||
@ -678,8 +688,8 @@
|
||||
<COLUMN>
|
||||
<ID/>
|
||||
<Order>1</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>19</Width>
|
||||
<IsVisible>0</IsVisible>
|
||||
<Width>0</Width>
|
||||
</COLUMN>
|
||||
<COLUMN>
|
||||
<ID>Time</ID>
|
||||
@ -733,11 +743,11 @@
|
||||
<ID>Checksum</ID>
|
||||
<Order>10</Order>
|
||||
<IsVisible>1</IsVisible>
|
||||
<Width>657</Width>
|
||||
<Width>676</Width>
|
||||
</COLUMN>
|
||||
<IsHex>1</IsHex>
|
||||
<IsAppend>0</IsAppend>
|
||||
<IsInterpret>1</IsInterpret>
|
||||
<IsAppend>1</IsAppend>
|
||||
<IsInterpret>0</IsInterpret>
|
||||
<Time_Mode>SYSTEM</Time_Mode>
|
||||
<Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
@ -750,20 +760,20 @@
|
||||
<Interpretation_Window_Position>
|
||||
<Visibility>SHOWNORMAL</Visibility>
|
||||
<WindowPlacement>RESTORETOMAXIMIZED</WindowPlacement>
|
||||
<Top>181</Top>
|
||||
<Left>12</Left>
|
||||
<Bottom>459</Bottom>
|
||||
<Right>361</Right>
|
||||
<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>4</Top>
|
||||
<Left>648</Left>
|
||||
<Bottom>659</Bottom>
|
||||
<Right>1508</Right>
|
||||
<Top>-1</Top>
|
||||
<Left>1035</Left>
|
||||
<Bottom>654</Bottom>
|
||||
<Right>1895</Right>
|
||||
</Window_Position>
|
||||
<Message_List>
|
||||
<Message>
|
||||
@ -886,6 +896,42 @@
|
||||
<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>
|
||||
|
@ -6,7 +6,7 @@
|
||||
|
||||
[BUSMASTER_VERSION] [3.2.2]
|
||||
|
||||
[NUMBER_OF_MESSAGES] 32
|
||||
[NUMBER_OF_MESSAGES] 33
|
||||
|
||||
[START_MSG] JOY_MEASURE,529,3,3,1,S
|
||||
[START_SIGNALS] posX,8,1,0,I,127,-128,1,0.000000,1.000000,%,
|
||||
@ -188,3 +188,6 @@
|
||||
[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