RX8 Cluster Working Canbus

RX8 Project – Part 6, Canbus #2

So now we have a powered up RX8 cluster and some Canbus hardware that we can talk to we can start doing a few interesting things with our new setup.

Fire up the Arduino IDE and we can start writing our basic controller code. Canbus devices have a device address and a memory location for all the required data so we need to work all of these out. This is a lot easier for digital IO than the more complicated analog values because digital IO are just either set bit on or off whereas analog values can have funny scaling and things going on. I initially used a canbus demo program which worked because I basically cloned the Arduino Canbus shield. Plenty of starter guides and information can be found here : https://learn.sparkfun.com/tutorials/can-bus-shield-hookup-guide

My initial approach involved setting the target address for the Canbus transmission and sending patterns of bits high and low and see what happens. Google told me that the cluster Canbus interface operates on 500 kHz clock so with that information we should get a connection.

#include <Arduino.h>
#include <mcp_can.h>
#include <mcp_can_dfs.h>

#define CANint 2
#define LED2 8
#define LED3 7

MCP_CAN CAN0(10); // Set CS to pin 10

void setup() {
 // put your setup code here, to run once:
 Serial.begin(115200);
 Serial.println("Init…");

Serial.println("Setup pins");
 pinMode(LED2, OUTPUT);
 pinMode(LED3, OUTPUT);
 pinMode(CANint, INPUT);

Serial.println("Enable pullups");
 digitalWrite(LED2, LOW);
 Serial.println("CAN init:");
 
 if (CAN0.begin(CAN_500KBPS) == CAN_OK) 
 {
 Serial.println("OK!");
 } 
 else 
 {
 Serial.println("fail :-(");
 while (1) 
 {
 Serial.print("Zzz… ");
 delay(1000);
 }
 }

Serial.println("Good to go!");
}

unsigned char offarray[8] = {0, 0, 0, 0, 0, 0, 0, 0}; // Always Off Array
unsigned char onarray[8] = {255,255,255,255,255,255,255,255}; // Always On Array

void loop() {
 // put your main code here, to run repeatedly:

for (int i=0; i <= 512; i++){ 
  for (int l=0; l <= 10; l++){  
    for (int j=0; j <= 100; j++){
       CAN0.sendMsgBuf(i, 0, 8,offarray);
       delay(10);
     }

     for (int k=0; k <= 100; k++){
     CAN0.sendMsgBuf(i, 0, 8,onarray);
     delay(10);
     }
   }
  }
}

So this loop will iterate through 512 addresses strobing all 8 bytes high and low on 1 second intervals. The trick here is that canbus needs regular packets to stay active, so we can’t just send a value once. In this case each value (high or low) is send 100 times at 10ms intervals so the cluster should stay active long enough to see if anything is happening. Each address will get 10 cycles of high and low before moving onto the next address. In concept this would work and provided ‘i’ is set to increment high enough you would cover all the addresses. Bear in mind at this rate you’d have to watch it for about 90 mins…

Thankfully around the time I started running though this trying to find any useful addresses I came across this :

https://www.cantanko.com/rx-8/reverse-engineering-the-rx-8s-instrument-cluster-part-one/

This nicely tied in with the hardware I was working on and so the code and information is all exceedingly useful and saved me a lot of time. Specifically it gives the address locations for most of the indicators on the cluster which is what we really need.

After lots of trial and error I managed to come up with a block of code that can control the cluster but easily allow me to set any warning light I need on the dash, or more accurately also to turn off all the warning lights. Something that will be essential come MOT time as a warning light that stays on is an MOT fail and since most of the systems that control them will no longer be in the car (primarily the original ECU).

#include <Arduino.h>
#include <mcp_can.h>
#include <mcp_can_dfs.h>


#define COMMAND 0xFE
#define CLEAR 0x01
#define LINE0 0x80
#define LINE1 0xC0

#define CANint 2
#define LED2 8
#define LED3 7

#define NOP __asm__ ("nop\n\t")

// Variables for StatusMIL
bool checkEngineMIL;
bool checkEngineBL;
byte engTemp;
byte odo;
bool oilPressure;
bool lowWaterMIL;
bool batChargeMIL;
bool oilPressureMIL;

// Variables for PCM
byte engRPM;
byte vehicleSpeed;

