chipKIT32 / chipKIT-core

Downloadable chipKIT core for use with Arduino 1.6 - 1.8+ IDE, PlatformIO, and UECIDE
http://chipkit.net/
Apache License 2.0
59 stars 53 forks source link

I2C/wire freeze after a short random time when I use PWM (analogWrite) or Servo lib #312

Open VigibotDev opened 7 years ago

VigibotDev commented 7 years ago

Hello,

On last release chipKIT Core + last Arduino 1.6.9 I have a lot of I2C freeze problem :

When I use I2C/wire (inside this lib https://github.com/AlexisTM/LIDAREnhanced/blob/master/I2CFunctions.h) with analogWrite (PWM on 4 OC pins to drive motors controller) I get my Max32 stuck after a short random time.

I get the same problem with I2C + Servo library.

I2C standalone no problem (but I get stuck when there is a write or read error on I2C ! This is a very bad idea to keep a embedded system waiting forever on I2C error:( )

I think there is I2C errors with any interrupt code, and I2C freeze on error.

All my Servo + PWM projet code without problem for week without reboot.

I run I2C @ 400KHz - DTWI.h patched with - bool beginMaster(I2C_FREQ freqI2C FQ400KHz); - I can't find other way or other high level API parameter to do this.

I2C is a PITA to get working with chipKIT :( please help.

This is a quick and dirty minimized code from my project, It freeze when I use lidarcontroller.spinOnce(); (I2C polling) with analogWrite. I must comment out I2C or analogWrite to keep working forever.

#include <Servo.h>
#include <Wire.h>
#include <I2CFunctions.h>
#include <LidarObject.h>
#include <LidarController.h>

#define DEBUG Serial
#define MODEM Serial1

#define TXCHANNEL 10
#define RXCHANNEL 5

#define CONTROLEURRATE 10

#define VMIN 1200
#define VMAX 1680

#define VIDEOSLEEPPIN 4               // C14

#define VPIN A0                       // B0

#define LIDARI2CADDRESS 0x62
#define LIDARTRIGGERPIN 75            // Dummy
#define LIDARENABLEPIN 75             // C13
#define LIDARMODEPIN 75               // Dummy

#define MOTEURAVGPWMPIN 3             // D0
#define MOTEURARGPWMPIN 5             // D1
#define MOTEURAVDPWMPIN 6             // D2
#define MOTEURARDPWMPIN 9             // D3
#define MOTEURAVGDIRPIN 10            // D4
#define MOTEURARGDIRPIN 39            // D5
#define MOTEURAVDDIRPIN 47            // D6
#define MOTEURARDDIRPIN 77            // D7

#define FLAGSPIN0 70                  // A0
#define FLAGSPIN1 71                  // A1
#define FLAGSPIN2 12                  // A2
#define FLAGSPIN3 13                  // A3
#define FLAGSPIN4 72                  // A4
#define FLAGSPIN5 73                  // A5
#define FLAGSPIN6 80                  // A6
#define FLAGSPIN7 81                  // A7
#define FLAGSPORT PORTA
#define FLAGSOFF B00110000

LidarController lidarcontroller;
LidarObject lidar;

uint32_t lidarsum = 0;
uint16_t lidardivider = 1;

void setup() {
 DEBUG.begin(115200);
 DEBUG.println("setup()");
 MODEM.begin(115200);

 lidar.begin(LIDARENABLEPIN, LIDARMODEPIN, LIDARTRIGGERPIN, LIDARI2CADDRESS, 2, DISTANCE, 'A');
 lidar.setCallbackDistance(&lidarcallback);
 lidarcontroller.begin();
 lidarcontroller.add(&lidar, 0);

 pinMode(VIDEOSLEEPPIN, OUTPUT);

 pinMode(MOTEURAVGPWMPIN, OUTPUT);
 pinMode(MOTEURARGPWMPIN, OUTPUT);
 pinMode(MOTEURAVDPWMPIN, OUTPUT);
 pinMode(MOTEURARDPWMPIN, OUTPUT);
 pinMode(MOTEURAVGDIRPIN, OUTPUT);
 pinMode(MOTEURARGDIRPIN, OUTPUT);
 pinMode(MOTEURAVDDIRPIN, OUTPUT);
 pinMode(MOTEURARDDIRPIN, OUTPUT);

 pinMode(FLAGSPIN0, OUTPUT);
 pinMode(FLAGSPIN1, OUTPUT);
 pinMode(FLAGSPIN2, OUTPUT);
 pinMode(FLAGSPIN3, OUTPUT);
 pinMode(FLAGSPIN4, OUTPUT);
 pinMode(FLAGSPIN5, OUTPUT);
 pinMode(FLAGSPIN6, OUTPUT);
 pinMode(FLAGSPIN7, OUTPUT);
 //FLAGSPORT = FLAGSPORT & 0xFF00 | FLAGSOFF;
 FLAGSPORT = FLAGSPORT & 0xFF00 | FLAGSOFF ^ B00001100;

 DEBUG.println("loop()");
}

void lidarcallback(LidarObject* self) {
 lidarsum += self->distance;
 lidardivider++;
}

void writeModem() {
 int16_t voltage;
 uint8_t v;
 uint16_t lidarcm;

 voltage = map(analogRead(VPIN), 0, 1023, 0, VMAX);
 if(voltage < VMIN)
  voltage = VMIN;
 v = map(voltage, VMIN, VMAX, 0, 255);

 lidarcm = lidarsum / lidardivider;
 lidarsum = 0;
 lidardivider = 1;

 MODEM.write("$T");
 MODEM.write(v);
 MODEM.write(lidarcm >> 8);
 MODEM.write(lidarcm & 0xFF);
 MODEM.write(uint8_t(0));
 MODEM.write(uint8_t(0));
 MODEM.write(uint8_t(0));
 MODEM.write(uint8_t(0));
 MODEM.write(TXCHANNEL);
 MODEM.write(RXCHANNEL);
}

void moteurs(int16_t moteuravg, int16_t moteurarg, int16_t moteuravd, int16_t moteurard) {
 moteuravg = constrain(moteuravg, -255, 255);
 moteurarg = constrain(moteurarg, -255, 255);
 moteuravd = constrain(moteuravd, -255, 255);
 moteurard = constrain(moteurard, -255, 255);

 digitalWrite(MOTEURAVGDIRPIN, moteuravg < 0);
 digitalWrite(MOTEURARGDIRPIN, moteurarg < 0);
 digitalWrite(MOTEURAVDDIRPIN, moteuravd < 0);
 digitalWrite(MOTEURARDDIRPIN, moteurard < 0);

 analogWrite(MOTEURAVGPWMPIN, abs(moteuravg));
 analogWrite(MOTEURARGPWMPIN, abs(moteurarg));
 analogWrite(MOTEURAVDPWMPIN, abs(moteuravd));
 analogWrite(MOTEURARDPWMPIN, abs(moteurard));
}

void loop() {
 uint32_t now;
 static uint32_t last = 0;

 now = millis();
 if(now != last) {

  if(!(now % CONTROLEURRATE))
   moteurs(-5, -5, 5, 5);

  lidarcontroller.spinOnce();

  if(!(now % 66))
   writeModem();

 }
 last = now;

}

I tested a lot of minimized code, I always get stuck with I2C + PWM or I2C + Servo lib (chipKIT stock) What I can test to help ?

-> I'm go to test directly with DTWI in place of Wire.

Pascal

JacobChrist commented 7 years ago

When you say latest version of chipKIT-core you mean version 1.3.1?

Can you provide a link to the LIDAR you are using?

I am doing a lot of work (using) I2C right now, I am not sure if I can help, but it would probably be beneficial if we can reproduce this issue with a low cost I2C device so that others can reproduce with out having to buy a LIDAR module.

VigibotDev commented 7 years ago

This is the LidarLite v3 : http://www.robotshop.com/en/lidar-lite-3-laser-rangefinder.html Yes the 1.3.1 : https://raw.githubusercontent.com/chipKIT32/chipKIT-core/master/package_chipkit_index.json

I can't understand DTWI : samples are very confusing and there is no Read/Write a byte or word to I2C adress documentation or sample on google !!!!

I think this is a low level problem with wire or I2C on chipkit. I don't have other I2C device. The huge problem : why when I made a bad contact on SCL or SDA all my software stuck on Wire ? this is a fundamental problem, without I2C my software get online 24/7 and never stuck.

You can play live with my project here : https://www.serveurperso.com/?page=robot all is working but I can't use I2C Lidar to make public the possibility to move the robot. This is a mecanum robot with 6 camera onboard, long range UHF radio modem and video TX,, GUI powered with NodeJS all code is from me exept the lidar library I can't get working:(

I tested two library with same freeze after few second/minute, the stock blocking one, and the AlexisTM advanced one.

VigibotDev commented 7 years ago

You can reproduce the problem. Attach any easy I2C device on any PIC32 board with chipKIT Core and wire. and make bad contact on SCL or SDA.

Why the entire code lock and there is no a safe timeout ? I found this I2C problem around the world and never solved since first version of MPIDE.

An embedded device must never and never stop working else this is unusable for serious project. like an UAV -> crash for an I2C error!

EmbeddedMan commented 7 years ago

When run on an Arduino, does it behave as you need it to? (i.e. properly timeout with bad I2C connection)

*Brian

On Sun, Dec 4, 2016 at 7:56 AM, Pascal notifications@github.com wrote:

You can reproduce the problem. Attach any easy I2C device on any PIC32 board with chipKIT Core and wire. and make bad contact on SCL or SDA.

Why the entire code lock and there is no a safe timeout ? I found this I2C problem around the world and never solved since first version of MPIDE.

An embedded device must never and never stop working else this is unusable for serious project.

— You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub https://github.com/chipKIT32/chipKIT-core/issues/312#issuecomment-264705350, or mute the thread https://github.com/notifications/unsubscribe-auth/AAbeCGJNAFDCJIKBdeVYAZG1wslsG_HGks5rEsZ1gaJpZM4LDkC- .

VigibotDev commented 7 years ago

Sorry for my english, I never tested on arduino but I can do it today if required.

I search about timeout with wire on Arduino because I never used wire lib before this case. http://forum.arduino.cc/index.php?topic=37822.0 -> look same problem.

AlexisTM lib is very easy to understand and it need like any other I2C device, only 2 or 3 low level I2C function. AlexisTM added some auto reset for robustness but it's useless in this case where I2C API freeze itself.

But there is two problem : why I2C data is corrupted with Servo or PWM ? and second I2C wait forever.

(I use UBW32 with Max32 bootloader for you information because I recognize the home logo:) I use a NON USB bootloader because I need wireless UART flashing:) If you know a UART bootloader dedicated for UBW32 I'm interested, and a the Board variant working with Serial to Serial3 I/O... else I open case next time... For now I use UBW32 like a chipKIT Max32 everywhere)

EmbeddedMan commented 7 years ago

Pascal,

Oh, no worries - your English is just fine. :-)

The only reason I ask about Arduino is because we like to make sure our libraries function at least as well as Arduino's. So if something works properly under Arduino, but fails under chipKIT, it will get extra high priority from us.

If you have a chance to easily try on an Arduino, that would be really helpful.

And I'm really excited to hear you're using a UBW32! So cool! I don't know of any UART bootloader that's been specifically changed for UBW32.

It has been on my list of things to do for a long time now to create a 'real' chipKIT variant for UBW32.

*Brian

On Sun, Dec 4, 2016 at 8:13 AM, Pascal notifications@github.com wrote:

Sorry for my english, I never tested on arduino but I can do it today if required. Before I search about timeout with wire on Arduino because I never used wire lib before this case. AlexisTM lib is very easy to understand and it need like any other I2C device, only 2 or 3 low level I2C function.

(I use UBW32 with Max32 bootloader for you information because I recognize the home logo:) I use a NON USB bootloader because I need wireless UART flashing:) If you know a UART bootloader dedicated for UBW32 I'm interested, and a the Board variant working with Serial to Serial3 I/O... else I open case next time... For now I use UBW32 like a chipKIT Max32 everywhere)

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/chipKIT32/chipKIT-core/issues/312#issuecomment-264706282, or mute the thread https://github.com/notifications/unsubscribe-auth/AAbeCGuSLpeOKGyEKlSpa1sqp5SlmYMQks5rEsqbgaJpZM4LDkC- .

