Code:

Here is everything needed to get serial communication working between the arduino and linuxcnc:

ArcEye’s code

This is the linuxcnc side of things,

I did not write this, nor is it my code, I’m just posting it here for the full picture

In the code, make sure to update this:

#define DEVICE (Add your Arduino’s serial port here)

The following code is saved as “serialcon.comp” and put in the path using halcompile from terminal:

sudo halcompile --install ‘serialcon.comp’

/********************************************************************************
Serial communications with a userspace component

Had problems with a global variable int fd to hold the file descriptor
I had the serial init code called from the EXTRA_SETUP macro and the 
cleanup code called from the EXTRA_CLEANUP macro

Everything compiled fine and did not error when running
However it printed the strings to the terminal instead of sending them to /dev/ttyUSB0
Run a a commandline app it worked perfectly.

Appears the global was volatile in this generated component set up,
the main loop was not reading the original value
As 0, 1, and 2 are all pre-set values for stdin-out-err looks like value ended up as 
1 or 2 and wrote out to tty

Putting everything in main code and passing fd explicitly works fine.

*********************************************************************************/

component serialcon                 "This component services the arduino pendant";

pin in float xposition              "Receives current position from Xpos";
pin in float yposition              "Receives current position from Ypos";
pin in float zposition              "Receives current position from Zpos";

option singleton yes;               // makes no sense to have more than one of these components running
option userspace yes;

author "ArcEye arceye@mgware.co.uk";
license "GPL";
;;

#include <stdio.h>    /* Standard input/output definitions */
#include <stdlib.h> 
#include <stdint.h>   /* Standard types */
#include <string.h>   /* String function definitions */
#include <unistd.h>   /* UNIX standard function definitions */
#include <fcntl.h>    /* File control definitions */
#include <errno.h>    /* Error number definitions */
#include <termios.h>  /* POSIX terminal control definitions */
#include <sys/ioctl.h>

#define BAUDRATE B115200
#define DEVICE "/dev/ttyACM0"
#define _POSIX_SOURCE 1 /* POSIX compliant source */

    // predefs of later functions
void sendCommand(char);
int serialport_init();
                             
struct termios toptions;;       // port setup

void user_mainloop(void)
{
char buffer[50];
char oldbuffer[50];
char ch;

int fd = serialport_init();
//    bzero(oldbuffer, 50); 
    while(fd != -1)
        {
            //  approx 1/4 sec appears to be optimum period for a steady display with min lag
            //  may differ on another system with different thread speeds
        usleep(250000);
            // ************************************************************************************
            // IT DOESN'T MATTER IF THERE ARE NO OTHER INSTANCES ie SINGLETON, MUST USE THIS MACRO 
            // In this case, if you don't, no data gets written
            // ************************************************************************************
        FOR_ALL_INSTS()  
            { 
            // %08.03f = 8 digit including decimal point and sign, leading zeros & 3 digit precision with trailing zeros                  
            bzero(buffer, 50);  
            sprintf(buffer, "X%08.03fY%08.03fZ%08.03f", xposition, yposition, zposition );
//            if(strcmp(oldbuffer, buffer) != 0)
            write(fd, buffer, sizeof(buffer));                                                  
//            strcpy(oldbuffer, buffer);       
            if(read(fd,&ch,1) == 1)  // if command byte read from arduino
                sendCommand(ch);
            }           
        }

    close(fd);
    exit(0);
}

//######################################################################

int serialport_init()
{
int fd;
 
    fd = open(DEVICE, O_RDWR | O_NOCTTY | O_NDELAY);
    if (fd == -1)  
        {
        perror("init_serialport: Unable to open port ");
        return -1;
        }
    
    if (tcgetattr(fd, &toptions) < 0) 
        {
        perror("init_serialport: Couldn't get term attributes");
        return -1;
        }
    speed_t brate = BAUDRATE; 
    cfsetispeed(&toptions, brate);
    cfsetospeed(&toptions, brate);
    // 8N1
    toptions.c_cflag &= ~PARENB;
    toptions.c_cflag &= ~CSTOPB;
    toptions.c_cflag &= ~CSIZE;
    toptions.c_cflag |= CS8;
    // no flow control
    toptions.c_cflag &= ~CRTSCTS;

    toptions.c_cflag |= CREAD | CLOCAL;  // turn on READ & ignore ctrl lines
    toptions.c_iflag &= ~(IXON | IXOFF | IXANY); // turn off s/w flow ctrl

    toptions.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); // make raw
    toptions.c_oflag &= ~OPOST; // make raw

    // see: http://unixwiz.net/techtips/termios-vmin-vtime.html
    toptions.c_cc[VMIN]  = 0;
    toptions.c_cc[VTIME] = 20;
    
    if( tcsetattr(fd, TCSANOW, &toptions) < 0) 
        {
        perror("init_serialport: Couldn't set term attributes");
        return -1;
        }
    return fd;
}

