This forum uses cookies
This forum makes use of cookies to store your login information if you are registered, and your last visit if you are not. Cookies are small text documents stored on your computer; the cookies set by this forum can only be used on this website and pose no security risk. Cookies on this forum also track the specific topics you have read and when you last read them. Please confirm whether you accept or reject these cookies being set.

A cookie will be stored in your browser regardless of choice to prevent you being asked this question again. You will be able to change your cookie settings at any time using the link in the footer.

Thread Rating:
  • 0 Vote(s) - 0 Average
  • 1
  • 2
  • 3
  • 4
  • 5
drive questions.
#15
(2022-03-27, 05:02 PM)NousVoila Wrote: Thank you very much for your help. I'm starting to understand a little bit the electronic principle of the PMV.
I use pi zero 2 with img from Selian and motor.ino from Andreasw29 everything works fine but pin 11 is not used.
If I use the last ino on Github I get a badvoltage_fault.
I tried disabling the current direction but I still have a bad voltage.
I know that the mosfet I made works fine and pwm_mode = 2.
1st solution : program the ino of Andréas to use pin 11
2nd solution : program Sean's ino to not have bad voltage it's probably more complicated because I think that the shunts are not electronically designed in the same way
Sch from Andeasw29
https://github.com/AndreasW29/pypilot-ti...otmain.pdf

Arduino sketch : https://github.com/AndreasW29/pypilot-ti...controller

What would you do?
Johnm, I would try your sketch and a program to use tiny85 to make pwm.
No matter what if you use the motor controller you have you will have to do a bit of work.
At least some programing work..

I'd try solution2 first.
It's been a year since I worked on it  so sorry if I'm not right on.
To get motor.ino to do pwm had to free up timer2 to  run clutch and use timer0 for what timer2 was used for.
I'd do a diff between new motor.ini and the version the hardware is designed for.
Because of the change in timers you will see a lot of changes that you can ignore.
Also as I recall Sean has some grounded pins that are used as switches to determine  which code to use. May have to force mode changes in the code if not set properly..
I found it challenging to understand the code since it access the registers on the counter timers directly.
Have done it before but that was over 30 years ago.

In case you want to resort to external pwm attached schematic and code.
Should have fuse in output connected to the mosfet.
Can use the circuit your using now for the mosfet.
clutch output from motor controller goes to pint 2 of attiny85.
jP1 is esp programing socket. You can get some inexpensive programmers for attiny85.
My current setup has the clutch output from the motor controller go to pin 1 of the programing socket, effectively bypassing the attiny85.
.

Program is below.
It's pretty simple.
Used platformio. It's c++ but pretty sure it will pass as .ino
Full on delay is about  100ms.
pwm is about 30%.

..............................................................................................
#include <Arduino.h>
#include <avr/wdt.h>
int8_t clutch_pin=1;
int8_t clutch_in_pin=3;
uint8_t clutch_level=78;
int8_t clutch_on_time=90;
int8_t clutch_state=0; //0=off 1 on 2 pwm
unsigned long clutch_pwm_time;
int8_t clutch_input=0;
int8_t led=4;
void clutch_on()
{
  clutch_state=1;
  digitalWrite(clutch_pin, HIGH);
  clutch_pwm_time = millis() + clutch_on_time;
}

void clutch_pwm()
{
  clutch_state=2;
  analogWrite(clutch_pin,clutch_level);
 }
void clutch_off()
{
  clutch_state=0;
  digitalWrite(clutch_pin, LOW);
}
void setup()
{
  // initialize LED digital pin as an output.
  wdt_enable(WDTO_2S);
  pinMode(clutch_in_pin, INPUT);
  pinMode(clutch_pin, OUTPUT);
  pinMode(led, OUTPUT);
  clutch_off();
}


void loop()
{   
    wdt_reset();
    clutch_input=digitalRead(clutch_in_pin);
    //clutch_input=HIGH;
    //digitalWrite(led, HIGH);
    if (clutch_input == LOW)
    {
       if (clutch_state > 0)
       {
          clutch_off();
          digitalWrite(led, LOW);
      }
    }
    else  // input HIGH
    { digitalWrite(led, HIGH);
        if (clutch_state==0)
        {
           clutch_on();
           digitalWrite(led, HIGH);
        }
    }
     
        
    if (  clutch_state==1  )
    {
        if (millis() > clutch_pwm_time)
        {
           clutch_pwm();
        }
        
    }
   
}

..............................................................................................................


Attached Files
.pdf   clutch.pdf (Size: 33.92 KB / Downloads: 132)
Reply


Messages In This Thread
drive questions. - by johnm - 2020-08-28, 03:50 PM
RE: drive questions. - by seandepagnier - 2020-08-29, 09:07 PM
RE: drive questions. - by NousVoila - 2022-03-16, 09:02 PM
RE: drive questions. - by johnm - 2022-03-18, 01:18 AM
RE: drive questions. - by NousVoila - 2022-03-20, 10:44 PM
RE: drive questions. - by Jean-Marc Douroux - 2022-03-22, 02:41 PM
RE: drive questions. - by johnm - 2022-03-23, 04:58 PM
RE: drive questions. - by NousVoila - 2022-03-23, 09:09 PM
RE: drive questions. - by seandepagnier - 2022-03-24, 01:11 AM
RE: drive questions. - by johnm - 2022-03-25, 08:51 PM
RE: drive questions. - by NousVoila - 2022-03-25, 10:46 PM
RE: drive questions. - by johnm - 2022-03-26, 03:57 PM
RE: drive questions. - by NousVoila - 2022-03-27, 05:02 PM
RE: drive questions. - by johnm - 2022-03-27, 07:21 PM
RE: drive questions. - by seandepagnier - 2022-03-26, 03:05 AM
RE: drive questions. - by seandepagnier - 2022-03-27, 07:32 PM
RE: drive questions. - by NousVoila - 2022-03-28, 04:42 PM
RE: drive questions. - by seandepagnier - 2022-03-30, 03:07 AM
RE: drive questions. - by NousVoila - 2022-03-31, 02:52 PM
RE: drive questions. - by seandepagnier - 2022-03-31, 10:12 PM
RE: drive questions. - by NousVoila - 2022-03-31, 10:35 PM
RE: drive questions. - by seandepagnier - 2022-03-31, 11:38 PM

Forum Jump:


Users browsing this thread: 2 Guest(s)