// Variables for DSC
bool dscOff;
bool absMIL;
bool brakeFailMIL;
bool etcActiveBL;
bool etcDisabled;


MCP_CAN CAN0(10); // Set CS to pin 10

void setup() 
{
    
    //Serial.begin(115200);
    //Serial.println("Init…");
    //Serial.println("Setup pins");
    
    pinMode(LED2, OUTPUT);
    pinMode(LED3, OUTPUT);
    pinMode(CANint, INPUT);

    //Serial.println("Enable pullups");
    digitalWrite(LED2, LOW);
    //Serial.println("CAN init:");
    
    if (CAN0.begin(CAN_500KBPS) == CAN_OK) 
    {
        //Serial.println("OK!");
    } 
    else 
    {
        //Serial.println("fail :-(");
        while (1) 
        {
            //Serial.print("Zzz… ");
            delay(1000);
        }
     }

Serial.println("Good to go!");
}

unsigned char stmp[8]       = {0, 0, 0, 0, 0, 0, 0, 0};                         // Always Off Array
unsigned char otmp[8]       = {255,255,255,255,255,255,255,255};                // Always On Array

unsigned char statusPCM[8]  = {125,0,0,0,156,0,0,0};                            // Write to 201
unsigned char statusMIL[8]  = {140,0,0,0,0,0,0,0};                              // Write to 420
unsigned char statusDSC[8]  = {0,0,0,0,0,0,0,0};                                // Write to 212

unsigned char statusEPS1[8] = {0x00,0x00,0xFF,0xFF,0x00,0x32,0x06,0x81};        // Write to 200 0x00 00 FF FF 00 32 06 81
unsigned char statusEPS2[8] = {0x89,0x89,0x89,0x19,0x34,0x1F,0xC8,0xFF};        // Write to 202 0x89 89 89 19 34 1F C8 FF

unsigned char statusECU1[8] = {0x02,0x2D,0x02,0x2D,0x02,0x2A,0x06,0x81};        // Write to 215 - Unknown
unsigned char statusECU2[8] = {0x0F,0x00,0xFF,0xFF,0x02,0x2D,0x06,0x81};        // Write to 231 - Unknown
unsigned char statusECU3[8] = {0x04,0x00,0x28,0x00,0x02,0x37,0x06,0x81};        // Write to 240 - Unknown
unsigned char statusECU4[8] = {0x00,0x00,0xCF,0x87,0x7F,0x83,0x00,0x00};        // Write to 250 - Unknown


/*

215 02 2D 02 2D 02 2A 06 81 // Some ECU status

231 0F 00 FF FF 02 2D 06 81 // Some ECU status

240 04 00 28 00 02 37 06 81 // Some ECU status

250 00 00 CF 87 7F 83 00 00 // Some ECU status

*/


void updateMIL()
{
    statusMIL[0] = engTemp;
    statusMIL[1] = odo;
    statusMIL[4] = oilPressure;
    
  if (checkEngineMIL == 1)
  {
    statusMIL[5] = statusMIL[5] | 0b01000000;
  }
  else
  {
    statusMIL[5] = statusMIL[5] & 0b10111111;
  }
   
    if (checkEngineBL == 1)
  {
    statusMIL[5] = statusMIL[5] | 0b10000000;
  }
  else
  {
    statusMIL[5] = statusMIL[5] & 0b01111111;
  }

   if (lowWaterMIL == 1)
  {
    statusMIL[6] = statusMIL[6] | 0b00000010;
  }
  else
  {
    statusMIL[6] = statusMIL[6] & 0b11111101;
  }

     if (batChargeMIL == 1)
  {
    statusMIL[6] = statusMIL[6] | 0b01000000;
  }
  else
  {
    statusMIL[6] = statusMIL[6] & 0b10111111;
  }

       if (oilPressureMIL == 1)
  {
    statusMIL[6] = statusMIL[6] | 0b10000000;
  }
  else
  {
    statusMIL[6] = statusMIL[6] & 0b01111111;
  }
}

void updatePCM()
{
    statusPCM[0] = engRPM;
    statusPCM[4] = vehicleSpeed;
}

