SpenceKonde / megaTinyCore

Arduino core for the tinyAVR 0/1/2-series - Ones's digit 2,4,5,7 (pincount, 8,14,20,24), tens digit 0, 1, or 2 (featureset), preceded by flash in kb. Library maintainers: porting help available!
Other
544 stars 141 forks source link

I need help Dr Azzy :D #974

Closed NicolasGracia closed 1 year ago

NicolasGracia commented 1 year ago

Hello, I am trying to verify a code with arduino for the control of a DC motor with an ATtiny 1606 but i have this message " error "This sketch takes over TCA0, don't use for millis here. Pin mappings on 8-pin parts are different".

I'm new in the field, I transformed my arduino into a UPDI programmer by following the instructions but I think that the problem comes from the code in question (below) Can you help me please?! The code I want to implement in the attiny1606 :

#include <PID_v2.h>
#include <EEPROM.h>

#if defined(MILLIS_USE_TIMERA0)||defined(__AVR_ATtinyxy2__)
  #error "This sketch takes over TCA0, don't use for millis here.  Pin mappings on 8-pin parts are different"
#endif

// Type of Motordriver, with just an PWM Interface = true
// DRV8803
#define PWMCONTROL        1
#define PWMMIN           65 // minimum value for PWM to turn the motor
#define PWMMAX          200 // maximum value for PWM

#define EEPIDADDR         1 // Adress for saved PID Values

// Connect to Hall Sensor PCB
#define encoder0PinA    2 // PA6
#define encoder0PinB    3 // PA7

#if PWMCONTROL
  #define MotorIN1        0 // PA4
  #define MotorIN2        1 // PA5
#else
  #define MotorDIR        0 // PA4
  #define MotorPWM        1 // PA5
#endif

//from ramps 1.4 stepper driver
#define STEP_PIN        12 // PC2
#define DIR_PIN         11 // PC1
#define EnableLED       15 // PB6

volatile long encoder0Pos = 0;

long GetSteps = 0;

// PID default values 
struct MyObject {
  double kp;
  double ki;
  double kd;
};
MyObject PIDvals = {
  7.00, 0.04, 0.20 // defaut values for PID
};

double input = 0, output = 0, setpoint = 0, error = 0;
PID myPID(&input, &output, &setpoint, PIDvals.kp, PIDvals.ki, PIDvals.kd, DIRECT);  

long LastInterval = 0;
long previousMillis = 0;        // will store last time LED was updated
bool dir     = false;

// ---------------------- SETUP -----------------------
void setup() { 
  Serial.begin(9600);

  // get Saved (EEPROM) or default PID Values
  MyObject PIDv;
  EEPROM.get(EEPIDADDR, PIDv);
  if(isnan(PIDv.kp)){
     PIDv = {
        PIDvals.kp, PIDvals.ki, PIDvals.kd // defaut values
     };
  }
  myPID.SetTunings(PIDv.kp, PIDv.ki, PIDv.kd);
  Serial.println("Saved (EEPROM) or default PID Values:");
  Serial.println(PIDv.kp);
  Serial.println(PIDv.ki);
  Serial.println(PIDv.kd);

  // Set Pins 
  pinMode(encoder0PinA, INPUT); 
  pinMode(encoder0PinB, INPUT);  

#if PWMCONTROL
  pinMode(MotorIN1, OUTPUT); 
  pinMode(MotorIN2, OUTPUT);
#else
  pinMode(MotorDIR, OUTPUT); 
  pinMode(MotorPWM, OUTPUT);
#endif

  pinMode(EnableLED, OUTPUT);

  //motor control Pins
  pinMode(STEP_PIN, INPUT_PULLUP);
  pinMode(DIR_PIN, INPUT);

  // Interupts for position and target steps 
  attachInterrupt(digitalPinToInterrupt(encoder0PinA), doEncoderMotor0, CHANGE);  // encoderA pin on interrupt
  attachInterrupt(digitalPinToInterrupt(STEP_PIN),     countStep,       RISING);  // interrupt to count steppules

  myPID.SetMode(AUTOMATIC);     //set PID in Auto mode
  myPID.SetSampleTime(2);     // refresh rate of PID controller
  myPID.SetOutputLimits(-255, 255); // this is the MAX PWM value to move motor

  Serial.println("start");
  Serial.println("Position ToPosition MotorPWM RealPWM");
} 

