SatNOGS Arduino Uno/CNC Shield Based Rotator Controller
Contents
Controlling the rotator as a stand alone system using GPredict
The SatNOGS rotator is primarily designed to be used as a system component that is part of a SatNOGS ground station. There may be occasion when it is desirable to have a stand alone ground station that is removed from the SatNOGS network. This can be done using existing equipment but can also be simplified using off the shelf components.
The following information is to connect your Rotator controller DIRECTLY TO A PC. If you'd like to still use it with the Raspberry Pi then you must keep the RS485 protocol in place.
We will need slightly different hardware and modified software to achieve this, the main changes will be to remove the RS485 and watchdog parts of the firmware. We will be using the following items:
Hardware
- SatNOGS Rotator V3.1 hardware
- Arduino Uno R3
- CNC Shield V3 with A4988 drivers
- NEMA 17 Stepper Motors
- 2x microswitches
- Suitable 12v power supply (The shield will accept between 12v and 36v)
- Cables to connect the Arduino to the PC
Software
For the purposes of this article we will be using Windows software. The same result can be achieved with Linux or Mac OS but for clarity these options have been ignored for the time being. We will need:
- A copy of the Arduino IDE (version 1.8.5 has been used as part of this tutorial)
- GPredict
- Hamlib
- A text editor such as Notepad++ for a small script
Method
Hardware setup
We will not be using the custom SatNOGS PCB
Software setup
We will need to modify two elements of the firmware, easycomm.h and rotator_pins.h. These changes are necessary to stop their being conflicts with the communication between boards and PC as well as re-assigning pins to match the CNC shield. We'll modify the rotator_pins.h first
I'm not using the custom SatNOGS pcb. I'm using a standard Arduino Uno with a CNC shield with A4988's, which has GREATLY simplified the project as they're all off the shelf, preassembled, inexpensive components... The Uno, stepper drivers, stepper motors, and shield came to about $60CAD on Amazon Prime, and electronically everything was working within an hour of the parts showing up. In order to do this I've made a few tweaks to the code to take advantage of parts I already have laying around... I'm using: Arduino Uno R3 clone Arduino CNC Shield V3 with 4x A4988's (only 2 in use) https://www.amazon.ca/gp/product/B016O7TD6O/ref=ppx_yo_dt_b_asin_title_o00__o00_s00?ie=UTF8&psc=1 Nema 17 Stepper Motors https://www.amazon.ca/gp/product/B06ZXQXD9X/ref=ppx_yo_dt_b_asin_title_o01__o00_s00?ie=UTF8&th=1 Gpredict on Windows 10 PC Rotctl
Currently I've modified easycomms.h to use Serial communications instead of RS485, which lets you connect the arduino to the pc directly without any adapter cables or modifications. I plan on adding the SatNOGS Pi Groundstation at a later time, my primary goal is to track satellites to enable capturing of HRPT.
I also had to modify the rotator_pins.h library to fix a few of the pinouts which changed when I used the CNC shield.
Here's the pinout thats working for me at the moment.
/*! * @file rotator_pins.h * * It is a header file for pin mapping. * * Licensed under the GPLv3 * */
#ifndef ROTATOR_PINS_H_ #define ROTATOR_PINS_H_
//#define M1IN1 10 ///< Motor 1 PWM pin #define M1IN1 2 ///< Motor 1 PWM pin #define M1IN2 5 ///< Motor 1 PWM pin #define M1SF 7 ///< Motor 1 digital input, status flag for DC Motor Drivers #define M1FB A1 ///< Motor 1 analog input, current/load feedback for DC Motor Drivers
#define M2IN1 3 ///< Motor 2 PWM pin #define M2IN2 6 ///< Motor 2 PWM pin #define M2SF 7 ///< Motor 2 digital input, status flag for DC Motor Drivers #define M2FB A0 ///< Motor 2 analog input, current/load feedback for DC Motor Drivers
#define MOTOR_EN 8 ///< Digital output, to enable the motors
#define SW1 11 ///< Digital input, to read the status of end-stop for motor 1 #define SW2 9 ///< Digital input, to read the status of end-stop for motor 2
#define RS485_DIR 2 ///< Digital output, to set the direction of RS485 communication
#define SDA_PIN 3 ///< I2C data pin #define SCL_PIN 4 ///< I2C clock pin
#define PIN12 12 ///< General purpose I/O pin #define PIN13 13 ///< General purpose I/O pin #define A2 A2 ///< General purpose I/O & analog pin #define A3 A3 ///< General purpose I/O & analog pin
#endif /* ROTATOR_PINS_H_ */
This will setup the arduino to talk directly to the PC and bypass the Pi completely..... I can connect the Arduino directly to my PC and control it via Gpredict.
I did this by editing the easycomm.h file. I basically removed every call to the RS485 library (which allows communications between the Pi and the Arduino directly) and replaced each 'rs485' with 'Serial' instead....
here's the edited easycomm.h file so that you can use the arduino sketch directly with gpredict and a PC.
/*! * @file easycomm.h * * It is a driver for easycomm 3 protocol as referred, in Hamlib. * * Licensed under the GPLv3 * */
#ifndef LIBRARIES_EASYCOMM_H_ #define LIBRARIES_EASYCOMM_H_
#include <Arduino.h> #include <WString.h> #include <avr/wdt.h> //#include "rs485.h" #include "rotator_pins.h" #include "globals.h"
#define RS485_TX_TIME 9 ///< Delay "t"ms to write in serial for RS485 implementation #define BUFFER_SIZE 256 ///< Set the size of serial buffer #define BAUDRATE 19200 ///< Set the Baudrate of easycomm 3 protocol
//rs485 rs485(RS485_DIR, RS485_TX_TIME);
/**************************************************************************/ /*! @brief Class that functions for easycomm 3 implementation */ /**************************************************************************/ class easycomm { public:
/**************************************************************************/ /*! @brief Initialize the RS485 bus */ /**************************************************************************/ void easycomm_init() { // rs485.begin(BAUDRATE); Serial.begin(9600); }
/**************************************************************************/ /*! @brief Get the commands from RS485 and response to the client */ /**************************************************************************/ void easycomm_proc() { char buffer[BUFFER_SIZE]; char incomingByte; char *Data = buffer; char *rawData; static uint16_t BufferCnt = 0; char data[100]; String str1, str2, str3, str4, str5, str6;
// Read from serial while (Serial.available() > 0) { incomingByte = Serial.read();
// Read new data, '\n' means new pacakage if (incomingByte == '\n' || incomingByte == '\r') { buffer[BufferCnt] = 0; if (buffer[0] == 'A' && buffer[1] == 'Z') { if (buffer[2] == ' ' && buffer[3] == 'E' && buffer[4] == 'L') { // Send current absolute position in deg str1 = String("AZ"); str2 = String(control_az.input, 1); str3 = String(" EL"); str4 = String(control_el.input, 1); str5 = String("\n"); Serial.print(str1 + str2 + str3 + str4 + str5); } else { // Get the absolute position in deg for azimuth rotator.control_mode = position; rawData = strtok_r(Data, " ", &Data); strncpy(data, rawData + 2, 10); if (isNumber(data)) { control_az.setpoint = atof(data); } // Get the absolute position in deg for elevation rawData = strtok_r(Data, " ", &Data); if (rawData[0] == 'E' && rawData[1] == 'L') { strncpy(data, rawData + 2, 10); if (isNumber(data)) { control_el.setpoint = atof(data); } } } } else if (buffer[0] == 'E' && buffer[1] == 'L') { // Get the absolute position in deg for elevation rotator.control_mode = position; rawData = strtok_r(Data, " ", &Data); if (rawData[0] == 'E' && rawData[1] == 'L') { strncpy(data, rawData + 2, 10); if (isNumber(data)) { control_el.setpoint = atof(data); } } } else if (buffer[0] == 'V' && buffer[1] == 'U') { // Elevation increase speed in mdeg/s rotator.control_mode = speed; strncpy(data, Data + 2, 10); if (isNumber(data)) { // Convert to deg/s control_el.setpoint_speed = atof(data) / 1000; } } else if (buffer[0] == 'V' && buffer[1] == 'D') { // Elevation decrease speed in mdeg/s rotator.control_mode = speed; strncpy(data, Data + 2, 10); if (isNumber(data)) { // Convert to deg/s control_el.setpoint_speed = - atof(data) / 1000; } } else if (buffer[0] == 'V' && buffer[1] == 'L') { // Azimuth increase speed in mdeg/s rotator.control_mode = speed; strncpy(data, Data + 2, 10); if (isNumber(data)) { // Convert to deg/s control_az.setpoint_speed = atof(data) / 1000; } } else if (buffer[0] == 'V' && buffer[1] == 'R') { // Azimuth decrease speed in mdeg/s rotator.control_mode = speed; strncpy(data, Data + 2, 10); if (isNumber(data)) { // Convert to deg/s control_az.setpoint_speed = - atof(data) / 1000; } } else if (buffer[0] == 'S' && buffer[1] == 'A' && buffer[2] == ' ' && buffer[3] == 'S' && buffer[4] == 'E') { // Stop Moving rotator.control_mode = position; str1 = String("AZ"); str2 = String(control_az.input, 1); str3 = String(" EL"); str4 = String(control_el.input, 1); str5 = String("\n"); Serial.print(str1 + str2 + str3 + str4 + str5); control_az.setpoint = control_az.input; control_el.setpoint = control_el.input; } else if (buffer[0] == 'R' && buffer[1] == 'E' && buffer[2] == 'S' && buffer[3] == 'E' && buffer[4] == 'T') { // Reset the rotator, go to home position str1 = String("AZ"); str2 = String(control_az.input, 1); str3 = String(" EL"); str4 = String(control_el.input, 1); str5 = String("\n"); Serial.print(str1 + str2 + str3 + str4 + str5); rotator.homing_flag = false; } else if (buffer[0] == 'P' && buffer[1] == 'A' && buffer[2] == 'R' && buffer[3] == 'K' ) { // Park the rotator rotator.control_mode = position; str1 = String("AZ"); str2 = String(control_az.input, 1); str3 = String(" EL"); str4 = String(control_el.input, 1); str5 = String("\n"); Serial.print(str1 + str2 + str3 + str4 + str5); control_az.setpoint = rotator.park_az; control_el.setpoint = rotator.park_el; } else if (buffer[0] == 'V' && buffer[1] == 'E') { // Get the version if rotator controller str1 = String("VE"); str2 = String("SatNOGS-v2.2"); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'I' && buffer[1] == 'P' && buffer[2] == '0') { // Get the inside temperature str1 = String("IP0,"); str2 = String(rotator.inside_temperature, DEC); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'I' && buffer[1] == 'P' && buffer[2] == '1') { // Get the status of end-stop, azimuth str1 = String("IP1,"); str2 = String(rotator.switch_az, DEC); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'I' && buffer[1] == 'P' && buffer[2] == '2') { // Get the status of end-stop, elevation str1 = String("IP2,"); str2 = String(rotator.switch_el, DEC); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'I' && buffer[1] == 'P' && buffer[2] == '3') { // Get the current position of azimuth in deg str1 = String("IP3,"); str2 = String(control_az.input, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'I' && buffer[1] == 'P' && buffer[2] == '4') { // Get the current position of elevation in deg str1 = String("IP4,"); str2 = String(control_el.input, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'I' && buffer[1] == 'P' && buffer[2] == '5') { // Get the load of azimuth, in range of 0-1023 str1 = String("IP5,"); str2 = String(control_az.load, DEC); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'I' && buffer[1] == 'P' && buffer[2] == '6') { // Get the load of elevation, in range of 0-1023 str1 = String("IP6,"); str2 = String(control_el.load, DEC); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'I' && buffer[1] == 'P' && buffer[2] == '7') { // Get the speed of azimuth in deg/s str1 = String("IP7,"); str2 = String(control_az.speed, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'I' && buffer[1] == 'P' && buffer[2] == '8') { // Get the speed of elevation in deg/s str1 = String("IP8,"); str2 = String(control_el.speed, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'G' && buffer[1] == 'S') { // Get the status of rotator str1 = String("GS"); str2 = String(rotator.rotator_status, DEC); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[0] == 'G' && buffer[1] == 'E') { // Get the error of rotator str1 = String("GE"); str2 = String(rotator.rotator_error, DEC); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if(buffer[0] == 'C' && buffer[1] == 'R') { // Get Configuration of rotator if (buffer[3] == '1') { // Get Kp Azimuth gain str1 = String("1,"); str2 = String(control_az.p, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[3] == '2') { // Get Ki Azimuth gain str1 = String("2,"); str2 = String(control_az.i, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[3] == '3') { // Get Kd Azimuth gain str1 = String("3,"); str2 = String(control_az.d, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[3] == '4') { // Get Kp Elevation gain str1 = String("4,"); str2 = String(control_el.p, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[3] == '5') { // Get Ki Elevation gain str1 = String("5,"); str2 = String(control_el.i, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[3] == '6') { // Get Kd Elevation gain str1 = String("6,"); str2 = String(control_el.d, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[3] == '7') { // Get Azimuth park position str1 = String("7,"); str2 = String(rotator.park_az, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[3] == '8') { // Get Elevation park position str1 = String("8,"); str2 = String(rotator.park_el, 2); str3 = String("\n"); Serial.print(str1 + str2 + str3); } else if (buffer[3] == '9') { // Get control mode str1 = String("9,"); str2 = String(rotator.control_mode); str3 = String("\n"); Serial.print(str1 + str2 + str3); } } else if (buffer[0] == 'C' && buffer[1] == 'W') { // Set Config if (buffer[2] == '1') { // Set Kp Azimuth gain rawData = strtok_r(Data, ",", &Data); strncpy(data, rawData + 4, 10); if (isNumber(data)) { control_az.p = atof(data); } } else if (buffer[2] == '2') { // Set Ki Azimuth gain rawData = strtok_r(Data, ",", &Data); strncpy(data, rawData + 4, 10); if (isNumber(data)) { control_az.i = atof(data); } } else if (buffer[2] == '3') { // Set Kd Azimuth gain rawData = strtok_r(Data, ",", &Data); strncpy(data, rawData + 4, 10); if (isNumber(data)) { control_az.d = atof(data); } } else if (buffer[2] == '4') { // Set Kp Elevation gain rawData = strtok_r(Data, ",", &Data); strncpy(data, rawData + 4, 10); if (isNumber(data)) { control_el.p = atof(data); } } else if (buffer[2] == '5') { // Set Ki Elevation gain rawData = strtok_r(Data, ",", &Data); strncpy(data, rawData + 4, 10); if (isNumber(data)) { control_el.i = atof(data); } } else if (buffer[2] == '6') { // Set Kd Elevation gain rawData = strtok_r(Data, ",", &Data); strncpy(data, rawData + 4, 10); if (isNumber(data)) { control_el.d = atof(data); } } else if (buffer[2] == '7') { // Set the Azimuth park position rawData = strtok_r(Data, ",", &Data); strncpy(data, rawData + 4, 10); if (isNumber(data)) { rotator.park_az = atof(data); } } else if (buffer[2] == '8') { // Set the Elevation park position rawData = strtok_r(Data, ",", &Data); strncpy(data, rawData + 4, 10); if (isNumber(data)) { rotator.park_el = atof(data); } } } else if (buffer[0] == 'R' && buffer[1] == 'S' && buffer[2] == 'T') { // Custom command to test the watchdog timer routine while(1) ; } else if (buffer[0] == 'R' && buffer[1] == 'B') { // Custom command to reboot the uC wdt_enable(WDTO_2S); while(1); } // Reset the buffer an clean the serial buffer BufferCnt = 0; Serial.flush(); } else { // Fill the buffer with incoming data buffer[BufferCnt] = incomingByte; BufferCnt++; } } }
private: bool isNumber(char *input) { for (uint16_t i = 0; input[i] != '\0'; i++) { if (isalpha(input[i])) return false; } return true; } };
#endif /* LIBRARIES_EASYCOMM_H_ */
Other things I had to do to make my modified rotator work properly:
reverse the direction of the elevation axis. This was accomplished by swapping two of the wires going to the servo motor (swap the wires going to one of the coils)
At first, it was only moving half as far as each command (if i asked for 180 rotation, it would do 90, if i asked for 80 elevation, it would do 40). Changing the Gear Ratio to 108 from the default 54 fixed this… I’m not sure if this was the proper way to do it, but it seems to work well. I have a feeling my microstepping jumpers might not be set the same as in the sketch (I have all my jumpers in to enable the highest microstepping). You could change the microsteps in the sketch, but there seems to be a lot of other variables which rely on it and might need to be modified to make that change? It seemed easier to just double the gear ratio, and it behaves as expected now? I might tweak that.
- define RATIO 108 ///< Gear ratio of rotator gear box default 54
Azimuth Stepper Driver/motor connected to Y port on CNC Board
Elevation Stepper Driver/motor connected to X port on CNC Board
The End stop switch for elevation is connected to the X end stop on the CNC board (+ or -)
The End stop switch for azimuth is connected to the Z end stop on the CNC board (+ or -)
I also had to change the default home state from HIGH to LOW
- define DEFAULT_HOME_STATE LOW ///< Change to LOW according to Home sensor
I had to comment out all of the watchdog lines as well. I think it’s checking for communication between the Pi and Arduino.
just do a search for ‘wdt’ and add // before all the wdt lines and comment them out.
How I start the Rotator software on my PC:
Install Hamlib: https://sourceforge.net/projects/hamlib/
Figure out which COM port your Arduino is (Mine is COM7)
create a .bat file in the same folder as rotctld (I found it in C:\Program Files (x86)\hamlib-w64-3.2\bin ) with the following (modify for your com port)
> rotctld -m 202 -r COM7 -s 9600 -T 127.0.0.1 -t 4533 -C timeout=500 -C retry=0 -vvvvvvvv > pause
Download Gpredict https://sourceforge.net/projects/gpredict/
Edit...Preferences...Interfaces...Rotators...Add New Name host port Arduino localhost 4533
Start your .bat, in the top right corner of Gpredict, click down arrow, then 'Antenna Control'
...Clicking 'Engage' should get the Rotator to start working.
Once you have configured some satellites you can them select them and click 'Track'