VigibotDev commented 7 years ago

OK I do the Arduino I2C test right now...

I love the UBW32, very small & efficient for battery operation when I power directly in 3.3V with a step down DC-DC. I just need to convert Max32 pin to port and it rock !

"Arduino" Because I use a Crumb2560 like an "UBW8" with Arduino bootloader (http://www.chip45.com/products/crumb2560-1.1_avr_atmega_module_board_atmega2560_usb_rs232_rs485.php) lol

VigibotDev commented 7 years ago

On AVR it never freeze with PWM (Unless I cause bad contacts on I2C lines BUT I can solve this with timeout like here https://github.com/arduino/Arduino/issues/1476 )

Quick and dirty minimized code "mock robot skeleton" :

#include <Servo.h>
#include <Wire.h>
#include <I2CFunctions.h>
#include <LidarObject.h>
#include <LidarController.h>

#define DEBUG Serial
#define MODEM Serial1

#define TXCHANNEL 10
#define RXCHANNEL 5

#define CONTROLEURRATE 20

#define VMIN 1200
#define VMAX 1680

#define VPIN A0                       // 

#define LIDARI2CADDRESS 0x6E          // 0x62
#define LIDARTRIGGERPIN 4             // Dummy
#define LIDARENABLEPIN 4              // PE2
#define LIDARMODEPIN 4                // Dummy

#define MOTEURAVGPWMPIN 2             // PE4
#define MOTEURARGPWMPIN 7             // PH4
#define MOTEURAVDPWMPIN 8             // PH5
#define MOTEURARDPWMPIN 12            // PB6
#define MOTEURAVGDIRPIN 26            // PA4
#define MOTEURARGDIRPIN 27            // PA5
#define MOTEURAVDDIRPIN 28            // PA6
#define MOTEURARDDIRPIN 29            // PA7

LidarController lidarcontroller;
LidarObject lidar;

uint32_t lidarsum = 0;
uint16_t lidardivider = 1;

void setup() {
 DEBUG.begin(115200);
 DEBUG.println("setup()");
 MODEM.begin(115200);

 lidar.begin(LIDARENABLEPIN, LIDARMODEPIN, LIDARTRIGGERPIN, LIDARI2CADDRESS, 2, DISTANCE, 'A');
 lidar.setCallbackDistance(&lidarcallback);
 lidarcontroller.begin();
 lidarcontroller.add(&lidar, 0);

 pinMode(MOTEURAVGPWMPIN, OUTPUT);
 pinMode(MOTEURARGPWMPIN, OUTPUT);
 pinMode(MOTEURAVDPWMPIN, OUTPUT);
 pinMode(MOTEURARDPWMPIN, OUTPUT);
 pinMode(MOTEURAVGDIRPIN, OUTPUT);
 pinMode(MOTEURARGDIRPIN, OUTPUT);
 pinMode(MOTEURAVDDIRPIN, OUTPUT);
 pinMode(MOTEURARDDIRPIN, OUTPUT);

 DEBUG.println("loop()");
}

void lidarcallback(LidarObject* self) {
 lidarsum += self->distance;
 lidardivider++;
}

void writeModem() {
 int16_t voltage;
 uint8_t v;
 uint16_t lidarcm;

 voltage = map(analogRead(VPIN), 0, 1023, 0, VMAX);
 if(voltage < VMIN)
  voltage = VMIN;
 v = map(voltage, VMIN, VMAX, 0, 255);

 lidarcm = lidarsum / lidardivider;
 lidarsum = 0;
 lidardivider = 1;

 DEBUG.println(lidarcm);

 MODEM.write("$T");
 MODEM.write(v);
 MODEM.write(lidarcm >> 8);
 MODEM.write(lidarcm & 0xFF);
 MODEM.write(uint8_t(0));
 MODEM.write(uint8_t(0));
 MODEM.write(uint8_t(0));
 MODEM.write(uint8_t(0));
 MODEM.write(TXCHANNEL);
 MODEM.write(RXCHANNEL);
}

void moteurs(int16_t moteuravg, int16_t moteurarg, int16_t moteuravd, int16_t moteurard) {
 moteuravg = constrain(moteuravg, -255, 255);
 moteurarg = constrain(moteurarg, -255, 255);
 moteuravd = constrain(moteuravd, -255, 255);
 moteurard = constrain(moteurard, -255, 255);

 digitalWrite(MOTEURAVGDIRPIN, moteuravg < 0);
 digitalWrite(MOTEURARGDIRPIN, moteurarg < 0);
 digitalWrite(MOTEURAVDDIRPIN, moteuravd < 0);
 digitalWrite(MOTEURARDDIRPIN, moteurard < 0);

 analogWrite(MOTEURAVGPWMPIN, abs(moteuravg));
 analogWrite(MOTEURARGPWMPIN, abs(moteurarg));
 analogWrite(MOTEURAVDPWMPIN, abs(moteuravd));
 analogWrite(MOTEURARDPWMPIN, abs(moteurard));
}

void loop() {
 uint32_t now;
 static uint32_t last = 0;

 now = millis();
 if(now != last) {

  if(!(now % CONTROLEURRATE)) {
   moteurs(-5, -5, 5, 5);
   lidarcontroller.spinOnce();
  }

  if(!(now % 66))
   writeModem();

 }
 last = now;

}
majenkotech commented 7 years ago

Do you have external pull-up resistors on your i2c lines?

VigibotDev commented 7 years ago

No, LidarLite have 3K internal pull-up, and there is no other sensor on my bus.

majenkotech commented 7 years ago

That's fine then. Arduino use ~30K internal pull-ups by default (10x too high) and many users don't realise that pull-ups are needed as a consequence.

VigibotDev commented 7 years ago

Yes I know weak internal pull-ups:) Why the "Wire.setClock(400000UL);" is not implemented ? patching the DTWI.h - bool beginMaster(I2C_FREQ freqI2C FQ400KHz); - is bad

VigibotDev commented 7 years ago

Can you apply this to chipKIT wire ? https://github.com/arduino/Arduino/issues/1476 http://forum.arduino.cc/index.php/topic,70705.0.html

AlexisTM commented 7 years ago

I could change the I2C library of LIDAREnhanced to this one: http://www.dsscircuits.com/index.php/articles/66-arduino-i2c-master-library

Multiple times quoted but I have no idea if this one is still better than the original Wire library and I have no idea if it would do the trick for you.

NOTE : You can use 100kHz I2C with no performance loss as you are using only one Lidarlite !

VigibotDev commented 7 years ago

I think this lib use AVR low level code (I use PIC32MX), I look tonight inside it.

I can't use 100KHz I2C because I get more blocking time inside your lib (I need to benchmark) and lower frequency is only a bad workaround (I never do this on my project I like maximum performance) -> Also it freeze (less often at 100KHz ? I can't permit any freeze on a 24/7 embedded system), But freeze... I can make any test for you if needed, I have also an AVR ready for tests.