void updateDSC()
{       
  if (dscOff == 1)
  {
    statusDSC[3] = statusDSC[3] | 0b00000100;
  }
  else
  {
    statusDSC[3] = statusDSC[3] & 0b01111011;
  }

    if (absMIL == 1)
  {
    statusDSC[4] = statusDSC[4] | 0b00001000;
  }
  else
  {
    statusDSC[4] = statusDSC[4] & 0b11110111;
  }

      if (brakeFailMIL == 1)
  {
    statusDSC[4] = statusDSC[4] | 0b01000000;
  }
  else
  {
    statusDSC[4] = statusDSC[4] & 0b10111111;
  }

     if (etcActiveBL == 1)
  {
     statusDSC[5] = statusDSC[5] | 0b00100000;
  }
  else
  {
    statusDSC[5] = statusDSC[5] & 0b11011111;
  }

    if (etcDisabled == 1)
  {
    statusDSC[5] = statusDSC[5] | 0b00010000;
  }
  else
  {
    statusDSC[5] = statusDSC[5] & 0b11101111;
  }
 

}

void loop() 
{
    // StatusMIL
    engTemp         = 145;
    odo             = 0;
    oilPressure     = 1;    // Either 0 (fault) or >=1 (Ok)
    checkEngineMIL  = 0;
    checkEngineBL   = 0;
    lowWaterMIL     = 0;
    batChargeMIL    = 0;
    oilPressureMIL  = 0;

    updateMIL();
    CAN0.sendMsgBuf(0x420, 0, 8, statusMIL);
    delay(10);


    // StatusPCM
    engRPM          = 60;    // RPM  Value*67 gives 8500 RPM Reading Redline is 127
    vehicleSpeed    = 93;    // Speed  Value=0.63*(Speed)+38.5

    updatePCM();
    CAN0.sendMsgBuf(0x201, 0, 8, statusPCM);          //CAN0.sendMsgBuf(CAN_ID, Data Type (normally 0), length of data, Data
    delay(10);

    // StatusDSC
    dscOff          = 0;
    absMIL          = 0;
    brakeFailMIL    = 0;
    etcActiveBL     = 0;    // Only works with dscOff set
    etcDisabled     = 0;    // Only works with dscOff set

    updateDSC();
    CAN0.sendMsgBuf(0x212, 0, 8, statusDSC);
    delay(10);

/*
    CAN0.sendMsgBuf(0x200, 0, 8, statusEPS1);
    delay(10);            

    CAN0.sendMsgBuf(0x202, 0, 8, statusEPS2);
    delay(10);    
           
    
    CAN0.sendMsgBuf(0x215, 0, 8, statusECU1);
    delay(10);  

    CAN0.sendMsgBuf(0x231, 0, 8, statusECU2);
    delay(10);  

    CAN0.sendMsgBuf(0x240, 0, 8, statusECU3);
    delay(10);  
    CAN0.sendMsgBuf(0x250, 0, 8, statusECU4);
    delay(10);  

*/
            
 }

This is the current latest version of the code I have, the serial comms section at the start is handy for checking you have a working connection but if you don’t have the serial monitor open it will cause the Arduino to hang at the transmit instruction and not get as far as updating the canbus so I recommend enabling these initially but once you get a working connection comment them back out as above. There are also sections above taken directly from the Cantanko page to deal with the power steering controller and some other bits, I haven’t tried these yes as the cluster isn’t in a car but I plan do so at some stage.

This code has some limitations in this form, basically the warning lights etc are set in the code as static values so this code will just set everything normal and all the lights I have addresses for to off. One particular curiosity is the way the cluster treats the oil pressure value. The data space actually has a whole byte for a value here but the cluster only only has two values despite having an actual gauge, a value of 0 drops the needle to the bottom, a value of 1 or more sets the gauge to normal. My feeling on this is the car was originally intended to have a proper oil pressure transmitter but someone decided it was too expensive and a normal pressure switch was used instead and rather than redesign the cluster they just changed the scaling in the on board microcontroller to behave as described. long term I’d love to mod the cluster to add the analog functionality back in but without the code for the controller this would probably involve disconnecting the original drive to that gauge and adding another Arduino inside the cluster just for driving that gauge. It seems like a lot of work to know oil pressure on a scale of low to high!

