improve ini selection robustness to prevent impossible selection according to mcu type etc.

allow canbus options to be chosen that were not previously available
This commit is contained in:
darren siepka 2018-09-23 22:50:15 +01:00
parent a5f4119715
commit 90420359f7
5 changed files with 676 additions and 402 deletions

File diff suppressed because it is too large Load Diff

View File

@ -17,10 +17,14 @@ void canCommand()
switch (currentcanCommand) switch (currentcanCommand)
{ {
case 'A': // sends the bytes of realtime values case 'A': // sends the bytes of realtime values from the CAN list
sendcanValues(0, CAN_PACKET_SIZE, 0x30, 1); //send values to serial3 sendcanValues(0, CAN_PACKET_SIZE, 0x30, 1); //send values to serial3
break; break;
//case 'A': // send x bytes of realtime values from the TS list
// sendValues(0, SERIAL_PACKET_SIZE, 0x30, 3); //send values to serial0
// break;
case 'G': // this is the reply command sent by the Can interface case 'G': // this is the reply command sent by the Can interface
byte destcaninchannel; byte destcaninchannel;
if (CANSerial.available() >= 9) if (CANSerial.available() >= 9)
@ -102,14 +106,14 @@ void canCommand()
} }
break; break;
case 'S': // send code version case 's': // send the "a" stream code version
for (unsigned int revn = 0; revn < sizeof( TSfirmwareVersion) - 1; revn++) CANSerial.write("Speeduino csx02018.7");
{
CANSerial.write( TSfirmwareVersion[revn]);
}
//Serial3.print("speeduino 201609-dev");
break; break;
case 'S': // send code version
CANSerial.write("Speeduino 2018.7-dev");
break;
case 'Q': // send code version case 'Q': // send code version
for (unsigned int revn = 0; revn < sizeof( TSfirmwareVersion) - 1; revn++) for (unsigned int revn = 0; revn < sizeof( TSfirmwareVersion) - 1; revn++)
{ {
@ -262,7 +266,7 @@ void sendCancommand(uint8_t cmdtype, uint16_t canaddress, uint8_t candata1, uint
break; break;
case 2: // requests via serial3 case 2: // requests via serial3
CANSerial.print("R"); //send "R" to request data from the parmagroup can address whos value is sent next CANSerial.print("R"); //send "R" to request data from the sourcecanAddress whos value is sent next
CANSerial.write(candata1); //the currentStatus.current_caninchannel CANSerial.write(candata1); //the currentStatus.current_caninchannel
CANSerial.write(lowByte(sourcecanAddress) ); //send lsb first CANSerial.write(lowByte(sourcecanAddress) ); //send lsb first
CANSerial.write(highByte(sourcecanAddress) ); CANSerial.write(highByte(sourcecanAddress) );

View File

@ -670,8 +670,9 @@ struct config6 {
//Page 9 of the config mostly deals with CANBUS control //Page 9 of the config mostly deals with CANBUS control
//See ini file for further info (Config Page 10 in the ini) //See ini file for further info (Config Page 10 in the ini)
struct config9 { struct config9 {
byte enable_canbus:2; byte enable_secondarySerial:1; //enable secondary serial
byte enable_candata_in:1; byte intcan_available:1; //enable internal can module
byte enable_intcan:1;
byte caninput_sel[16]; //bit status on/Can/analog_local/digtal_local if input is enabled byte caninput_sel[16]; //bit status on/Can/analog_local/digtal_local if input is enabled
uint16_t caninput_source_can_address[16]; //u16 [15] array holding can address of input uint16_t caninput_source_can_address[16]; //u16 [15] array holding can address of input
uint8_t caninput_source_start_byte[16]; //u08 [15] array holds the start byte number(value of 0-7) uint8_t caninput_source_start_byte[16]; //u08 [15] array holds the start byte number(value of 0-7)

View File

@ -56,23 +56,29 @@ void initialiseADC()
auxIsEnabled = false; auxIsEnabled = false;
for (byte AuxinChan = 0; AuxinChan <16 ; AuxinChan++) for (byte AuxinChan = 0; AuxinChan <16 ; AuxinChan++)
{ {
currentStatus.current_caninchannel = AuxinChan; currentStatus.current_caninchannel = AuxinChan;
//currentStatus.canin[14] = ((configPage9.Auxinpinb[currentStatus.current_caninchannel]&127)+1); if (((configPage9.caninput_sel[currentStatus.current_caninchannel]&12) == 4)
//currentStatus.canin[13] = (configPage9.caninput_sel[currentStatus.current_caninchannel]&3); && ((configPage9.enable_secondarySerial == 1) || ((configPage9.enable_intcan == 1) && (configPage9.intcan_available == 1))))
if ( (configPage9.caninput_sel[currentStatus.current_caninchannel] == 1) && (configPage9.enable_candata_in > 0) && (configPage9.enable_canbus == 1)) //if current input channel is enabled as canbus { //if current input channel is enabled as external input in caninput_selxb(bits 2:3) and secondary serial or internal canbus is enabled(and is mcu supported)
{ //currentStatus.canin[14] = 22; Dev test use only!
auxIsEnabled = true; auxIsEnabled = true;
} }
else if ((configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 2) //if current input channel is enabled as analog local pin else if ((((configPage9.enable_secondarySerial == 1) || ((configPage9.enable_intcan == 1) && (configPage9.intcan_available == 1))) && (configPage9.caninput_sel[currentStatus.current_caninchannel]&12) == 8)
{ || (((configPage9.enable_secondarySerial == 0) && (configPage9.enable_intcan == 1 && configPage9.intcan_available == 0 )) && (configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 2)
|| (((configPage9.enable_secondarySerial == 0) && (configPage9.enable_intcan == 0)) && ((configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 2)))
{ //if current input channel is enabled as analog local pin check caninput_selxb(bits 2:3) with &12 and caninput_selxa(bits 0:1) with &3
//Channel is active and analog //Channel is active and analog
pinMode( (configPage9.Auxinpina[currentStatus.current_caninchannel]&127), INPUT); pinMode( (configPage9.Auxinpina[currentStatus.current_caninchannel]&127), INPUT);
//currentStatus.canin[14] = 33; Dev test use only!
auxIsEnabled = true; auxIsEnabled = true;
} }
else if ((configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 3) //if current input channel is enabled as digital local pin else if ((((configPage9.enable_secondarySerial == 1) || ((configPage9.enable_intcan == 1) && (configPage9.intcan_available == 1))) && (configPage9.caninput_sel[currentStatus.current_caninchannel]&12) == 12)
{ || (((configPage9.enable_secondarySerial == 0) && (configPage9.enable_intcan == 1 && configPage9.intcan_available == 0 )) && (configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 3)
|| (((configPage9.enable_secondarySerial == 0) && (configPage9.enable_intcan == 0)) && ((configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 3)))
{ //if current input channel is enabled as digital local pin check caninput_selxb(bits 2:3) wih &12 and caninput_selxa(bits 0:1) with &3
//Channel is active and digital //Channel is active and digital
pinMode( (configPage9.Auxinpinb[currentStatus.current_caninchannel]&127), INPUT); pinMode( (configPage9.Auxinpinb[currentStatus.current_caninchannel]&127), INPUT);
//currentStatus.canin[14] = 44; Dev test use only!
auxIsEnabled = true; auxIsEnabled = true;
} }
} }

View File

@ -155,19 +155,19 @@ void setup()
configPage4.bootloaderCaps = 0; configPage4.bootloaderCaps = 0;
Serial.begin(115200); Serial.begin(115200);
if (configPage9.enable_canbus == 1) { CANSerial.begin(115200); } if (configPage9.enable_secondarySerial == 1) { CANSerial.begin(115200); }
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
configPage9.intcan_available = 0; // device does NOT have internal canbus
#endif
#if defined(CORE_STM32) || defined(CORE_TEENSY) #if defined(CORE_STM32) || defined(CORE_TEENSY)
else if (configPage9.enable_canbus == 2) configPage9.intcan_available = 1; // device has internal canbus
{
//Teensy onboard CAN not used currently //Teensy onboard CAN not used currently
//enable local can interface //enable local can interface
//setup can interface to 250k //setup can interface to 250k
//FlexCAN CANbus0(2500000, 0); //FlexCAN CANbus0(2500000, 0);
//static CAN_message_t txmsg,rxmsg; //static CAN_message_t txmsg,rxmsg;
//CANbus0.begin(); //CANbus0.begin();
}
#endif #endif
//Repoint the 2D table structs to the config pages that were just loaded //Repoint the 2D table structs to the config pages that were just loaded
@ -840,7 +840,7 @@ void loop()
if (Serial.available() > 0) { command(); } if (Serial.available() > 0) { command(); }
} }
//if can or secondary serial interface is enabled then check for requests. //if can or secondary serial interface is enabled then check for requests.
if (configPage9.enable_canbus == 1) //secondary serial interface enabled if (configPage9.enable_secondarySerial == 1) //secondary serial interface enabled
{ {
if ( ((mainLoopCount & 31) == 1) or (CANSerial.available() > SERIAL_BUFFER_THRESHOLD) ) if ( ((mainLoopCount & 31) == 1) or (CANSerial.available() > SERIAL_BUFFER_THRESHOLD) )
{ {
@ -848,7 +848,7 @@ void loop()
} }
} }
#if defined(CORE_TEENSY) || defined(CORE_STM32) #if defined(CORE_TEENSY) || defined(CORE_STM32)
else if (configPage9.enable_canbus == 2) // can module enabled else if (configPage9.enable_secondarySerial == 2) // can module enabled
{ {
//check local can module //check local can module
// if ( BIT_CHECK(LOOP_TIMER, BIT_TIMER_15HZ) or (CANbus0.available()) // if ( BIT_CHECK(LOOP_TIMER, BIT_TIMER_15HZ) or (CANbus0.available())
@ -1001,34 +1001,59 @@ void loop()
//check through the Aux input channels if enabed for Can or local use //check through the Aux input channels if enabed for Can or local use
for (byte AuxinChan = 0; AuxinChan <16 ; AuxinChan++) for (byte AuxinChan = 0; AuxinChan <16 ; AuxinChan++)
{ {
currentStatus.current_caninchannel = AuxinChan; currentStatus.current_caninchannel = AuxinChan;
//currentStatus.canin[14] = ((configPage9.Auxinpinb[currentStatus.current_caninchannel]&127)+1);
//Dev test use only!
//currentStatus.canin[13] = ((configPage9.Auxinpinb[currentStatus.current_caninchannel]&127)+1);
//currentStatus.canin[14] = (configPage9.caninput_sel[1]);
//currentStatus.canin[12] = (configPage9.caninput_sel[1]&12);
//currentStatus.canin[14] = configPage9.enable_secondarySerial; //> 0)((configPage9.Auxinpinb[currentStatus.current_caninchannel]&127)+1);
//currentStatus.canin[13] = (configPage9.caninput_sel[currentStatus.current_caninchannel]&3); //currentStatus.canin[13] = (configPage9.caninput_sel[currentStatus.current_caninchannel]&3);
if (configPage9.caninput_sel[currentStatus.current_caninchannel] == 1) //if current input channel is enabled as canbus
{ if (((configPage9.caninput_sel[currentStatus.current_caninchannel]&12) == 4)
if (configPage9.enable_candata_in > 0) //if external data input is enabled && (((configPage9.enable_secondarySerial == 1) && ((configPage9.enable_intcan == 0)&&(configPage9.intcan_available == 1)))
|| ((configPage9.enable_secondarySerial == 1) && ((configPage9.enable_intcan == 1)&&(configPage9.intcan_available == 1))&&
((configPage9.caninput_sel[currentStatus.current_caninchannel]&64) == 0))
|| ((configPage9.enable_secondarySerial == 1) && ((configPage9.enable_intcan == 1)&&(configPage9.intcan_available == 0)))))
{ //if current input channel is enabled as external & secondary serial enabled & internal can disabled(but internal can is available)
// or current input channel is enabled as external & secondary serial enabled & internal can enabled(and internal can is available)
//currentStatus.canin[13] = 11; Dev test use only!
if (configPage9.enable_secondarySerial == 1) // megas only support can via secondary serial
{ {
if (configPage9.enable_canbus == 1) // megas only support can via secondary serial sendCancommand(2,0,currentStatus.current_caninchannel,0,((configPage9.caninput_source_can_address[currentStatus.current_caninchannel]&2047)+0x100));
{ //send an R command for data from caninput_source_address[currentStatus.current_caninchannel] from CANSERIAL
sendCancommand(2,0,currentStatus.current_caninchannel,0,((configPage9.caninput_source_can_address[currentStatus.current_caninchannel]&2047)+0x100));
//send an R command for data from caninput_source_address[currentStatus.current_caninchannel]
}
#if defined(CORE_STM32) || defined(CORE_TEENSY)
else if (configPage9.enable_canbus == 2) // can via internal can module
{
sendCancommand(3,configPage9.speeduino_tsCanId,currentStatus.current_caninchannel,0,configPage9.caninput_source_can_address[currentStatus.current_caninchannel]); //send via localcanbus the command for data from paramgroup[currentStatus.current_caninchannel]
}
#endif
} }
} }
else if ((configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 2) //if current input channel is enabled as analog local pin else if (((configPage9.caninput_sel[currentStatus.current_caninchannel]&12) == 4)
{ && (((configPage9.enable_secondarySerial == 1) && ((configPage9.enable_intcan == 1)&&(configPage9.intcan_available == 1))&&
((configPage9.caninput_sel[currentStatus.current_caninchannel]&64) == 64))
|| ((configPage9.enable_secondarySerial == 0) && ((configPage9.enable_intcan == 1)&&(configPage9.intcan_available == 1))&&
((configPage9.caninput_sel[currentStatus.current_caninchannel]&128) == 128))))
{ //if current input channel is enabled as external for canbus & secondary serial enabled & internal can enabled(and internal can is available)
// or current input channel is enabled as external for canbus & secondary serial disabled & internal can enabled(and internal can is available)
//currentStatus.canin[13] = 12; Dev test use only!
#if defined(CORE_STM32) || defined(CORE_TEENSY)
if (configPage9.enable_intcan == 1) // if internal can is enabled
{
sendCancommand(3,configPage9.speeduino_tsCanId,currentStatus.current_caninchannel,0,((configPage9.caninput_source_can_address[currentStatus.current_caninchannel]&2047)+0x100));
//send an R command for data from caninput_source_address[currentStatus.current_caninchannel] from internal canbus
}
#endif
}
else if ((((configPage9.enable_secondarySerial == 1) || ((configPage9.enable_intcan == 1) && (configPage9.intcan_available == 1))) && (configPage9.caninput_sel[currentStatus.current_caninchannel]&12) == 8)
|| (((configPage9.enable_secondarySerial == 0) && (configPage9.enable_intcan == 1 && configPage9.intcan_available == 0 )) && (configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 2)
|| (((configPage9.enable_secondarySerial == 0) && (configPage9.enable_intcan == 0)) && ((configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 2)))
{ //if current input channel is enabled as analog local pin
//read analog channel specified //read analog channel specified
//currentStatus.canin[13] = 13; Dev test use only!
currentStatus.canin[currentStatus.current_caninchannel] = readAuxanalog(configPage9.Auxinpina[currentStatus.current_caninchannel]&127); currentStatus.canin[currentStatus.current_caninchannel] = readAuxanalog(configPage9.Auxinpina[currentStatus.current_caninchannel]&127);
} }
else if ((configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 3) //if current input channel is enabled as digital local pin else if ((((configPage9.enable_secondarySerial == 1) || ((configPage9.enable_intcan == 1) && (configPage9.intcan_available == 1))) && (configPage9.caninput_sel[currentStatus.current_caninchannel]&12) == 12)
{ || (((configPage9.enable_secondarySerial == 0) && (configPage9.enable_intcan == 1 && configPage9.intcan_available == 0 )) && (configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 3)
|| (((configPage9.enable_secondarySerial == 0) && (configPage9.enable_intcan == 0)) && ((configPage9.caninput_sel[currentStatus.current_caninchannel]&3) == 3)))
{ //if current input channel is enabled as digital local pin
//read digital channel specified //read digital channel specified
//currentStatus.canin[13] = 14; Dev test use only!
currentStatus.canin[currentStatus.current_caninchannel] = readAuxdigital((configPage9.Auxinpinb[currentStatus.current_caninchannel]&127)+1); currentStatus.canin[currentStatus.current_caninchannel] = readAuxdigital((configPage9.Auxinpinb[currentStatus.current_caninchannel]&127)+1);
} //Channel type } //Channel type
} //For loop going through each channel } //For loop going through each channel