Connect HAL Pins

Put these lines in the postgui.hal file for linuxcnc:


loadusr -W serialcon


net Xposition halui.axis.0.pos-commanded serialcon.xposition
net Yposition halui.axis.1.pos-commanded serialcon.yposition

Arduino code:

The beginning portion of the loop in this code is written by ArcEye, which reads the serial data.

The rest is just the tedious process of checking the coordinates against the electromagnet positions, job done!

//Serial stuff

#include <SoftwareSerial.h>
#include "Wire.h"

char XReading[8];  // 0000.000\0 pos
char YReading[8];
char ZReading[8];

int Xpos;
int Ypos;


void zeroX() {
  for (int x = 0; x < 8; x++) XReading[x] = 0;
}
void zeroY() {
  for (int x = 0; x < 8; x++) YReading[x] = 0;
}
void zeroZ() {
  for (int x = 0; x < 8; x++) ZReading[x] = 0;
}

//Coordinate stuff
#define x1y1 32
#define x1y2 33
#define x1y3 34

#define x2y1 35
#define x2y2 36
#define x2y3 37

#define x3y1 38
#define x3y2 38
#define x3y3 31

#define x4y1 30
#define x4y2 28
#define x4y3 29

#define x5y1 27
#define x5y2 26
#define x5y3 25

#define x6y1 24
#define x6y2 9
#define x6y3 8

#define x7y1 7
#define x7y2 6
#define x7y3 5

#define x8y1 4
#define x8y2 3
#define x8y3 2

int X1Y1[2] = { 4, 3 };
int X1Y2[2] = { 1, 23 };
int X1Y3[2] = { 3, 40 };

int X2Y1[2] = { 16, 3 };
int X2Y2[2] = { 13, 23 };
int X2Y3[2] = { 15, 40 };

int X3Y1[2] = { 28, 3 };
int X3Y2[2] = { 25, 23 };
int X3Y3[2] = { 27, 40 };

int X4Y1[2] = { 40, 3 };
int X4Y2[2] = { 37, 23 };
int X4Y3[2] = { 39, 40 };

int X5Y1[2] = { 52, 3 };
int X5Y2[2] = { 49, 23 };
int X5Y3[2] = { 51, 40 };

int X6Y1[2] = { 63, 3 };
int X6Y2[2] = { 61, 23 };
int X6Y3[2] = { 63, 40 };

int X7Y1[2] = { 76, 3 };
int X7Y2[2] = { 72, 23 };
int X7Y3[2] = { 74, 40 };

int X8Y1[2] = { 87, 3 };
int X8Y2[2] = { 84, 23 };
int X8Y3[2] = { 86, 40 };

int deviation = 1;


void setup() {
  Serial.begin(115200);

  zeroX();
  zeroY();
  zeroZ();

  pinMode(x1y1, OUTPUT);
  pinMode(x1y2, OUTPUT);
  pinMode(x1y3, OUTPUT);

  pinMode(x2y1, OUTPUT);
  pinMode(x2y2, OUTPUT);
  pinMode(x2y3, OUTPUT);

  pinMode(x3y1, OUTPUT);
  pinMode(x3y2, OUTPUT);
  pinMode(x3y3, OUTPUT);

  pinMode(x4y1, OUTPUT);
  pinMode(x4y2, OUTPUT);
  pinMode(x4y3, OUTPUT);

  pinMode(x5y1, OUTPUT);
  pinMode(x5y2, OUTPUT);
  pinMode(x5y3, OUTPUT);

  pinMode(x6y1, OUTPUT);
  pinMode(x6y2, OUTPUT);
  pinMode(x6y3, OUTPUT);

  pinMode(x7y1, OUTPUT);
  pinMode(x7y2, OUTPUT);
  pinMode(x7y3, OUTPUT);

  pinMode(x8y1, OUTPUT);
  pinMode(x8y2, OUTPUT);
  pinMode(x8y3, OUTPUT);
}

