gergelytakacs/AutomationShield

MotoShield: Arduino API redesign (General notes and ideas)

gergelytakacs opened this issue ยท 7 comments

The MotoShield Arduino API needs serious redesign.

Issue-Label Bot is automatically applying the label feature_request to this issue, with a confidence of 0.81. Please mark this comment with ๐Ÿ‘ or ๐Ÿ‘Ž to give our bot feedback!

Links: app homepage, dashboard and code for this bot.

28.11.2019 Session notes

  • Try the current software (API) with the current hardware and get to know and learn it.
  • Read the API Guide #42
  • Try to write your own API for the MotoShield (Arduino).

Evening,
I wrote some basic methods for NEW API. Also there seems to be a defect on the Motor you provided me with. I think that the permanent-magnet wheel is scratching against of the Motor Housing.

I've filmed it. Link.

Header:

#ifndef MOTOSHIELD_H_ // don't define if its already defined condition
#define MOTOSHIELD_H_

#include "AutomationShield.h" //including AutomationShield library
#include "Arduino.h"    // including basic Arduino library

// defining the pins, MotoShield uses
#define MOTO_YPIN1      3  // hallsensor pin channel 1
#define MOTO_YPIN2      4  // hallsensor pin channel 2 
#define MOTO_UPIN       5  // PWM ~pin for turning on/off Engine Control Unit
#define MOTO_RPIN       4  // analog pin for potentiometer reference 

#define MOTO_DIR_PIN1   6  // direction pin1 for ECU
#define MOTO_DIR_PIN2   7  // direction pin2 for ECU

Class MotoShieldClass{
  public: 
    void begin();
    bool setDirecntion(bool direction = true);
    float referenceRead();
    void actuatorWrite(float percentValue);
    
  
  }

extern MotoShieldClass MotoShield
#endif

Cpp:

#include "MotoShield.h"
#include "AutomationShield.h"

//initialize hardware pins
//sets default spin direction - clockwise
void MotoShieldClass::begin() {
  pinMode(MOTO_YPIN1, INPUT);
  pinMode(MOTO_YPIN2, INPUT);
  pinMode(MOTO_RPIN, INPUT);
  pinMode(MOTO_UPIN, OUTPUT);
  pinMode(MOTO_DIR_PIN1,OUTPUT);
  pinMode(MOTO_DIR_PIN2,OUTPUT);
  digitalWrite(MOTO_DIR_PIN1, 0); //making setDirection() method non-obligatory
  digitalWrite(MOTO_DIR_PIN2, 1);    // THIS IS TEMPORARY
}

// Sets the direction motor - clockwise if input parameter is true
//                          - counterclockwise if input parameter is false
bool MotoShieldClass::setDirection(bool direction = true) { // default direction - clockwise
  if (direction) {  // clockwise      
    digitalWrite(MOTO_DIR_PIN1, 0);
    digitalWrite(MOTO_DIR_PIN2, 1);
  return 1; // method returns 1 if direction is set clockwise
  }
  else {             // counter-clockwise 
    digitalWrite(MOTO_DIR_PIN1, 1);
    digitalWrite(MOTO_DIR_PIN2, 0);
  return 0; // method returns 0 if direction is set counter-clockwise
  }
}

// Reads potentiometers reference value and returns it in %
float MotoShieldClass::referenceRead() {
  return AutomationShield.mapFloat((float)analogRead(MOTO_RPIN), 0.0, 1023.0, 0.0, 100.0);
}

// Sends PWM signal to ECU in %, thus determining Motors speed
void MotoShieldClass::actuatorWrite(float percentValue) {
  analogWrite(MOTO_UPIN, AutomationShield.percToPwm(percentValue));
}

void MotoShieldClass::sensorRead() {
  //problems occurred
}

MotoShieldClass MotoShield; // creates an object in MotoShieldClass 

*Note: Returning 0 or 1 from bool MotoShieldClass::setDirection(bool direction = true) method, I find very useful for further applications, e.g. changing rotation direction after certain amount of revolutions.

@xboldocky

