//-----------------------------------------3DofDuino 0.01 - tonehack for gazz---------------------------------------
//-------------------------------Daniel Christiansen - X-Sim->Arduino mega Interface -------------------------------
//--------------------------------------daniel.christiansen@gmail.com ----------------------------------------------
//--------------------------------------------------USAGE-----------------------------------------------------------
// ##protocol##
// syntax:
// $<axis><value>#<checkvalue>*
// example:
// $X123#123*
// 1-axis example for x-sim2:
// ~36~X~a01~~35~~a01~~42~ // Axis in CAPITAL letters
// 3-axis example for x-sim2:
// ~36~X~a01~~35~~a01~~42~~36~Y~a02~~35~~a02~~42~~36~Z~a03~~35~~a03~~42~ // Axis in CAPITAL letters
// Use the USO output 16 bits - decimal - 115200 - 8 - NOPARITY - ONESTOPBIT
//--------------------------------------------------USAGE-----------------------------------------------------------
//--------------------------------------------Configuration---------------------------------------------------------
// ##Pin Assignment##
int rxOkLed = 32;
int rxNotOkLed = 33;
int ServoXPin = 7;
int ServoYPin = 8;
int tonePin = 9; //pin for rpmcounter
// ##Pin Assignment##
int servosMinValue = 0; // servos motion range minimum value
int servosMaxValue = 180; // servos motion range maximum value
unsigned int servoval = 90; // servos initial start point
//--------------------------------------------Configuration---------------------------------------------------------
#include <Servo.h>
Servo servoX;
Servo servoY;
Servo servoZ;
unsigned int charbuffer[50];
int bytesread = 0;
int serialchar;
int axis;
boolean packageRecieved = false;
boolean PackageVaild = false;
int packageLength;
void setup() {
Serial.begin(115200); // Connect to the serial port
pinMode(rxOkLed,OUTPUT); // Package verified led
pinMode(rxNotOkLed,OUTPUT); // Package Corrupt led
servoX.attach(ServoXPin);
servoY.attach(ServoYPin);
}
void loop () {
unsigned int axisValue;
unsigned int axisValueCheck;
if(Serial.available() > 0) {
serialchar = Serial.read();
// Serial.print("\nbyte: ");
// Serial.print(serialchar);
if (serialchar == 42){
packageRecieved = true;
packageLength = bytesread;
bytesread = 0;
// Serial.print("\nPackage recieved!!");
}
else {
if ((serialchar == 36) || (bytesread > 0) && (packageRecieved == false)) {
charbuffer[bytesread] = serialchar;
bytesread ++; // ready for next char
//Serial.print("\nbytesread: ");
//Serial.print(bytesread);
//Serial.print("\nbyte: ");
//Serial.print(serialchar);
}
}
}
digitalWrite(rxOkLed,LOW);
digitalWrite(rxNotOkLed,LOW);
if (packageRecieved == true){
int valueLength = (packageLength - 3) / 2;
int decMultiplier = 1;
axisValue = 0;
axisValueCheck= 0;
for (int i=valueLength; i > 0; i--){
axisValue = axisValue + ((charbuffer[i + 1 ] - 48) * decMultiplier);
axisValueCheck = axisValueCheck + ((charbuffer[i + valueLength + 2] - 48) * decMultiplier);
decMultiplier = decMultiplier * 10;
}
if (axisValue == axisValueCheck){
axis = charbuffer[1];
PackageVaild = true;
//Serial.print("\naxisValue: ");
//Serial.print(axisValue);
//Serial.print("\naxisValueCheck: ");
//Serial.print(axisValueCheck);
if (PackageVaild == true){
digitalWrite(rxOkLed,HIGH); // blink the OK led
switch (axis) {
case 88: //ascii for X
servoval = map(axisValue, 0, 65535, servosMinValue, servosMaxValue);
servoX.write(servoval);
break;
case 89: //ascii for Y
servoval = map(axisValue, 0, 65535, servosMinValue, servosMaxValue);
servoY.write(servoval);
break;
case 90://ascii for Z
servoval = map(axisValue, 0, 65535, 0, 433);
tone(tonePin,servoval);
}
}
}
else {
digitalWrite(rxNotOkLed,HIGH); //blink the Not OK led
}
packageRecieved = false; // were now done with this package - on to the next one
}
}
/*** TMC - Tippett Motion Control
**** Timer 0B - PMW Motor 1
**** Timer 1 - PID Timer Run PID Calculations every PIDDELAY (Currently 2500 for every 10ms)
****
****
**** TO control Motors change OCR2B, OCR0B, OCR0A
****
****/
#include <avr/io.h>
#include <stdio.h>
#include <stdlib.h>
#include <util/delay.h>
#include <avr/interrupt.h>
#include "pid.h"
#include "lcd.h"
#include <string.h>
#define NO_OF_POTS 3
#define NO_OF_AXIS 3
#define NO_OF_INPUTS (NO_OF_AXIS * 2)
#define potSensitivity 10
/* UART SERIAL DEFINES */
#define F_CPU 16000000UL
#define BAUD 9600
#define MYUBRR F_CPU/16/BAUD-1
#define PIDDELAY 2500
//Put in header file
void InitPIDTimer(void);
void ADC_Init(int preScaler, int tenBit);
//To Do. make these values editable via lcd and buttons
double K_P = 3;
double K_I = 35;
double K_D = 10;
//TO DO. DELETE THESE VARIABLES
volatile int desiredPosition;
volatile int actualPosition;
volatile uint8_t inputBuffer[NO_OF_INPUTS];
volatile uint8_t position;
struct Motors
{
uint16_t CurrentPosition;
uint16_t DesiredPosition;
struct PID_DATA PidData;
uint16_t PWMspeed;
} Motor1, Motor2, Motor3;
/* ADC METHODS */
// Initate ADC.
// Input prescaler amount, and 10bit or 8bit results
void ADC_Init(int preScaler, int tenBit)
{
ADCSRA |= (1 << ADEN); //Enable ADC
//To Do. Set Different prescalers.
if (preScaler == 128)
ADCSRA |= (1 << ADPS2) | (1 << ADPS1) | (1 << ADPS0); //set prescaler to 128
if (!tenBit)
ADMUX |= (1 << ADLAR); //Left adjust ADC result to allow easy 8 bit reading
ADMUX |= (1 << REFS0); //USE AVCC as refernece;
ADCSRA |= (1 << ADSC); //start first conversion
}
/***************/
/* PWM Methods */
void PWM_init(void)
{
/* Init Timer 0A PORT D6 or PORT 6 on Arduino */
DDRD |= (1 << DDD6);
// PD6 is now an output
OCR0A = 100;
// set PWM for 50% duty cycle
TCCR0A |= (1 << COM0A1);
// set none-inverting mode
TCCR0A |= (1 << WGM00); //PWM Phase Corrected
TCCR0B |= (1 << CS00);
// set prescaler to 8 and starts PWM
/* Init Timer 0B PORT D5 or PORT 5 on Arduino */
DDRD |= (1 << DDD5);
OCR0B = 128; // set PWM for 50% duty cycle
TCCR0A |= (1 << COM0B1);
// set none-inverting mode
OCR0B = 128;
/* INIT Timer 2B Port D3 or 3 oon Arduino*/
DDRD |= (1 << DDD3);
// PD6 is now an output
OCR2B = 150;
// set PWM for 50% duty cycle
TCCR2A |= (1 << COM2B1) | (1 << WGM20);
// set none-inverting mode & set PWM Phase correct Mode
TCCR2B |= (1 << CS21);
// set prescaler to 8 and starts PWM
}
/***************/
/* SERIAL METHODS */
/* SETUP UART */
void USART_Init( unsigned int ubrr)
{
/*Set baud rate */
UBRR0H = (unsigned char)(ubrr>>8);
UBRR0L = (unsigned char)ubrr;
/*Enable receiver and transmitter */
UCSR0B = (1<<RXEN0)|(1<<TXEN0);
/* Set frame format: 8data, 1stop bit */
UCSR0C = (3<<UCSZ00);
/*Turn on Receive Complete Interrupt*/
UCSR0B |= (1 << RXCIE0);
position = -1;
}
/******************/
void InitPIDTimer()
{
TCCR1B |= (1 << WGM12); // Configure timer 1 for CTC mode
TIMSK1 |= (1 << OCIE1A); // Enable CTC interrupt
TCCR1B |= ((1 << CS10) | (1 << CS11)); // Start timer at Fcpu/64
OCR1A = PIDDELAY;
}
void Init(void)
{
//Setup PID structs
pid_Init(K_P, K_I, K_D, &Motor1.PidData);
pid_Init(K_P, K_I, K_D, &Motor2.PidData);
pid_Init(K_P, K_I, K_D, &Motor3.PidData);
/* Init LCD */
lcd_init(LCD_DISP_ON);
/* Setup ADC */
//ADC_Init(128, 1);
/*Turn on Receive Complete Interrupt*/
UCSR0B |= (1 << RXCIE0);
/*Turn on ADC Interrupt */
ADCSRA |= (1 << ADIE);
//Turn on PORTB 12 to input
DDRB &= ~(1 << PINB4); //set input direction
lcd_clrscr();
lcd_puts("Init Okay");
}
int main(void)
{
PWM_init();
Init();
InitPIDTimer();
/* INITALISE SERIAL */
USART_Init(MYUBRR);
//turn on interrupts
sei();
int LCDCount = 0;
while (1)
{
if (LCDCount > 10000)
{
LCDCount = 0;
char Motor1String[7];
char Motor2String[7];
sprintf(Motor1String,"%u ", Motor1.DesiredPosition);
itoa(Motor1.PWMspeed, Motor2String, 10);
lcd_clrscr(); /* clear the screen*/
lcd_puts(Motor1String);
lcd_gotoxy(0,1);
lcd_puts(Motor2String);
Motor1.CurrentPosition += Motor1.PWMspeed;
Motor3.CurrentPosition += Motor3.PWMspeed;
}
LCDCount++;
}
}
/* INTERRUPTS */
//Timer 1A Interrupt
/*Every 10ms Calcualte the PWM value via pid_controller in pid.c*/
ISR(TIMER1_COMPA_vect)
{
Motor1.PWMspeed = pid_Controller(Motor1.DesiredPosition, Motor1.CurrentPosition, &Motor1.PidData);
Motor2.PWMspeed = pid_Controller(Motor2.DesiredPosition, Motor2.CurrentPosition, &Motor2.PidData);
Motor3.PWMspeed = pid_Controller(Motor3.DesiredPosition, Motor3.CurrentPosition, &Motor3.PidData);
}
//SERIAL INTERRUPT
ISR (USART_RX_vect)
{
int input = UDR0;
if (input == 'R')
{
position = 0;
}
else if ((input != 'E') && (position > -1))
{
if (position < NO_OF_INPUTS)
{
inputBuffer[position] = input;
position++;
}
else
{
//error; ignore and restart
position = -1;
}
}
else if (input == 'E')
{
if (position == 5)
{
/* Correct Packet Count Recevied. Commit Values */
Motor1.DesiredPosition = (inputBuffer[0] << 8) | inputBuffer[1];
Motor2.DesiredPosition = (inputBuffer[2] << 8) | inputBuffer[3];
Motor3.DesiredPosition = (inputBuffer[4] << 8) | inputBuffer[5];
}
position = -1;
}
}
//ADC INTERRUPT
ISR(ADC_vect)
{
switch (ADMUX)
{
case 0x40:
if ((Motor1.DesiredPosition > ADC + potSensitivity) || (Motor1.DesiredPosition < ADC - potSensitivity))
{
Motor1.DesiredPosition = ADC;
}
ADMUX = 0x41;
break;
case 0x41:
if ((Motor2.DesiredPosition > ADC + potSensitivity) || (Motor2.DesiredPosition < ADC - potSensitivity))
{
Motor2.DesiredPosition = ADC;
}
ADMUX = 0x42;
break;
case 0x42:
if ((Motor3.DesiredPosition > ADC + potSensitivity) || (Motor3.DesiredPosition < ADC - potSensitivity))
{
Motor3.DesiredPosition = ADC;
}
ADMUX = 0x40;
break;
}
ADCSRA |= (1 << ADSC); //next conversion
}
/*-----------------------------------------------3DofDuino 0.02-----------------------------------------------------
-------------------------------Daniel Christiansen - X-Sim->Arduino mega Interface -------------------------------
--------------------------------------daniel.christiansen@gmail.com ----------------------------------------------
--------------------------------------------------USAGE-----------------------------------------------------------
1) Modify The "Setup" Below. And define our outputs.
2) Configure X-Sim USO:
##protocol##
syntax:
$<value><axis><value><axis><value><axis>#
example:
$1234X4567Y89ABZ#
1-axis example for x-sim2:
~36~~a01~Y~~35~ // Axis in CAPITAL letters
3-axis example for x-sim2:
~36~~a01~Y~a02~X~a03~Z~35~ // Axis in CAPITAL letters
Use the USO output settings: 16 bits - HEX - 115200 - 8 - NOPARITY - ONESTOPBIT
--------------------------------------------------USAGE-----------------------------------------------------------
*/
//-----------------Includes---------------------
#include <Dans3dofServo.h> //should we only include this if we define servos?
#include <PID_v1.h> //likewise with pid
//--------------Servo Objects-------------------
Servo servo[6];//can we only create the amount we need? For now we create an array of six servos
//--------------PID Objects---------------------
const int numOfPids = 6;
int activePids = 0;
double pidInput[numOfPids];
double pidOutput[numOfPids];
double pidSetpoint[numOfPids];
// Adjust the P-I-D here - referrs to the order of definePwm
PID pid0(&pidInput[0], &pidOutput[0], &pidSetpoint[0],2,5,1, DIRECT);
PID pid1(&pidInput[1], &pidOutput[1], &pidSetpoint[1],2,5,1, DIRECT);
PID pid2(&pidInput[2], &pidOutput[2], &pidSetpoint[2],2,5,1, DIRECT);
PID pid3(&pidInput[3], &pidOutput[3], &pidSetpoint[3],2,5,1, DIRECT);
PID pid4(&pidInput[4], &pidOutput[4], &pidSetpoint[4],2,5,1, DIRECT);
PID pid5(&pidInput[5], &pidOutput[5], &pidSetpoint[5],2,5,1, DIRECT);
//------------Global variables-----------------
boolean debug;
boolean serialHeaderRecieved = false;
char inputString[50];
int numOfConfiguredOutputs = 0;
int numOfServos = 0;
int inputStringIndex=0;
unsigned int output[20][12];
//--------------Setup---------------------
//Change to match your setup
void setup() {
Serial.begin(115200); //set the serial rate
debug = false;
defineServo('X',9,0,255,32768);
definePwm('Y',45,0,1023,32768,50,51,0,52,20000);
}
/* Usage
Please declare the same number of axis as those configured in x-sim
defineServo('<axis from x-sim>',<pinnumber>,<rangeLow>,<rangeHigh>,<startpos>)
definepwm('<axis from x-sim>',<pwmOutputPin>,<rangeLow>,<rangeHigh>,<startpos>,<LimitSwLowPin>,<LimitSwHighPin><analog PID-feedbackPin><reversePin><pwm frequency)
Be aware that pins <44,45> <6,7,8> <2,3,5> are grouped together - changing the frequency for
one pin also changes the frequency for the other pins in that group.
<range> is the range of feedback for feedbackPin - typically 0-1023 for the analog input.
"Debug = true" prints a lot of stuff to the serial port -
Use serial monitor and send a corectly formatted package to see debugging messages
*/
void loop() {
//--------------Serial stuff---------------------
if (Serial.available()) {
// get the new byte:
char inChar = (char)Serial.read();
if (inChar == '$'){ //if the new byte is our header
inputStringIndex=0; //start at the beginning of our char array
serialHeaderRecieved = true; //
if (debug)
Serial.println("\nHeader found.");
}
if (inChar == '#'){ //if the new byte is our trailer :)
serialHeaderRecieved = false; // be ready for the next package
// Serial.println("\nEnd of Package found.");
}
if (serialHeaderRecieved == true) { // only begin joining our package when we have recievede a start-of-package
if ((inChar >= 'A' && inChar <= 'F') || (inChar >= '0' && inChar <= '9')){ //we only want HEX digits in our inputstring
inputString[inputStringIndex]= inChar; //add the chars to inputstring one at a time as they arrive.
inputStringIndex ++;
if (debug){
Serial.print("\nHex Digit Found: ");
Serial.print(inputString[inputStringIndex -1]);
}
}
else { //this byte is not a valid HEX caracter - maybe its an axis..
int inCharAsInt = inChar; //convert from char to integer
for (int i=0; i < numOfConfiguredOutputs; ++i){ //search the output array for an axis matching our recieved byte
if (output[i][0] == inCharAsInt){
if (debug){
Serial.print("\nOutput Axis found: ");
Serial.print(output[i][0]);
}
inputString[inputStringIndex] = '\0'; //finish our char array
output[i][5] = strtol(inputString,NULL,16);
inputStringIndex=0;
if (debug){
Serial.print(" With DEC-value: ");
Serial.print(output[i][5],DEC);
}
}
}
}
}
}
//--------------Output stuff---------------------
for (int i=0; i <= numOfConfiguredOutputs; i++){ // run through our outputs,
switch(output[i][2]) {
case 1: // Pwm
pidSetpoint[output[i][6]] = map(output[i][5], 0, 65535, output[i][3], output[i][4]); // where we would like to be
pidInput[output[i][6]] = analogRead(output[i][9]); //where we are
pidHandler(output[i][6],'C', NULL); //compute the error offset
if (pidOutput[output[i][6]] > 0 && pidSetpoint[output[i][6]] > pidInput[output[i][6]])
{
digitalWrite(output[i][10],LOW); // set reverse pin low - we are going forward
analogWrite(output[i][1],pidOutput[output[i][6]]); //send the corrected value to pwm pin
}
else if(pidOutput[output[i][6]] < 0 && pidSetpoint[output[i][6]] < pidInput[output[i][6]])
{
digitalWrite(output[i][10],HIGH); // set reverse pin High - we are reversing
analogWrite(output[i][1],(-1 * pidOutput[output[i][6]])); //send the corrected value to pwm pin
}
else
{
analogWrite(output[i][1],0); //motor stopped
digitalWrite(output[i][10],LOW); // set reverse pin low - we are going forward
}
if (debug){
Serial.print("\n Input value : ");
Serial.print(output[i][5],DEC);
Serial.print("\n scaling to match feedback : ");
Serial.print(pidSetpoint[output[i][6]],DEC);
Serial.print("\n feedback : ");
Serial.print(pidInput[output[i][6]],DEC);
Serial.print("\n pid correction : ");
Serial.print(pidOutput[output[i][6]],DEC);
}
break;
case 2: // Servo
unsigned int servoval = map(output[i][5], 0, 65535, output[i][3], output[i][4]); //scale it to match the specified motion range
if (servoval >= 0 && servoval < 256)
servo[output[i][6]].write(servoval);
break;
}
}
} // The END
//------------------Functions-----------------------
void pidHandler(int pidNum, int cmd, int pwmResolution){
switch (pidNum) {
case 0:
if (cmd == 'M'){
pid0.SetMode(AUTOMATIC);
pid0.SetOutputLimits((-1 * pwmResolution),pwmResolution);
}
if (cmd == 'C')
pid0.Compute();
break;
case 1:
if (cmd == 'M'){
pid1.SetMode(AUTOMATIC);
pid1.SetOutputLimits((-1 * pwmResolution),pwmResolution);
}
if (cmd == 'C')
pid1.Compute();
break;
case 2:
if (cmd == 'M'){
pid2.SetMode(AUTOMATIC);
pid2.SetOutputLimits((-1 * pwmResolution),pwmResolution);
}
if (cmd == 'C')
pid2.Compute();
break;
case 3:
if (cmd == 'M'){
pid3.SetMode(AUTOMATIC);
pid3.SetOutputLimits((-1 * pwmResolution),pwmResolution);
}
if (cmd == 'C')
pid3.Compute();
break;
case 4:
if (cmd == 'M'){
pid4.SetMode(AUTOMATIC);
pid4.SetOutputLimits((-1 * pwmResolution),pwmResolution);
}
if (cmd == 'C')
pid4.Compute();
break;
case 5:
if (cmd == 'M'){
pid5.SetMode(AUTOMATIC);
pid5.SetOutputLimits((-1 * pwmResolution),pwmResolution);
}
if (cmd == 'C')
pid5.Compute();
break;
}
}
void defineServo(int axis, int pinNum, unsigned int rangeLow, unsigned int rangeHigh, unsigned int startPos){
output[numOfConfiguredOutputs][0] = axis;
output[numOfConfiguredOutputs][1] = pinNum;
output[numOfConfiguredOutputs][2] = 2; //servo Type
output[numOfConfiguredOutputs][3] = rangeLow;
output[numOfConfiguredOutputs][4] = rangeHigh;
output[numOfConfiguredOutputs][5] = startPos; //is later value
output[numOfConfiguredOutputs][6] = numOfServos; //servo identifier
servo[numOfServos].attach(pinNum); //set the servo output pin
numOfConfiguredOutputs ++; //total number of outputs has increased by 1
numOfServos ++; //so has the total number of servos
if (debug){
Serial.print("\nServo ");
Serial.print(numOfServos);
Serial.print(" on pin ");
Serial.print(pinNum);
Serial.print(" attatched to axis: ");
char charAxis = axis;
Serial.print(charAxis);
}
}
void definePwm(int axis, int pinNum, unsigned int rangeLow, unsigned int rangeHigh, unsigned int startPos, int LimitSwLowPin, int LimitSwHighPin, int feedbackPin, int reversePin, int pwmFrequency){
output[numOfConfiguredOutputs][0] = axis;
output[numOfConfiguredOutputs][1] = pinNum;
output[numOfConfiguredOutputs][2] = 1; //PWM Type
output[numOfConfiguredOutputs][3] = rangeLow; //range start (Analog is at minimum 0) (quadcoder is at minimum 0)
output[numOfConfiguredOutputs][4] = rangeHigh; // range stop (analog is max 1023) (quadcoder can be at most 65535)
output[numOfConfiguredOutputs][5] = startPos; //will later be used as value
output[numOfConfiguredOutputs][6] = activePids; //our personal pid controller
output[numOfConfiguredOutputs][7] = LimitSwLowPin; //inputPin Used to signal end of travel LOW
output[numOfConfiguredOutputs][8] = LimitSwHighPin; //input Pin Used to signal end of travel High
output[numOfConfiguredOutputs][9] = feedbackPin; // analog input for positioning feedback
output[numOfConfiguredOutputs][10] = reversePin; //Pin Used to signal reverse
pinMode(output[numOfConfiguredOutputs][1], OUTPUT);
pinMode(output[numOfConfiguredOutputs][10], OUTPUT);
pinMode(output[numOfConfiguredOutputs][7], INPUT);
pinMode(output[numOfConfiguredOutputs][8], INPUT);
int Freq = pwmFreq(pwmFrequency,pinNum); //set frequency for pwm by manipulationg the correct timer -- returns the pwm resolution for this pin
pidHandler(activePids,'M',Freq); //set pid mode and activate current pid
numOfConfiguredOutputs ++; //total number of outputs has increased by 1
activePids ++; //so has the total number of Pids
}
int pwmFreq(int desiredFreq, int pinNum) {
int regCounter = 8000000 / desiredFreq; //cpu freq div by 2 = 8000000 / desired frequency = pwm resolution
if (pinNum == 2 || pinNum == 3 || pinNum == 5){ //timer 3
TCCR3A = B00101001; // Phase and frequency correct PWM change at OCRA
TCCR3B = B10001; // System clock
OCR3A = regCounter; // this is now our pwm resolution
}
if (pinNum == 6 || pinNum == 7 || pinNum == 8){ //timer 4
TCCR4A = B00101001; // Phase and frequency correct PWM change at OCRA
TCCR4B = B10001; // System clock
OCR4A = regCounter; // this is now our pwm resolution
}
if (pinNum == 44 || pinNum == 45){ //timer 5 (I didn't know that was here :-) cool huh
TCCR5A = B00101001; // Phase and frequency correct PWM change at OCRA
TCCR5B = B10001; // System clock
OCR5A = regCounter; // this is now our pwm resolution
}
return regCounter; // we will need tihs to scale our output to the pwm resolution
}
rainman2002z wrote:Ok think im having dumb moment, testing a rig with adruino uno r3 and adafruit motor server, two servos .. Learning curve with code .. But seeing error writing to com port as soon as click start - servos start to twitch but have tried all different setups but still error.. Outside of xsim all works not issues
Anyone got any ideas ??
Return to Controllers and Drivers
Users browsing this forum: No registered users and 3 guests