void loop() {
  int x;
  char ch;

  if (Serial.available() >= 9) {
    ch = Serial.read();
    switch (ch) {

      case 'X':
        while (Serial.available() < 8)
          delay(10);
        for (x = 0; x < 8; x++)
          XReading[x] = Serial.read();
        Xpos = atoi(&XReading[0]);

        zeroX();
        break;

      case 'Y':
        while (Serial.available() < 8)
          delay(10);
        for (x = 0; x < 8; x++)
          YReading[x] = Serial.read();
        Ypos = atoi(&YReading[0]);

        zeroY();
        break;

      default:
        break;
    }
  }

  //X1
  if (((Xpos > (X1Y1[0] - deviation)) && (Xpos < (X1Y1[0] + deviation))) && ((Ypos > (X1Y1[1] - deviation)) && (Ypos < (X1Y1[1] + deviation)))) {
    digitalWrite(x1y1, LOW);
  } else {
    digitalWrite(x1y1, HIGH);
  }

  if (((Xpos > (X1Y2[0] - deviation)) && (Xpos < (X1Y2[0] + deviation))) && ((Ypos > (X1Y2[1] - deviation)) && (Ypos < (X1Y2[1] + deviation)))) {
    digitalWrite(x1y2, LOW);
  } else {
    digitalWrite(x1y2, HIGH);
  }

  if (((Xpos > (X1Y3[0] - deviation)) && (Xpos < (X1Y3[0] + deviation))) && ((Ypos > (X1Y3[1] - deviation)) && (Ypos < (X1Y3[1] + deviation)))) {
    digitalWrite(x1y3, LOW);
  } else {
    digitalWrite(x1y3, HIGH);
  }


  //X2
  if (((Xpos > (X2Y1[0] - deviation)) && (Xpos < (X2Y1[0] + deviation))) && ((Ypos > (X2Y1[1] - deviation)) && (Ypos < (X2Y1[1] + deviation)))) {
    digitalWrite(x2y1, LOW);
  } else {
    digitalWrite(x2y1, HIGH);
  }

  if (((Xpos > (X2Y2[0] - deviation)) && (Xpos < (X2Y2[0] + deviation))) && ((Ypos > (X2Y2[1] - deviation)) && (Ypos < (X2Y2[1] + deviation)))) {
    digitalWrite(x2y2, LOW);
  } else {
    digitalWrite(x2y2, HIGH);
  }

  if (((Xpos > (X2Y3[0] - deviation)) && (Xpos < (X2Y3[0] + deviation))) && ((Ypos > (X2Y3[1] - deviation)) && (Ypos < (X2Y3[1] + deviation)))) {
    digitalWrite(x2y3, LOW);
  } else {
    digitalWrite(x2y3, HIGH);
  }

  //X3
  if (((Xpos > (X3Y1[0] - deviation)) && (Xpos < (X3Y1[0] + deviation))) && ((Ypos > (X3Y1[1] - deviation)) && (Ypos < (X3Y1[1] + deviation)))) {
    digitalWrite(x3y1, LOW);
  } else {
    digitalWrite(x3y1, HIGH);
  }

  if (((Xpos > (X3Y2[0] - deviation)) && (Xpos < (X3Y2[0] + deviation))) && ((Ypos > (X3Y2[1] - deviation)) && (Ypos < (X3Y2[1] + deviation)))) {
    digitalWrite(x3y2, LOW);
  } else {
    digitalWrite(x3y2, HIGH);
  }

  if (((Xpos > (X3Y3[0] - deviation)) && (Xpos < (X3Y3[0] + deviation))) && ((Ypos > (X3Y3[1] - deviation)) && (Ypos < (X3Y3[1] + deviation)))) {
    digitalWrite(x3y3, LOW);
  } else {
    digitalWrite(x3y3, HIGH);
  }


  //X4
  if (((Xpos > (X4Y1[0] - deviation)) && (Xpos < (X4Y1[0] + deviation))) && ((Ypos > (X4Y1[1] - deviation)) && (Ypos < (X4Y1[1] + deviation)))) {
    digitalWrite(x4y1, LOW);
  } else {
    digitalWrite(x4y1, HIGH);
  }

  if (((Xpos > (X4Y2[0] - deviation)) && (Xpos < (X4Y2[0] + deviation))) && ((Ypos > (X4Y2[1] - deviation)) && (Ypos < (X4Y2[1] + deviation)))) {
    digitalWrite(x4y2, LOW);
  } else {
    digitalWrite(x4y2, HIGH);
  }

  if (((Xpos > (X4Y3[0] - deviation)) && (Xpos < (X4Y3[0] + deviation))) && ((Ypos > (X4Y3[1] - deviation)) && (Ypos < (X4Y3[1] + deviation)))) {
    digitalWrite(x4y3, LOW);
  } else {
    digitalWrite(x4y3, HIGH);
  }


  //X5
  if (((Xpos > (X5Y1[0] - deviation)) && (Xpos < (X5Y1[0] + deviation))) && ((Ypos > (X5Y1[1] - deviation)) && (Ypos < (X5Y1[1] + deviation)))) {
    digitalWrite(x5y1, LOW);
  } else {
    digitalWrite(x5y1, HIGH);
  }

  if (((Xpos > (X5Y2[0] - deviation)) && (Xpos < (X5Y2[0] + deviation))) && ((Ypos > (X5Y2[1] - deviation)) && (Ypos < (X5Y2[1] + deviation)))) {
    digitalWrite(x5y2, LOW);
  } else {
    digitalWrite(x5y2, HIGH);
  }

  if (((Xpos > (X5Y3[0] - deviation)) && (Xpos < (X5Y3[0] + deviation))) && ((Ypos > (X5Y3[1] - deviation)) && (Ypos < (X5Y3[1] + deviation)))) {
    digitalWrite(x5y3, LOW);
  } else {
    digitalWrite(x5y3, HIGH);
  }


  //X6
  if (((Xpos > (X6Y1[0] - deviation)) && (Xpos < (X6Y1[0] + deviation))) && ((Ypos > (X6Y1[1] - deviation)) && (Ypos < (X6Y1[1] + deviation)))) {
    digitalWrite(x6y1, LOW);
  } else {
    digitalWrite(x6y1, HIGH);
  }

  if (((Xpos > (X6Y2[0] - deviation)) && (Xpos < (X6Y2[0] + deviation))) && ((Ypos > (X6Y2[1] - deviation)) && (Ypos < (X6Y2[1] + deviation)))) {
    digitalWrite(x6y2, LOW);
  } else {
    digitalWrite(x6y2, HIGH);
  }

  if (((Xpos > (X6Y3[0] - deviation)) && (Xpos < (X6Y3[0] + deviation))) && ((Ypos > (X6Y3[1] - deviation)) && (Ypos < (X6Y3[1] + deviation)))) {
    digitalWrite(x6y3, LOW);
  } else {
    digitalWrite(x6y3, HIGH);
  }


  //X7
  if (((Xpos > (X7Y1[0] - deviation)) && (Xpos < (X7Y1[0] + deviation))) && ((Ypos > (X7Y1[1] - deviation)) && (Ypos < (X7Y1[1] + deviation)))) {
    digitalWrite(x7y1, LOW);
  } else {
    digitalWrite(x7y1, HIGH);
  }

  if (((Xpos > (X7Y2[0] - deviation)) && (Xpos < (X7Y2[0] + deviation))) && ((Ypos > (X7Y2[1] - deviation)) && (Ypos < (X7Y2[1] + deviation)))) {
    digitalWrite(x7y2, LOW);
  } else {
    digitalWrite(x7y2, HIGH);
  }

  if (((Xpos > (X7Y3[0] - deviation)) && (Xpos < (X7Y3[0] + deviation))) && ((Ypos > (X7Y3[1] - deviation)) && (Ypos < (X7Y3[1] + deviation)))) {
    digitalWrite(x7y3, LOW);
  } else {
    digitalWrite(x7y3, HIGH);
  }

  //X8
  if (((Xpos > (X8Y1[0] - deviation)) && (Xpos < (X8Y1[0] + deviation))) && ((Ypos > (X8Y1[1] - deviation)) && (Ypos < (X8Y1[1] + deviation)))) {
    digitalWrite(x8y1, LOW);
  } else {
    digitalWrite(x8y1, HIGH);
  }

  if (((Xpos > (X8Y2[0] - deviation)) && (Xpos < (X8Y2[0] + deviation))) && ((Ypos > (X8Y2[1] - deviation)) && (Ypos < (X8Y2[1] + deviation)))) {
    digitalWrite(x8y2, LOW);
  } else {
    digitalWrite(x8y2, HIGH);
  }

  if (((Xpos > (X8Y3[0] - deviation)) && (Xpos < (X8Y3[0] + deviation))) && ((Ypos > (X8Y3[1] - deviation)) && (Ypos < (X8Y3[1] + deviation)))) {
    digitalWrite(x8y3, LOW);
  } else {
    digitalWrite(x8y3, HIGH);
  }
}
Next
Next

RC Snowblower