Added working code for dc motor speed controller and planner.

master
Martin 2018-10-13 22:19:06 +02:00
rodzic f105aa05b5
commit d79942d8f5
11 zmienionych plików z 305 dodań i 26 usunięć

Wyświetl plik

@ -1,5 +1,5 @@
# Teathimble
Teathimble is a minimalistic firmware intended to control variety of stepper motor based machines. It runs on most AVR (so arduino as well) microcontrollers and fits into ATmega16 MCU, providing great base for many projects. Teathimble is a trimmed fork of [Teacup](https://github.com/Traumflug/Teacup_Firmware) - lean and efficient firmware for RepRap printers by Triffid Hunter, Traumflug, jakepoz, many others.
Teathimble is a minimalistic firmware intended to control embroidery machines. It runs on most AVR (so arduino as well) microcontrollers and fits into ATmega32 MCU, providing great base for many projects. Teathimble is a trimmed fork of [Teacup](https://github.com/Traumflug/Teacup_Firmware) - lean and efficient firmware for RepRap printers by Triffid Hunter, Traumflug, jakepoz, many others.
## Features
- Minimalistic code.
@ -7,10 +7,11 @@ Teathimble is a minimalistic firmware intended to control variety of stepper mot
- True acceleration, interrupt based, with look-ahead and jerk calculation planning.
- Integer only math to save cpu cycles for performance boost.
- Up to 4 axis in straight or coreXY kinematics scheme.
- DC motor speed controller.
- Decent performance: can run up to 48'000 evenly spaced steps/second on 20 MHz as mentioned by core developers.
## Work progress
For coli winder machine check this [branch](https://gitlab.com/markol/Coil_winder). Current code is checked on custom made arduino-like board top on ATmega32 to control winder. It is just a matter of formality to port configurations on other avaiable boards. You might also need [this arduino core](https://github.com/MCUdude/MightyCore) to turn custom board into arduino compatible.
For coil winder machine check this [branch](https://gitlab.com/markol/Coil_winder). Current code is checked on custom made arduino-like board top on ATmega32 to control [simple embroidery machine](https://gitlab.com/markol/embroiderino) and coils winder. It is just a matter of formality to port configurations on other available boards. You might also need [this arduino core](https://github.com/MCUdude/MightyCore) to turn custom board into arduino compatible.
To run inside simple [simulator](https://reprap.org/wiki/SimulAVR) build project with enclosed makefile, this might be come in handy for development.
## Building
@ -33,7 +34,8 @@ Code is written in pure C.
|msg.c | For numbers parsing. |
|pinio.c | Initialize all I/O. |
|queue.c | The queue of moves received from the host. |
|sensors_control.c| DC motor speed controller implementation and needle position detection and processing. |
|serial.c | Serial buffers and communication management. |
|teathimble.ino.c| Code starts here. |
|teathimble.ino | Same as above, allows firmware to be built in Arduino IDE. |
|timer-avr.c | Timer management, used primarily by motor.c for timing steps. |
|timer-avr.c | Timer management, used primarily by motor.c for timing steps. |

Wyświetl plik

@ -88,7 +88,7 @@
Units: mm/s^2
Useful range: 1 to 10'000
*/
#define ACCELERATION 6000
#define ACCELERATION 2000
/** \def ENDSTOP_CLEARANCE
@ -155,7 +155,7 @@
to ignore jerk on an axis, define it to twice the maximum feedrate of this
axis.
Having these values too low results in more than neccessary slowdown at
Having these values too low results in more than necessary slowdown at
movement crossings, but is otherwise harmless. Too high values can result
in stepper motors suddenly stalling. If angles between movements in your
G-code are small and your printer runs through entire curves full speed,
@ -189,7 +189,7 @@
/** \def MOTHERBOARD
***************MOTHERBOARD***************
* Define this to use one of predefined configuratoins.
* Define this to use one of predefined configurations.
**/
//#define MOTHERBOARD 2
#include "boards.h"
@ -248,17 +248,88 @@
#define E_INVERT_ENABLE
*/
/** \def ENCODER_PIN
* ENCODER_PIN_A must be connected to INT1 pin for external interrupt to work!
* Motor encoder needs INT0 pin.
**/
#define ENCODER_PIN_A PD3
#define ENCODER_PIN_B PA4
#define INVERT_DIRECTION_ENCODER
#define PWR_OUT1_PIN 18
#define PWR_OUT2_PIN 19
/** \def PULSES_PER_TURN
* Motor encoder pulses per one machine shaft revolution.
* If encoder wheel is mounted on motor pulley for better resolution,
* its gear ratio must be taken into account. Every change of square wave from encoder
* counts as one tick so number of pulses per wheel revolution equals to number of blades doubled.
**/
#define PULSES_PER_TURN 84
/** \def MOTOR_SPEED
* Defines minimal and maximal functional speed of machine shaft in RPM
Units: revolutions/min, stitches/min
Sane values: 50 to 1900
Valid range: 1 to 3000
**/
#define MIN_MOTOR_SPEED 80
#define MAX_MOTOR_SPEED 400
/** \def KX_FACTOR
* Proportional and integral factor for speed controller.
* True value of the factor equals to: value / POINT_SHIFT
Sane values: 100 to 90000
Valid range: 1 to 900000
**/
#define KP_FACTOR 40000
#define KI_FACTOR 2000
/** \def ACCUMULATOR_LIMIT
* Limits for integral part of the controller. Higher values mean that controller
* remebers more errors in past and might make it unstable on varying load and speed changes.
* Don't exceed int 16 bit 32,768 value.
Sane values: 100 to 9000
Valid range: 0 to 32768
**/
#define ACCUMULATOR_LIMIT 4000
/** \def POINT_SHIFT
* PI controller uses fixed point arithmetic, change number of ZEROS for better or worse accuracy.
* Default value is enough in most cases, bigger numbers might cause overflow.
Sane values: 100 to 100000
Valid range: 1 to 1000000
**/
#define POINT_SHIFT 100000
#define PWR_OUT1_PIN PD4
#define PWR_OUT2_PIN PD5
#define ANALOG_IN_PIN 33
#define SWITCH1_PIN 34
#define SWITCH2_PIN 35
#define SWITCH3_PIN PD2
/** \def MAX_JUMP_LENGTH
* This parameter tells motor speed planner to use lowest defined speed
* for stitches of length close to this value.
Units: mm
Sane values: 5 to 16
Valid range: 1 to 200
**/
#define MAX_JUMP_LENGTH 12
/** \def JUMP_MOTOR_SPEED_DIFF_MAX
* This parameter tells motor speed planner to try keep maximal possible
* difference in speed between all jumps in range of this value.
Units: rpm
Sane values: 50 to 400
Valid range: 1 to 2000
**/
#define JUMP_MOTOR_SPEED_DIFF_MAX 100
#endif
/** \def MOVEBUFFER_SIZE

Wyświetl plik

@ -4,10 +4,12 @@
#include "homing.h"
#include "serial.h"
#include "gcode_parser.h"
#include "sensors_control.h"
GCODE_PARAM BSS gcode_params[8];
static volatile uint8_t current_parameter = 0;
uint8_t option_all_relative = 0;
int16_t speed_limit = 0;
TARGET BSS next_target;
// Parser is implemented as a finite state automata (DFA)
@ -92,6 +94,9 @@ uint8_t process_command()
case 'F':
next_target.F = decfloat_to_int(gcode_params[i].value, gcode_params[i].exponent, gcode_params[i].is_negative, 1);
break;
case 'S':
speed_limit = decfloat_to_int(gcode_params[i].value, gcode_params[i].exponent, gcode_params[i].is_negative, 1);
break;
}
}
// convert relative to absolute
@ -205,7 +210,7 @@ uint8_t process_command()
case 202: //set acceleration
break;
case 222: //set speed
desired_speed = speed_limit;
break;
default:
result = STATE_ERROR;

69
motor.c
Wyświetl plik

@ -9,12 +9,13 @@
#include <math.h>
#include "maths.h"
#include "kinematics.h"
#include "kinematics.h"
#include "timer.h"
#include "serial.h"
#include "queue.h"
#include "pinio.h"
#include "sensors_control.h"
/*
position tracking
@ -140,12 +141,12 @@ void dda_create(DDA *dda, const TARGET *target) {
axes_int32_t steps;
uint32_t distance, c_limit, c_limit_calc;
uint8_t i;
static DDA* prev_dda = NULL;
#ifdef LOOKAHEAD
// Number the moves to identify them; allowed to overflow.
static uint8_t idcnt = 0;
static DDA* prev_dda = NULL;
if ((prev_dda && prev_dda->done) || dda->waitfor)
if (prev_dda && prev_dda->done)
prev_dda = NULL;
#endif
@ -394,25 +395,79 @@ void dda_create(DDA *dda, const TARGET *target) {
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
serial_writestr_P(PSTR("] }\n"));
// now prepare speed values for dc motor
if (dda->waitfor)
{
// calculate dc motor speed according to distance, is linear interpolation ok here?
int16_t dc_motor_speed = MIN_MOTOR_SPEED + ((MAX_MOTOR_SPEED - MIN_MOTOR_SPEED) * ((int32_t)(distance - MAX_JUMP_LENGTH*1000) / (1 - MAX_JUMP_LENGTH))) / 1000;
if(dc_motor_speed > MAX_MOTOR_SPEED) dc_motor_speed = MAX_MOTOR_SPEED;
else if(dc_motor_speed < MIN_MOTOR_SPEED) dc_motor_speed = MIN_MOTOR_SPEED;
if(dc_motor_speed > 0)
{
if(prev_dda)
{
// start spinning motor slowly
if(prev_dda->dc_motor_speed == 0)
dc_motor_speed = MIN_MOTOR_SPEED;
// speed up, decrease current dda speed if needed
else if(dc_motor_speed - prev_dda->dc_motor_speed > JUMP_MOTOR_SPEED_DIFF_MAX )
dc_motor_speed = prev_dda->dc_motor_speed + JUMP_MOTOR_SPEED_DIFF_MAX;
// slow down, decrease previous dda speed if needed
else if(prev_dda->dc_motor_speed - dc_motor_speed > JUMP_MOTOR_SPEED_DIFF_MAX )
prev_dda->dc_motor_speed = dc_motor_speed + JUMP_MOTOR_SPEED_DIFF_MAX;
}
else // no previous movement, start slowly as well
dc_motor_speed = MIN_MOTOR_SPEED;
}
dda->dc_motor_speed = dc_motor_speed;
}
// other kind of movement requires motor to be stopped
else
{
dda->dc_motor_speed = 0;
}
// end of motor speed planner
// next dda starts where we finish
memcpy(&startpoint, &dda->endpoint, sizeof(TARGET));
#ifdef LOOKAHEAD
prev_dda = dda;
#endif
}
void dda_start(DDA *dda) {
// called from interrupt context: keep it simple!
// apply dc motor speed
uint8_t queue_elements = queue_current_size();
if(dda->dc_motor_speed == 0 )
stop_dc_motor();
else
{
// slow down on almost empty buffer
if(queue_elements < 4)
{
desired_speed = dda->dc_motor_speed / 2;
if(desired_speed < MIN_MOTOR_SPEED)
desired_speed = MIN_MOTOR_SPEED;
}
else // just use planned speed value from dda
desired_speed = dda->dc_motor_speed;
}
if (dda->endstop_check)
endstops_on();
#ifdef TRIGGERED_MOVEMENT
// if movement dda in not allowed yet
// if stepper movement dda is not allowed yet
else if(dda->waitfor)
return;
#endif
// buffer is empty, this is probably last move
if(queue_elements == 0)
desired_speed = 0;
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
#ifdef STEPS_PER_M_Z
sersendf_P(PSTR("Start: X %lq Y %lq Z %lq F %lu\n"),

Wyświetl plik

@ -162,6 +162,8 @@ typedef struct {
/// Endstop homing
uint8_t endstop_check; ///< Do we need to check endstops? 0x1=Check X, 0x2=Check Y, 0x4=Check Z
uint8_t endstop_stop_cond; ///< Endstop condition on which to stop motion: 0=Stop on detrigger, 1=Stop on trigger
int16_t dc_motor_speed; /// speed change for spindle motor
}__attribute__ ((__packed__)) DDA;
/*

Wyświetl plik

@ -46,6 +46,11 @@ uint8_t queue_empty() {
return result;
}
uint8_t queue_current_size()
{
return mb_tail > mb_head ? (MOVEBUFFER_SIZE - mb_tail + mb_head) : (mb_head - mb_tail);
}
DDA *queue_current_movement() {
DDA* current;

Wyświetl plik

@ -16,6 +16,7 @@ extern DDA *mb_tail_dda;
uint8_t queue_full(void);
uint8_t queue_empty(void);
void queue_flush(void);
uint8_t queue_current_size();
#ifdef __cplusplus
}
#endif

Wyświetl plik

@ -1,23 +1,145 @@
#include "sensors_control.h"
uint8_t last_direction = 0;
uint8_t stop_motor_flag = 0;
uint8_t interrupt_ticks = 0;
uint16_t motor_pulses = 0;
// Init INT0 and INT1 interrupts for optical sensors
int32_t ki, kp;
int16_t error_speed_sum;
int16_t desired_speed, error_speed;
// Init INT0 and INT1 interrupts for optical sensors, init pwm and timers for dc motor speed controller
void sensing_init()
{
// externally trigged interrupts setup
MCUCR |= (1<<ISC01)|(1<<ISC11)|(1<<ISC10); /* INT0 - falling edge, INT1 - raising edge */
//MCUCR |= (1<<ISC00)|(1<<ISC10); /* INT0 - any change, INT1 - any change */
GICR |= (1<<INT0)|(1<<INT1); /* enable INT0 and INT1 */
PULL_OFF(PD2);
PULL_OFF(PD2);
PULL_OFF(ENCODER_PIN_A);
PULL_OFF(ENCODER_PIN_B);
SET_INPUT(PD2);
SET_INPUT(ENCODER_PIN_A);
SET_INPUT(ENCODER_PIN_B);
#if defined (__AVR_ATmega32U4__) || defined (__AVR_ATmega32__) || \
defined (__AVR_ATmega16__)
// externally trigged interrupts setup
MCUCR |= MASK(ISC00) | MASK(ISC11) | MASK(ISC10); /* INT0 - any change, INT1 - raising edge */
GICR |= MASK(INT0) | MASK(INT1); /* enable INT0 and INT1 */
// setup PWM timers: fast PWM
// Warning: these are not consistent across all AVRs
TCCR0 = MASK(WGM01) | MASK(WGM00) | MASK(COM01);
// pwm frequency
#ifndef FAST_PWM
TCCR0 |= MASK(CS02); // F_CPU / 256
#else
TCCR0 |= MASK(CS01); // F_CPU / 8
#endif
#define MOTOR_PWM OCR0
OCR0 = 0;
PB4_DDR = 0xFF;
// timer 1 is used for stepping
TCCR2 = MASK(CS20) | MASK(CS21) | MASK(CS22); // F_CPU / 256 / 1024
OCR2 = 0;
// enable timer overflow int
TIMSK |= MASK(TOIE2);
#else
// externally trigged interrupts setup
EICRA |= MASK(ISC00) | MASK(ISC11) | MASK(ISC10); /* INT0 - any logic change INT1 - raising edge */
EIMSK |= MASK(INT0) | MASK(INT1); /* enable INT0 and INT1 */
// timer 1 is used for stepping
// PWM frequencies in TCCR2B, see page 156 of the ATmega644 reference.
TCCR2A = 0;
TCCR2B = MASK(CS20) | MASK(CS21) | MASK(CS22); // F_CPU / 256 / 1024
OCR2A = 0;
OCR2B = 0;
// pwm frequency
#ifndef FAST_PWM
TCCR0B = (TCCR0B & 0b11111000) | 0x04;
#else
TCCR0B = (TCCR0B & 0b11111000) | 0x02;
#endif
#define MOTOR_PWM OCR0A
OCR0A = 0;
OCR0B = 0;
PD6_DDR = 0xFF;
// enable timer overflow int
TIMSK2 = MASK(TOIE2);
#endif
error_speed = desired_speed = error_speed_sum = 0;
kp = KP_FACTOR;
ki = KI_FACTOR;
}
void set_dc_motor_speed(int16_t value)
{
desired_speed = value;
}
// activates stop of the the motor on needle interrupt
void stop_dc_motor()
{
if(desired_speed == 0) return;
desired_speed = MIN_MOTOR_SPEED;
stop_motor_flag = 1;
}
//PI control update procedure
void update_dc_motor()
{
int16_t pwm_pulse;
if (desired_speed > 3 )
{
if(interrupt_ticks <= 0) return;
// ticking interrupt is called at about 61 Hz rate
uint8_t time_interval = (F_CPU / 256 / 1024 / interrupt_ticks);
//calculate motor speed, unit is decimal rpm
int16_t pv_speed = ( 60 * (motor_pulses*POINT_SHIFT/PULSES_PER_TURN) * time_interval ) / POINT_SHIFT;
interrupt_ticks = 0;
motor_pulses = 0;
error_speed = desired_speed - pv_speed;
pwm_pulse = (int32_t)(((int32_t) error_speed*kp) + ((int32_t) error_speed_sum*ki)) / POINT_SHIFT;
error_speed_sum += error_speed; //sum of error
// integral limitation
if (error_speed_sum >ACCUMULATOR_LIMIT) error_speed_sum = ACCUMULATOR_LIMIT;
else if (error_speed_sum < -ACCUMULATOR_LIMIT) error_speed_sum = -ACCUMULATOR_LIMIT;
}
else
{
error_speed = 0;
error_speed_sum = 0;
pwm_pulse = 0;
interrupt_ticks = 0;
}
// set new motor power
if (pwm_pulse < 255 && pwm_pulse > 0)
{
MOTOR_PWM = pwm_pulse;
}
else
{
if (pwm_pulse>255)
{
MOTOR_PWM = 255;
}
else
{
MOTOR_PWM = 0;
}
}
}
// needle interrupt
// needle interrupt
ISR(INT1_vect)
{
// check if second sensor is trigged to estimate needle direction
@ -27,8 +149,13 @@ ISR(INT1_vect)
if(last_direction)
return;
last_direction = 1;
if(stop_motor_flag)
{
desired_speed = 0;
stop_motor_flag = 0;
}
//serial_writestr_P(PSTR("int1 up\n"));
if(mb_tail_dda &&!mb_tail_dda->live)
if(mb_tail_dda && !mb_tail_dda->live)
{
mb_tail_dda->waitfor = 0;
dda_start(mb_tail_dda);
@ -45,10 +172,15 @@ ISR(INT1_vect)
}
}
// motor rotary encoder interrupt
// motor rotary encoder interrupt for speed measurement
ISR(INT0_vect)
{
++motor_pulses;
}
// timer tick interrupt
ISR(TIMER2_OVF_vect)
{
++interrupt_ticks;
}

Wyświetl plik

@ -10,10 +10,14 @@
#define direction_encoder() (READ(ENCODER_PIN_B)?0:1)
#endif
extern int16_t desired_speed;
void stop_dc_motor();
#ifdef __cplusplus
extern "C" {
#endif
void sensing_init();
void update_dc_motor();
#ifdef __cplusplus
}
#endif

Wyświetl plik

@ -44,5 +44,6 @@ void loop()
}
}
}
update_dc_motor();
}
#endif

Wyświetl plik

@ -57,5 +57,6 @@ void loop()
}
}
}
update_dc_motor();
}
#endif