I already found 400KHz I2C consume too many time for rest of code -> it lock my main loop often more than 1ms !!!

VigibotDev commented 7 years ago

Hi, no news about this I2C hangs ?

I plan to add MPU6050 on my project, it's a cheap (but good) I2C IMU, this make another test for this issue.

Pascal

VigibotDev commented 7 years ago

I get a hang after about 10 seconds with MPU6050 and Servo or PWM !!!! There is a critical issue with I2C on ChipKit Core... Please help.

I used the simplest RAW sample code from here : http://chipkit.net/forum/viewtopic.php?t=2385 (From https://www.i2cdevlib.com/)

AlexisTM commented 7 years ago

Dear,

This is pretty sad but it also mean the issue is not related to my library. For me, it is probably a corrupted memory when requesting two bytes. (Too small input/output buffers or wrongly allocated)

This is the "only" difference between the "ACQUISITION" state and the other states of LidarEnhanced.

So you now know where to dig :D

Good luck!

Alexis

EmbeddedMan commented 7 years ago

Pascal,

Any chance you could get a logic analyzer trace of those 10 seconds and upload it for us to look at?

*Brian

On Mon, Dec 19, 2016 at 4:01 PM, Pascal notifications@github.com wrote:

I get a hang after about 10 seconds with MPU6050 and Servo or PWM !!!! There is a critical issue with I2C on ChipKit Core... Please help.