The code also sets a speed and RPM however the ODO and trip meters will not increment as it stands – I purposefully left this bit of code out because it’s only really applicable if you’re on an actual car otherwise your cluster will just keep clocking up. The ODO and trips seemed to be the one bit no-one else had managed to do or identify but after quite a few hours of testing  random blocks will various combinations of high and low as well as sending incrementing / decrementing values I noticed my trip meter had actually moved up by 0.1 miles which meant something was working. I eventually managed to trace it to the address listed above. The trick to actually making it work is that the value in the byte is irrelevant to what the cluster displays, so no this doesn’t let you clock it back! What it appears to do is counts the changes to the value so I made it work by setting up a loop of code that keeps changing this value up to a certain number to give a specific distance. Turns out the cluster needs to see 4140 changes per mile. Eventually I plan to tie this in to the speedometer value so only one value needs to be set, by knowing the pulses per mile and the speed we can work out the time delay between each change. As an example at 100mph we need to send 115 changes per second, this is one every 8.7ms which is obviously faster than the loops above and so for speed and accuracy would have to be hardware timed with an interrupt to do the update at the right speed. I’ll probably do an updated version at a later date.

There’s a couple other things I need to sort out, the airbag warning light being the prime one because this is an outright MOT fail. Now in theory when it’s back on the car it should work just fine as the airbag wiring is all there but I figured it was worth working out anyway. So after working through all of the RX8 cluster wiring diagrams (1)(2)(3)(4) I pieced this together :RX8 Cluster Pinout

This covers the majority of everything someone might need to use the cluster on a simulator apart from the fuel gauge. The RX8 fuel gauge is a bit of an oddity because the car uses a saddle shaped fuel tank to allow it to clear the driveshaft and so it has two senders denoted as ‘main’ and ‘sub’.

RX8 Fuel System Senders