Thank you, good work with the software. Please work on the RPM measurement and current measurement parts at this time, to properly finish up the Arduino API - as we have agreed during our personal consultation.

Hello,
I got really confused with current measurement and can't see the point of 4 ADC's for reading voltage. I presume the voltage from non-inverting OpAmp should be taken as a final value of voltage drop on 10kโ„ฆ resistor. However, I wrote a method for each possibility.
Also I updated the actuatorWrite() method so that motor writes minimal duty cycle for motor to spin and yet preserves the option of turning it off.
Sadly haven't managed to complete the method for measuring RPM yet. Wrote something completely useless.

Header:

#ifndef MOTOSHIELD_H_ //--don't define if its already defined condition
#define MOTOSHIELD_H_

#include "AutomationShield.h" //--including AutomationShield library
#include "Arduino.h"    //--including basic Arduino library

// defining the pins, MotoShield uses
#define MOTO_YPIN1      3  //--hallsensor pin channel 1
#define MOTO_YPIN2      4  //--hallsensor pin channel 2 
#define MOTO_UPIN       5  //--PWM ~pin for turning on/off Engine Control Unit 
#define MOTO_DIR_PIN1   6  //--direction pin1 for ECU
#define MOTO_DIR_PIN2   7  //--direction pin2 for ECU
#define MOTO_RPIN       4  //--analog pin for potentiometer reference
#define MOTO_YV1		0  //--analog pin for voltage before 10ohm resistor
#define MOTO_YV2		1  //--analog pin for voltage after 10ohm resistor
#define MOTO_YAMP1		2  //--analog pin for output of differential OpAmp
#define MOTO_YAMP2		3  //--analog pin for output of non-inverting OpAmp

#define MIN_PWM			30 //--minimal PWM duty cycle for motor to spin
#define AMP_GAIN		2.96 //--Gain of non-inverting OpAmp
#define R				10.0 //--resistance 10ohm for current measurement



class MotoShieldClass{
  public: 
    void begin();
    bool setDirection(bool direction);
    float referenceRead();
    void actuatorWrite(float percentValue);
    float sensorReadVoltage();
	float sensorReadVoltageAmp1();
	float sensorReadVoltageAmp2();
	float sensorReadCurrent();
	float MotoShieldClass::sensorReadRPM();
	void MotoShieldClass::ISR();
  
  };

extern MotoShieldClass MotoShield;
#endif

CPP:

#include "MotoShield.h"
#include "AutomationShield.h"
volatile unsigned long impulse=0;
float Ts=0.2; //--milisec # sample duration
float K=60.0/Ts/1000.0; //--60sec/Ts in sec # number of samples in minute

// Sets the direction motor - clockwise if input parameter is true
//                          - counterclockwise if input parameter is false
bool MotoShieldClass::setDirection(bool direction = true) { //--default direction - clockwise
  if (direction) {  //--clockwise      
    digitalWrite(MOTO_DIR_PIN1, 0);
    digitalWrite(MOTO_DIR_PIN2, 1);
  return 1; //--method returns 1 if direction is set clockwise
  }
  else {             //--counter-clockwise 
    digitalWrite(MOTO_DIR_PIN1, 1);
    digitalWrite(MOTO_DIR_PIN2, 0);
  return 0; //--method returns 0 if direction is set counter-clockwise
  }
}


void MotoShieldClass::ISR() {
	impulse++;
}

//--initialize hardware pins
//--sets default spin direction - clockwise
//--attachInterrupt
void MotoShieldClass::begin() {
  pinMode(MOTO_YPIN1, INPUT); 
  pinMode(MOTO_YPIN2, INPUT);
  pinMode(MOTO_RPIN, INPUT);
  pinMode(MOTO_UPIN, OUTPUT);
  pinMode(MOTO_DIR_PIN1,OUTPUT);
  pinMode(MOTO_DIR_PIN2,OUTPUT); 
  MotoShield.setDirection(true); //--making setDirection() method non-obligatory
  attachInterrupt(digitalPinToInterrupt(MOTO_YPIN1),MotoShield.ISR,RISING);
}