I used the simplest RAW sample code from here : http://chipkit.net/forum/viewtopic.php?t=2385 (From https://www.i2cdevlib.com/)

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/chipKIT32/chipKIT-core/issues/312#issuecomment-268091525, or mute the thread https://github.com/notifications/unsubscribe-auth/AAbeCH4h1Cy1uoAMQpiXB7jwLKIilV20ks5rJv7RgaJpZM4LDkC- .

VigibotDev commented 7 years ago

Alexis, I was pretty sure it was not your lib it's for that I never opened an issue on your github lib:)

Embedded Man I must do it but I'm not equipped with hardware logic analyser you can give me the Arduino solution (faster to start/format you prefer) to do it (https://www.google.fr/webhp?ie=utf-8&oe=utf-8&gws_rd=cr&ei=EexYWLOlO4W2ae-3mvgP#q=arduino+i2c+logic+analyzer) or I2C Sniffer.

VigibotDev commented 7 years ago

FYI old MPIDE on my old project use I2C + PWM 24/7 without any problem (the special analog video receiver online on my website for the robot).

AlexisTM commented 7 years ago

It make me thinks about the Arduino Due, my favourite Arduino especially for the USB HID compatible protocols & the 86Mhz frequency. Badly, the I2C driver is badly implemented and sometimes simply do not work. This made me forget the Due for many projects... :'(

