todbot / ServoEaser

Arduino library for servo easing
73 stars 18 forks source link

Fix division by zero #11

Closed FedericoBusero closed 2 years ago

FedericoBusero commented 2 years ago

There is a mistake in the time-based implementation of the ServoEaser library: it can cause a division by zero in case

Although this sound like a situation never to happen, it is in fact a situation that happens when e.g. a linear easer is used in combination with a remote control/rotary button, to ease to the new position.

I give an example where a rotary button is used (analogRead) to move the servo with a lineair ease set with a fixed speed (10 milliseconds per degree). So when the rotary button is not moved, the duration will be 0*10=0, causing a lot of divisions by zero. You will see e.g. New target position servo (degree): 83 currPos: nan <=== here is the division by zero currPos: 83.00 currPos: 83.00 currPos: 83.00 currPos: 83.00

#include <Servo.h>
#include "ServoEaser.h"

const int servoPin = 7;
const int analogPin = A0;
const unsigned long time_between_analogread = 500;

int servoFrameMillis = 0;  // minimum time between servo updates

Servo servo1;
ServoEaser servoEaser;

float linearTween (float t, float b, float c, float d) {
  return c * t / d + b;
}

void setup()
{
  Serial.begin(115200);
  Serial.println("ServoEaser Divide by zero test");

  pinMode(analogPin, INPUT);

  servo1.attach( servoPin );
  servoEaser.begin( servo1, servoFrameMillis );
  servoEaser.setEasingFunc( linearTween );
}

void loop()
{
  float currPos;
  int newpos;
  static unsigned long newanalogtime = millis() + time_between_analogread;

  servoEaser.update();

  currPos = servoEaser.getCurrPos();
  Serial.print("currPos: ");
  Serial.println( currPos );

  if (millis() >= newanalogtime)
  {
    newpos = map(analogRead(analogPin), 0, 1024, 40, 160);
    Serial.print("New target position servo (degree): ");
    Serial.println(newpos);

    servoEaser.easeTo( newpos, abs(newpos - currPos) * 10);

    newanalogtime += time_between_analogread;
  }
  else
  {
    delay(40);
  }
}
todbot commented 2 years ago

awesome thank you!