float MotoShieldClass::sensorReadRPM(){
	if(millis()>=millisplus){
		impulseTs = impulse - prevImpulse;
		return impulseTs/(7*Ts*K); //--7 impulses is one revolution
	millisplus = millis()+Ts;
	prevImpulse = impulse;
	}
}


//--Reads potentiometers reference value and returns it in percentage
float MotoShieldClass::referenceRead() {
  return AutomationShield.mapFloat((float)analogRead(MOTO_RPIN), 0.0, 1023.0, 0.0, 100.0);
}

//--Sends PWM signal to ECU in %, thus determining Motors speed
void MotoShieldClass::actuatorWrite(float percentValue) {
	//--When input is 0, motor is disabled
	if(percentValue < MIN_PWM && percentValue !=0) percentValue = MIN_PWM; 
	analogWrite(MOTO_UPIN, AutomationShield.percToPwm(percentValue));
}

//--Voltage difference before and after 10ohm resistor
float MotoShieldClass::sensorReadVoltage() {
  return (analogRead(MOTO_YV1)-analogRead(MOTO_YV2))*5.0/1023.0;
}

//--Output from differential OpAmp in Volt
float MotoShieldClass::sensorReadVoltageAmp1() {
  return analogRead(MOTO_YAMP1)*5.0/1023.0; 
}

//--Output from non-inverting OpAmp in Volt
float MotoShieldClass::sensorReadVoltageAmp2() {
  return analogRead(MOTO_YAMP2)*5.0/1023.0/AMP_GAIN;//--Gain of OpAmp is 2.96 
}

//--Current calculation - Ohms law
float MotoShieldClass::sensorReadCurrent() {
  return MotoShield.sensorReadVoltageAmp2()/R*1000.0;//--R is 10ohm # 1000 - conversion to mA
}

MotoShieldClass MotoShield; //--creates an object in MotoShieldClass 

RPM measurement and calibration method

I'm experiencing a horrific bug with calibration method. When Serial.print(_minRPM); isn't included, variables _minRPM and _maxRPM seem to acquire the same value. This makes mapping impossible, returned value from mapping function is inf because in the calculation value is divided by 0.

static volatile unsigned int count; //--counting pulses of hall sensor encoder
unsigned int counted;
float _Ts=50.0; //--sample duration
float _K=60000.0/(float)_Ts; //--minute to millisec / sample duration # number of samples in minute
int _minRPM;
int _maxRPM;
int _minDuty;

float MotoShieldClass::sensorReadRPM(){
	//--calculation of RPM
	return (float)counted/7.0*_K; //--7 is number of ticks in one rotation
}
float MotoShieldClass::sensorReadRPMPerc(){
	return AutomationShield.mapFloat(MotoShield.sensorReadRPM(), _minRPM, _maxRPM, 0.0, 100.0);
}

void MotoShieldClass::_InterruptServiceRoutine(){
	count++; //--incrementing +1 for every pulse
}

void MotoShieldClass::_InterruptSample(){
	counted = count;
	count = 0;
}

void MotoShieldClass::calibration(){
	int i = 25;
    do{
		MotoShield.actuatorWrite(i);
		delay(2500);
		if(counted >= 10){
			_minDuty = i;
			_minRPM = sensorReadRPM();
			Serial.print(_minRPM); //-- PRECO BEZ TOHTO NEFUNGUJE???
			MotoShield.actuatorWrite(0);
			break;
		}
	i++;
	}while(counted <= 10);
	MotoShield.actuatorWrite(100);
	delay(2500);
	_maxRPM = sensorReadRPM();
	MotoShield.actuatorWrite(0);
}

@xboldocky

I've been looking at your code for a while. I'm not really used to the 'do' cycles, and I'm afraid your logic here is a bit convoluted (to my taste). I cannot give you a definite answer, but could it be that the time it takes to Serial.print() has some role in there? That the issue is timing sensitive? If you'd call _minRPM as a function inside print() I could argue that it is called twice, but its not. So maybe try to add a delay and see if that helps?

@erik1392 @mgulan care to comment?