VigibotDev commented 7 years ago

AlexisTM thanks for the information (Now I know, I don't want to switch to Due for I2C lol).

With MPIDE I successfully do : 400KHz I2C / changing frequency rapidly on Comtech tuner module (to do an embedded spectrum analyser / to check spectrum before drone flight) + PWM (continuous "HQ" polyphonic sound without any freeze) :

I2C part (called very often at short interval)

void sendDivider(uint8_t tuner, bool chargepump) {
 Wire.beginTransmission(B1100001);
 Wire.send(highByte(divider));
 Wire.send(lowByte(divider));
 Wire.send(chargepump ? CHARGEPUMP170 : CHARGEPUMP50);
 Wire.endTransmission();
}

Sampler parts (HQ polyphonic sound on PIC32)

 // PWM
 OpenTimer3(T3_ON | T3_PS_1_1, 1 << SINEBITDEPTH);
 OpenOC4(OC_ON | OC_TIMER3_SRC | OC_PWM_FAULT_PIN_DISABLE, 0, 0);

 // Sampler
 ConfigIntTimer5(T5_INT_ON | T5_INT_PRIOR_3);
 OpenTimer5(T5_ON | T5_PS_1_1, F_CPU / SINESAMPLERATE);

// The sound mixer engine
extern "C" {
 void __ISR(_TIMER_5_VECTOR, ipl3) T5InterruptHandler(void) {
  uint8_t channel;
  static uint32_t pos[SINECHANNELS] = {0};
  int16_t sum;

  sum = 0;
  for(channel = 0; channel < SINECHANNELS; channel++) {
   pos[channel] += sineFreq[channel];
   pos[channel] %= SINESIZE << SINEDIVIDER;

   sum += sine[pos[channel] >> SINEDIVIDER] * sineAmp[channel] / sineMax[channel];

   if(sineAmp[channel])
    sineAmp[channel]--;
   else {
    sineFreq[channel] = 0;
    pos[channel] = 0;
   }
  }

  OC4RS = sum / SINECHANNELS + 128;

  mT5ClearIntFlag();
 }
}

EDIT : I think there is no freeze because this is a write only app

MicioMax commented 6 years ago

Same problem here, or at least very similar one. I'm on a stepper motor closed loop application; when I read the I2C data from encoder and the motor PWM is active it hangs quite often. It hangs on requestFrom(), waiting for fNacking going false : } while (i2cStatus.fMyBus && !i2cStatus.fNacking) ; I added some dumps; the read is ALWAYS of 2 bytes, when it hangs dtwi.cbToNAK stays at 1 forever. The code is quite simple, just needs to read a 2 bytes register. Without the PWM on it doesn't hang.

EDIT: I could easily add a timeout there, but that would only mask out the issue. I think it has something to do with interrupts, but not sure.

EmbeddedMan commented 6 years ago

MicroMax - would you mind posting your sketch? I'd like to try and reproduce this problem.

*Brian

On Mon, Mar 19, 2018 at 2:50 PM, MicioMax notifications@github.com wrote:

Same problem here, or at least very similar one. I'm on a stepper motor closed loop application; when I read the I2C data from encoder and the motor PWM is active it hangs quite often. It hangs on requestFrom(), waiting for fNacking going false : } while (i2cStatus.fMyBus && !i2cStatus.fNacking) ; I added some dumps; the read is ALWAYS of 2 bytes, when it hangs dtwi.cbToNAK stays at 1 forever. The code is quite simple, just needs to read a 2 bytes register. Without the PWM on it doesn't hang.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/chipKIT32/chipKIT-core/issues/312#issuecomment-374347401, or mute the thread https://github.com/notifications/unsubscribe-auth/AAbeCP166mXrx1NjeJCx5-9S3V40BBesks5tgAwZgaJpZM4LDkC- .

MicioMax commented 6 years ago

Hi Brian, it's a bit complicated, with many libraries I've written for the purpose. I can try to simplify it tomorrow, just to isolate the problem. But I don't know what you can do without my hardware... it's a custom board, still not on sale, using pic32mx230f128h controller, a stepmotor driver chip and a magnetic encoder with AM4096. The latter requires I2C communication.

EmbeddedMan commented 6 years ago

Fair enough. However, it sounds like the problem is really with doing any I2C comms while running a PWM at the same time, no? Hopefully there isn't anything special about your hardware (CPU or sensor) that is causing the problem, but it's more a "chipKIT-core" thing. If that's the case, then I should be able to take your code and whittle it down to just a simple I2C read and PWM setup and have it fail on my hardware (I'll use an I2C EEPROM or something). If we can get to that point, then I'm sure we can fix it.