Each of these apparently has a resistance value of between about 325Ω at the bottom and 10Ω at the top. There seems to be some questions about how this system works out what to display based on the two sender values and whether it expects to see one remain full while the other empties or something similar. Unfortunately I’ve not played with it much because I’ve don’t actually need to make this work off the car (since the car will have the senders but I can say putting 100Ω a resistor between both 2R-2P and 2R-2T gives a value of about 1/3 of a tank and 9Ω (because I just added a 10Ω on along side the existing 100Ω) across these connections gives a full tank reading  (actually a little above full) so as long as you move both together it works fine, this is ok if all you want to do is get the fuel warning light off for a driving simulator but not that helpful for a single fuel sender conversion which is why most people are interested. If I get chance I’ll investigate further. Also for some reason it takes an absolute age to move up the scale which is a bit unfortunate but I suspect is as intended. At least it should be stable!

All of that leaved us with just one light I can’t get to turn of, the warning light for the electronic power steering. This is controlled via canbus by the look of the circuit diagram but as yet I’ve not found the address for it. If anyone knows the address please leave a comment! Else I will have to go back to either trial and error or the really dodgy backup plan which involves cutting the tracks in the cluster and doubling up on another warning light which isn’t used much! Maybe I should just add another controller in the cluster!

So hopefully that gives you (almost) everything you need to know about making the cluster work! We might get back to mechanical things in the next update…

17 thoughts on “RX8 Project – Part 6, Canbus #2”

  1. I’m soooo glad I’ve found this page, i’m just pulled my engine out and when the adapter plate and flywheel arrive my 1JZ-GTE will be going in..

    I have had the engine running on the pallet with the stock ECU so i know i will be able to turn the key and it will work but obviously nothing else will work.

    I have been googling for the last few days trying to find as many CAN message ID’s as i could and then i found the holy grail (this page), i have a spare set of instruments on my toolbox with an ELM327-USB connected to it for sending and receiving CAN messages.

    I have two RX8’s, one that is untouched so i can compare signals, i have an automotive oscilloscope that can log CAN data also.
    I also have a more complete pin-out for the instruments which i’d love to share.

    If you are on Facebook or somewhere else that has a messaging platform i’d love to connect with you and we can get your code tested in the next few weeks.

  2. Hi mate,

    We are currently doing a RX8 with a LS3 in Australia. We have used a EMU Black from ECU master which has a Can Interface. So we can manually type commands over the interface to turn off lights etc.

    I was wondering do you have the codes you sent for various things?

    The code we have for electric power steering is
    ID 300 minimum 0.5 Seconds timing

    Cheers!

    Jeff

    1. Hi, that’s really interesting, one of the codes I haven’t yet identified was a code 300 as it only appears to have two states on live systems – either 0 or 80 depending on whether the PCM is connected or not. Can I ask what that code actually does? Is it the dash warning light? If so what value are you sending?

      Other info I have is : (May need some reformatting? Let me know if it looks rubbish and I’ll email it separately!)

      ID Freq Byte 0 Byte 1 Byte 2 Byte 3 Byte 4 Byte 5 Byte 6 Byte 7
      4C0 67
      4B0 673 From ABS wheel speeds (x-10000)/100 km/h FL FL FR FR RL RL RR RR
      4B1 6582 ABS?
      47 8 Stops broadcast with Ign on – usually static values 6 1 FF 0 0 0 0 0
      81 8960 Byte 0 Seems to be a status and changes with ign/start/run – block otherwise static ? 6F 0 67 0 0 0 0
      201 1453 Signal to Dash RPM and Speed, Byte 6 Accel position 0-200(full down) RPM RPM FF FF Speed Speed Accel FF
      203 669 0-0-0-0-AF-2-0 Ign, 20-20-20-21-AF-2-20 ?, 10-10-10-15-AF-2-10 Run
      204 360 Seems to just constantly broadcast a single byte of 0 value 0 0 0 0 0 0 0 0
      212 729 Signals to Dash DSC lights – Format FE FE FE 34 40 40 0 with PCM, FF FF FF 34 48 0 without FE FE FE 0
      215 10757 From PCM 2’s never change, byte 7 is 0 then changes to 81 when running, byte 1,3 equal 2 2 2 81
      231 5258 From PCM – Appears to be F-0-FF-FF-0 at idle and FF-0-FF-FF-0 when running?C12 F 0 FF FF 0 0 0 0
      240 126 byte 7 appears to go 4, 8, and 2 during run 2 0 ? ? 77-80 8C 0 0
      250 135 Bytes 4 & 5 are zero when not running 0 0 76-D4 33-39 0-E 19-FD 21-3D 4
      300 10386 Appears to indicate PCM fault, reads 80 (1000 0000) with no PCM 0 0 0 0 0 0 0 0
      420 109 From PCM – Signals to Dash multi function lights
      430 2393
      620 102 Fixed 0 0 0 0 10 0 4 0
      630 1313 Fixed? 8 0 0 0 0 0 6A 6A
      650 3064 Fixed 0 0 0 0 0 0 0 0
      No PCM IDs
      81
      47
      430
      4B1
      4B0
      4C0
      300
      204
      212 Format FE FE FE 34 40 40 0 with PCM, FF FF FF 34 48 0 without

      This is still very much a work in progress so any further information you have would be very much appreciated! More detail on the ones I’ve used can be found in the canbus arduino posts – the program details which bit in a block at a specific address controls which light etc. Hopefully this helps? Let me know if you want any more explanation.

      Jon

  3. Hello,
    I really appreciate your hard work on this project. I have been trying to send some CAN messages to my RX8 cluster (also using your code here), but there is something wrong. First of all, my RPM pointer doesn’t want to keep its raised state (it goes up to the desired level, and then instantly falls down). Secondly, when sending few different messages, cluster seems to be buffering only one of them, and not necessarily the first one. The rest of them seem to be ignored. If you have any ideas what am I doing wrong, then please let me know.
    Raphael

    1. Hi,

      Bit of a delay in replying, I’ve not had much time recently.

      To keep the cluster in a specific state you must keep sending CAN messages at regular intervals even if the value doesn’t change and what you describe is symptomatic of it only getting the data once. The warning lights need data in the order of once every few seconds but other items are in the order of milliseconds. The code must be set to run on a loop to keep these refreshed. It’s also worth pointing out here that if you don’t add a short delay between data packets being sent to the cluster it will not see successive transmissions – I suspect this is to do with message queues on the canbus interface chip connected to the arduino (but it may be a limitation of the cluster) but it doesn’t cause much of an issue for operation but if you have not included these it may explain part of your problem. This is why I have “delay(1)” between each send in the code.

      Also I assume you have the cluster disconnected from the car? If not then in turning on the ignition the PCM (ecu) and all the other devices on the bus will be broadcasting their actual data and the cluster will start doing all sorts of odd things!

      Let me know how you get on.

      Jon

  4. Hi Jon,

    Do you have any more info on the various warning light IDs? Can we email each other?

    Have just found the message to turn off the ABS light that comes on if it doesn’t sense the PCM. So effectively this message is sent to confirm the PCM is there, and after that handshake it allows the ABS to operate independently.

    Jeff

    1. Hi,

      Much of what I have is already posted. The ABS light is an interesting one – I can turn the light off with the dash on the bench out of the car but on the car from what I remember my ABS module doesn’t initialise so the light flickers. I was trying to replay a whole canbus log file into the system to identify the parts I’ve not yet managed to (primarily initialising the power steering module) but my can interface wasn’t fast enough for it and I’ve not had time to work on that recently. Any information you have on getting that to work would be much appreciated, I will email you.

      1. Hi,

        ID 620 is sent by the ECU (PCM) but appears to be some sort of setting for the ABS unit, based on the information I have it is a constant value for a given car, in hex my car is 0x 00 00 00 00 10 0 4. From the information I have the last digit can vary, so far I’m aware of 2, 3 and 4 being possible options but as yet I’ve not worked out what this actually does.
        ID 630 is also associated with the ABS and defines the transmission type and wheel sizes, in my case 0x 08 00 00 00 00 00 6A 6A. It appears the 08 means manual (I’ve heard an 02 is here for an automatic but haven’t been able to check this) and the 6A (106 dec) is the wheel size.

        If you figure any more out let me know!

        Jon

  5. Hi!

    I’ve been looking on this for some time now wanting to put this cluster on my car, and while i have most of the things figured out or completely disabled -my car doesn’t have cruise control for example- i can’t make the odometer work as it should, it will just be stuck at whatever number it has or slowly creep up at a constant rate.

    1. Hi,

      The odometer is controlled by the MIL (420 – same CAN ID as engine temp and oil pressure). The value you need to manipulate is byte 1 but the stored value doesn’t correspond to anything as far as I can tell. It seems to work by registering the change in value and incrementing but it doesn’t matter what value you write. I worked it out as being 4140 changes per mile displayed on the cluster and this seems to work quite consistently but that was done by trial and error.

      I never got round to doing a proper implementation of this when reading the value from somewhere sensible. I suggest calculating from whatever value you are using for the actual speedometer. This will probably need a hardware timer set up on the arduino with an interrupt to update the value at the correct rate regardless of the rest of the code. So for example 60 mph is 1 mile/min which means you need 4140 changes/min which is 69 Hz update rate. There’s a calculator for working out the arduino timer settings to get whatever frequency you need http://www.8bit-era.cz/arduino-timer-interrupts-calculator.html .

      Let me know how you get on.

      Good luck!

  6. Thanks a lot of posting this info! I’m currently starting my Subaru CAN Bus gauge cluster project referencing some of the work you’ve done with your RX-8. If I can understand it, I’ll also apply this to my LS swapped RX to possibly eliminate the Factory computer. My one question, can you point me to the git tag of the can Library you are using? It looks like the one I have is too new. https://github.com/coryjfowler/MCP_CAN_lib

    1. Hi,

      If you take a look at the latest code (https://www.chamberofunderstanding.co.uk/2021/06/11/rx8-project-part-21-canbus-6-working-code/ )you’ll see some option selection where the declaration for the more recent Seeed Library is slightly different. Someone else recently asked me about the library I was using and genuinely I can’t remember but looking back at it it seems it’s most likely an archaic version of the Seeed one from about 2016!

      I suggest just using the latest code which includes a lot of new features and use the active library to “Seeed_Library” as follows:

      // Comment out to select correct CAN library
      #define Seeed_Library
      //#define MCP_Library

      The difference in the declarations are shown below in case you want to edit the other versions of code to work with the latest seeed library:

      #ifdef Seeed_Library
      #include “mcp2515_can.h”
      mcp2515_can CAN0(CAN_CS); // Configure CAN SPI Chip Select
      #endif

      #ifdef MCP_Library
      #include
      #include
      MCP_CAN CAN0(CAN_CS); // Configure CAN SPI Chip Select
      #endif

      I’ve edited the page with the latest code to clarify the info around this, hopefully this all helps you out, if not just message me again. I’d be very interested to hear more about your project as it develops and if you manage to find out the CAN codes for the Subaru please let me know as I’d be glad to post them here.

      I’ve actually developed some special Arduino hardware intended for doing swaps and things, so far I’ve only done the first prototype but I’m hoping to do a post on it shortly, I’ve just been very busy lately.

      Good luck!

      Jon

  7. Hi Jon,

    Jeff Here from Australia again.

    As we are still using the ECU Master EMU black, we can only enter one extra canbus item at a time to trial. We can’t seem to get the DSC light turned off?

    Using our ID and minimum timing setting. What do you reccomend sending?

    1. Hi again! Good to hear from you!

      The DSC light itself it ID 212 Byte 3, bit 2 ( dealt with by this bit in the arduino code when enabled :

      void updateDSC() {
      if (dscOff == 1) {
      send212[3] = send212[3] | 0b00000100;
      } else {
      send212[3] = send212[3] & 0b01111011;
      }

      So if you don’t have the ABS unit you can just send 7 bytes of zero’s to this ID and it will turn off all ABS/DSC lights on the dash, the ABS unit usually updates this every 25ms but for the dash I know sending every 100ms is plenty to keep the light off.

      In your case (I can’t remember your exact setup) if you still have the ABS unit in the car then this will broadcast on the same ID so you can’t actually override it and attempting to do so will just end up with a weirdly blinking warning light(s), however if you do still have the ABS you probably just need to do a DSC reset. Basically just turn on the ignition, turn the steering all the way to each end and back to centre and the light should go out (you might have to ignition off and back on after, I can’t remember) this allows the the ABS unit to relearn the steering travel after it has lost power due to the battery going flat or disconnected. I had exactly the same on mine!

      Hopefully this helps!

      Jon

  8. Hi Jon,

    So it looks like your right. Under my current setup I can get DSC OFF and ABS light to turn off after initialising the turning left to right.

    Only thing that’s left now is the traction control light. (Car with the squiggly lines).

    I did try send message 212 over Can and this would flicker the traction control light on and off like you said as I have obviously already sent the ABS start up message from the EMU.

    I wonder is there a message ID only for the traction control light?

    1. Hi Jeff,

      I’ve got the same on mine, from what I’ve heard this is quite common after a battery disconnect. In essence doing the steering wheel re-calibrates the steering angle sensor which is used by the DSC system so it sorts out that error but the traction control doesn’t clear until it sees a certain amount of movement on the ABS wheel speed sensors to confirm they are all working correctly as those sensors are used to track the relative wheel speeds for the traction control. So all going well just driving it a short distance should clear it! but no, unfortunately the etc is also on DSC (ID 212).

      if (etcActiveBL == 1) {
      send212[5] = send212[5] | 0b00100000;
      } else {
      send212[5] = send212[5] & 0b11011111;
      }

      if (etcDisabled == 1) {
      send212[5] = send212[5] | 0b00010000;
      } else {
      send212[5] = send212[5] & 0b11101111;
      }

      As an interesting aside to all of this is means in theory the traction control light will still flash on if there is wheelspin but with an aftermarket ECU it doesn’t have to do anything about it unless you set it up to. In my case I set up megasquirt to read the ABS speed sensor data from CAN (ID decimal 1201, hex 4B1) so it can use it internally as a speed reference for anything requiring speed reference such as traction control or pit limiter etc. Each is a 2 byte field, I have the scaling set as multiply 983 and divide 16100 but I’ve not checked this on the vehicle so I can’t vouch for this giving accurate values but it worked on bench test. Also worth pointing out here that on the factory setup the ECU converts the ABS data to the speed signal for the dash speedometer and odometer so these update so in the latest arduino code there’s a section which performs this function.

      If you continue to have issues I’ve actually developed some custom arduino hardware designed for manipulating CAN data in flight so in theory you could edit individual bits before passing them to the other side to do things like block problem warning light signals from reaching the dash, or link the lights to another data field or even to a physical input. I built the first prototype version months ago and bought enough parts to make 10 of them. I was intending to make them available for sale but haven’t quite got there yet!

      Hopefully for you it will just clear itself, but please let me know how you get on!

      Jon

Leave a Reply to Raphael Cancel reply

Your email address will not be published. Required fields are marked *