// ---------------------- LOOP -----------------------
void loop(){

  byte n = Serial.available();
  if (n != 0) {
    MyObject PIDv;
    PIDv.kp = Serial.parseFloat();
    PIDv.ki = Serial.parseFloat();
    PIDv.kd = Serial.parseFloat();

    MyObject PIDvals = {
      PIDv.kp, PIDv.ki, PIDv.kd // defaut values
    };
    Serial.println("Input PID values saved in eeprom:");
    EEPROM.put(EEPIDADDR, PIDvals);

    myPID.SetTunings(PIDv.kp, PIDv.ki, PIDv.kd);

    Serial.println(PIDv.kp);
    Serial.println(PIDv.ki);
    Serial.println(PIDv.kd);
  }

  setpoint = GetSteps; // setpoint to Steps get from controller
  input = encoder0Pos; // real Position
  error = abs(setpoint - input);
  myPID.Compute();   // compute correct value
  int realpwm=0;
  if(error){
    realpwm = pwmOut(output);    // get PWM Value from PID calculated
  }
  else {
    realpwm = pwmOut(0);    // break
  }

  // Diganostic via serialplotter from arduino ide
  // Serial.println("Position ToPosition MotorPWM DIR");
  if(millis() - LastInterval > (abs(error) > 10 ? 100 : 1000)){

    if(output < PWMMIN){
      digitalWrite (EnableLED, HIGH); // signal that mcu is running
    }

    Serial.print(input);
    Serial.print(" ");
    Serial.print(setpoint);
    Serial.print(" ");
    Serial.print(output);
    Serial.print(" ");
    Serial.print(realpwm);
    Serial.println("");

    if(output < PWMMIN){
      digitalWrite (EnableLED, LOW);
    }
    LastInterval=millis();
  }
}

// ---------------------- SUBS -----------------------
#if PWMCONTROL
int pwmOut(int out) {
  int pwm = 0;
  if (out > 0) {
    // forward
    pwm = map(out, 0, 255, PWMMIN, PWMMAX );
    analogWrite ( MotorIN1, pwm );       
    digitalWrite ( MotorIN2, LOW );
  }
  else if (out < 0) {
    // reverse
    pwm = map(abs(out), 0, 255, PWMMIN, PWMMAX );
    digitalWrite ( MotorIN1, LOW );    // if REV < encoderValue motor move in reverse direction.   
    analogWrite ( MotorIN2, pwm );                      
  }
  else {
    // break
    digitalWrite ( MotorIN1, LOW );
    digitalWrite ( MotorIN2, LOW );
  }
  return pwm;
}
#else
void pwmOut(int out) {                               
  if (out > 0) {
    analogWrite( MotorPWM, out );       
    digitalWrite ( MotorDIR ,LOW );
  }
  else {
    analogWrite( MotorPWM, abs(out) );                      
    digitalWrite ( MotorDIR, HIGH );    // if REV < encoderValue motor move in reverse direction.   
  }
}
#endif

void doEncoderMotor0(){
  if (digitalRead(encoder0PinA) == HIGH) {   // found a low-to-high on channel A
    if (digitalRead(encoder0PinB) == LOW) {  // check channel B to see which way
                         // encoder is turning
      encoder0Pos = encoder0Pos - 1;         // CCW
    } 
    else {
      encoder0Pos = encoder0Pos + 1;         // CW
    }
  }
  else                                        // found a high-to-low on channel A
  { 
    if (digitalRead(encoder0PinB) == LOW) {   // check channel B to see which way
                          // encoder is turning  
      encoder0Pos = encoder0Pos + 1;          // CW
    } 
    else {
      encoder0Pos = encoder0Pos - 1;          // CCW
    }
  }
}

void countStep(){
  dir = digitalRead(DIR_PIN);
  if(dir == HIGH){
    GetSteps++;
  }
  else{
    GetSteps--;
  }
} 
SpenceKonde commented 1 year ago

Where did my response to this go?

That sketch was clearly derived from one of my PWM demo sketches for taking over TCA0, andyou're tripping over this:

#if defined(MILLIS_USE_TIMERA0)||defined(__AVR_ATtinyxy2__)
  #error "This sketch takes over TCA0, don't use for millis here.  Pin mappings on 8-pin parts are different"
#endif

But it doesn't look like your sketch actually takes over TCA0 (by calling takeOverTCA0() to make thecore pretend it doesn't exist and give you full control over it), or modifies the configuration of TCA0 unless one of those libraries which you haven't posted does do.

If never reconfigure TCA except by calling analogRead() on it, then just delete that block, since it doesn't apply - you are not taking over TCA0

If you are taking oiver TCA0 in one of those libraries, you must either, from the tools menu, disable millis or set it to use a different timer. The available timers on the gimped 0-series parts are just TCA0, TCB0, and the RTC.