I'm not sure where else to start - I've never had these types of I2C problems with chipKIT core before, and I've done a lot of I2C with it. That said, I don't think I've ever done I2C and PWM output (I'm assuming you're using an OC for that with a timer module? - that's part of what I want to understand from your code) at the same time.

*Brian

On Mon, Mar 19, 2018 at 6:17 PM, MicioMax notifications@github.com wrote:

Hi Brian, it's a bit complicated, with many libraries I've written for the purpose. I can try to simplify it tomorrow, just to isolate the problem. But I don't know what you can do without my hardware... it's a custom board, still not on sale, using pic32mx230f128h controller, a stepmotor driver chip and a magnetic encoder with AM4096. The latter requires I2C communication.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/chipKIT32/chipKIT-core/issues/312#issuecomment-374418218, or mute the thread https://github.com/notifications/unsubscribe-auth/AAbeCBXeGgJuKCpyEQkg2tiaXZ7S4vGDks5tgDx6gaJpZM4LDkC- .

MicioMax commented 6 years ago

I've got 2 PWM running to drive the 2 motor windings, with fast-changing duty cycle, using a couple of OC pins. I also disabled the interrupt-driven SSI encoder reading (you'll see it commented into encoder.cpp code), but no changes. Anyways, I'll attach the whole stuff here, but it's less than complete. I just started to code it when stumbled on the problem. You have to remove some parts (references to FishinoEEPROM and FishinoDebug libraries, mostly, you don't need them and they'd bring some 4-5 other libraries with them). Tomorrow maybe I'll try with logic analyzer. Not sure if it'll be useful, this time.

Thank you and best regards

Massimo MotorFishCalibrate.zip

majenkotech commented 6 years ago

I do I2C and PWM together on a board. Only for LED driving though - nothing as noisy (EMI wise) as steppers though. Could it just be noise? Are you using uni- or bi-polar steppers?

MicioMax commented 6 years ago

Bipolar, driven with 2 pwm-synthesized sinusoids. On testing board the PWM is filtered before reaching the driver, so it should be quite noiseless. There's also a switching power supply on board which powers the digital part from motor high voltage supply, so I don't think it can be a supply problem either. It could be the chopping electronics inside the driver, but I don't think it can bring such a nasty effect.

MicioMax commented 6 years ago

Some news: the loop hangs with 2 bytes on cbToNAK (the requested 2 bytes), the state machine on state 2 (I2C_DATA_READ) and the RBF (receive buffer full) flag active. I guess that the interrupt routine isn't called for some reason, and the data stays forever in receive buffer.

MicioMax commented 6 years ago

Other update: the sequence of events in working case: beginTransmission write(register number) (one or 2 DTWI state machine calls) endTransmission(false) requestFrom (2 bytes) (pass first while loop inside requestFrom) (4 state machine calls, cbToNAK == 1 after, state = 5 (I2C_WAIT)) (end of requestFrom) (2 state machine calls) read() call read() call END

The sequence in failing case:

beginTransmission write(register number) (one or 2 DTWI state machine calls) endTransmission(false) requestFrom (2 bytes) (pass first while loop inside requestFrom) FROM HERE NO MORE CALLS TO STATE MACHINE loops waiting for cbToNAK to become 0, RBF flag is set, state is 2 (I2C_DATA_READ)

It seems that the interrupt routine, which calls into state machine, doesn't get executed anymore.