Laser-Pointer-Tracker-Abob
Problem Statement
I teach classes where we build amsat antennas and try to listen to satellites and the International Space Station. It is really hard to point to nothing at all, so I thought this would help (at least, during the night). It also has the handy dandy feature that it can be used to point out astronomical items if you modify the pyephem script barely.
The thing you have to 3D print
It is here: http://www.thingiverse.com/thing:1403736
Video of the thing in action is here: https://www.youtube.com/watch?v=uu8M_wjfsk4
System Overview
The system consists of:
- A servo to control elevation
- A stepper to control azimuth
- An Arduino to control the servo and stepper
- A Raspberry Pi (or laptop) to calculate the ephemris and find the pointing vector
- A serial data link between the Pi and the Arduino
Arduino Code
I used an uno to do this with a polalu stepper driver (one that takes steps and direction pulses) I also used a futaba servo. I also used the highest microstepping, which is 1/16th microstepping.
/* Laser Pointer (to degrees and elevation, to track or point out celestial objects, satellites, etc) by Nebarnix <http://www.nebarnix.com> This example code is in the public domain. */ #include <Servo.h> //#include <PID_v1.h> Servo myservo; // create servo object to control a servo //Stepper hardware setup int stepper_pin_step_state=HIGH; int stepper_pin_step = 2; int stepper_pin_dir = 3; int stepper_dir_CW = HIGH; int stepper_dir_CCW = LOW; int stepper_pin_enable = 8; int stepper_enable = LOW; int stepper_disable = HIGH; //Stepper parameters int stepper_steps_360 = 3200; //steps per 360 degrees int stepper_pos_steps_current=0; int stepper_pos_steps_setpoint=0; double stepper_pos_deg_current=180; //south double stepper_pos_deg_prev=180; double stepper_pos_deg_setpoint=0; //South double stepper_time_last_step=0; //Servo paramaters int servo_pos_time_min = 550; //600 for SG9 int servo_pos_time_max = 2350; //2300 for SG9 (2400 abs max, 2300 for 180) int servo_pos_time_current=servo_pos_time_min; int servo_pos_time_setpoint=servo_pos_time_min; double servo_pos_deg_prev=0; double servo_pos_deg_current=0; double servo_pos_deg_setpoint=0; float servo_pos_deg_rate_limit=50; float servo_pos_deg_rate; float servo_pos_deg_ramp_rate=50; long time_prev=0; long time_current=0; long time_delta=0; void setup() { time_current = micros(); pinMode(stepper_pin_step, OUTPUT); pinMode(stepper_pin_dir, OUTPUT); pinMode(stepper_pin_enable, OUTPUT); digitalWrite(stepper_pin_step, LOW); digitalWrite(stepper_pin_dir, stepper_dir_CW); digitalWrite(stepper_pin_enable, stepper_disable); myservo.attach(11); // attaches the servo on pin 9 to the servo object myservo.writeMicroseconds(servo_pos_time_min); //test_servo(); //test_stepper_motion(); Serial.begin(115200); } void test_stepper_motion() { int rot = 0; digitalWrite(stepper_pin_enable, stepper_enable); for ( rot = 0; rot <= stepper_steps_360/2; rot += 1) { digitalWrite(stepper_pin_dir, stepper_dir_CW); digitalWrite(stepper_pin_step, HIGH); digitalWrite(stepper_pin_step, LOW); delay(2); stepper_pos_steps_current = stepper_pos_steps_current++; } delay(100); for ( rot = stepper_steps_360/2; rot >= 0; rot -= 1) { digitalWrite(stepper_pin_dir, stepper_dir_CCW); digitalWrite(stepper_pin_step, HIGH); digitalWrite(stepper_pin_step, LOW); delay(2); stepper_pos_steps_current = stepper_pos_steps_current--; } delay(100); for ( rot = 0; rot <= stepper_steps_360/2; rot += 1) { digitalWrite(stepper_pin_dir, stepper_dir_CCW); digitalWrite(stepper_pin_step, HIGH); digitalWrite(stepper_pin_step, LOW); delay(2); stepper_pos_steps_current = stepper_pos_steps_current--; } delay(100); for ( rot = stepper_steps_360/2; rot >= 0; rot -= 1) { digitalWrite(stepper_pin_dir, stepper_dir_CW); digitalWrite(stepper_pin_step, HIGH); digitalWrite(stepper_pin_step, LOW); delay(2); stepper_pos_steps_current = stepper_pos_steps_current++; } digitalWrite(stepper_pin_enable, stepper_disable); } void test_servo() { int pos; for (pos = servo_pos_time_min; pos <= servo_pos_time_max; pos += 2) { // goes from 0 degrees to 180 degrees // in steps of 1 degree myservo.writeMicroseconds(pos); // tell servo to go to position in variable 'pos' delay(10); // waits 15ms for the servo to reach the position } for (pos = servo_pos_time_max; pos >= servo_pos_time_min; pos -= 2) { // goes from 180 degrees to 0 degrees myservo.writeMicroseconds(pos); // tell servo to go to position in variable 'pos' delay(5); // waits 15ms for the servo to reach the position } } void servo_motion_go(){ float servo_pos_error; float K; servo_pos_deg_prev = servo_pos_deg_current; servo_pos_error = servo_pos_deg_setpoint-servo_pos_deg_prev; servo_pos_deg_rate = constrain(servo_pos_deg_rate+servo_pos_deg_ramp_rate*time_delta*.000001,0,servo_pos_deg_rate_limit); if(abs(servo_pos_error) < 1) servo_pos_deg_current = servo_pos_deg_setpoint; else { K = (servo_pos_deg_rate*time_delta*.000001)/abs(servo_pos_error); servo_pos_deg_current = (servo_pos_deg_prev + K*servo_pos_error); } } void stepper_motion_go() { stepper_pos_steps_setpoint = map(stepper_pos_deg_setpoint,-180,180,-stepper_steps_360/2,stepper_steps_360/2); if(time_current-stepper_time_last_step > 1000 && (stepper_pos_steps_setpoint - stepper_pos_steps_current) != 0) { if(stepper_pos_steps_setpoint > stepper_pos_steps_current) { digitalWrite(stepper_pin_dir, stepper_dir_CW); stepper_pos_steps_current = stepper_pos_steps_current+1; } else if(stepper_pos_steps_setpoint < stepper_pos_steps_current) { digitalWrite(stepper_pin_dir, stepper_dir_CCW); stepper_pos_steps_current = stepper_pos_steps_current-1; } else return; digitalWrite(stepper_pin_enable, stepper_enable); digitalWrite(stepper_pin_step, HIGH); digitalWrite(stepper_pin_step, LOW); stepper_time_last_step = time_current; } else if(time_current < stepper_time_last_step) //catch timer overflows { stepper_time_last_step = time_current; } //else if(time_current-stepper_time_last_step > 10000000) //10 second timeout, only use if the motor or driver gets too hot. OR JUST TURN DOWN THE CURRENT // { // digitalWrite(stepper_pin_enable, stepper_disable); // } } void loop() { time_prev = time_current; time_current = micros(); time_delta = time_current-time_prev; //servo crappy hacky rate limited ramped control loop servo_motion_go(); myservo.write(servo_pos_deg_current); //Stepper crappy hacky rate limited ramped control loop stepper_motion_go(); if(millis() % 1000 == 0) { /* Serial.print(servo_pos_deg_setpoint); Serial.print(" "); Serial.print(servo_pos_deg_current); Serial.print(" "); Serial.println(servo_pos_deg_prev);*/ Serial.print(stepper_pos_steps_setpoint); Serial.print(" "); Serial.print(stepper_pos_steps_current); Serial.print(" "); //Serial.print(time_current-stepper_time_last_step); Serial.print(" "); Serial.println(stepper_pos_deg_setpoint); } if (Serial.available() > 0) { int serInInt1 = Serial.parseInt(); int serInInt2 = Serial.parseInt(); if (Serial.read() == '\n') { servo_pos_deg_setpoint = serInInt1/10.0; stepper_pos_deg_setpoint = serInInt2/10.0-180; servo_pos_deg_rate = 4; } } }
Python Code
#!/usr/bin/env python #Laser tracker thinger using pyephem to send serial alt-az commands to the arduino. #remember to set your ground station GPS coordinates!!! #The line looks kinda like this => solution.lon, solution.lat = '-111.717379', '33.401926' import time import datetime import ephem import optparse import sys import serial filename = "TLE.txt" try: fo = open("/home/pi/" + filename, "r") except: print "TLE file not found - error" print filename sys.exit(1) #Read the first three lines of TLE.txt line1=fo.readline() line2=fo.readline() line3=fo.readline() fo.close #port = serial.Serial("/dev/ttyAMA0", baudrate=115200, timeout=3.0) #Pi pins port = serial.Serial("/dev/ttyACM0", baudrate=115200, timeout=3.0) #Arduino USB sat = ephem.readtle(line1, line2, line3) solution = ephem.Observer() solution.lon, solution.lat = '-111.717379', '33.401926' #solution.date = '2015-10-19 13:44:51.4584'; try: while True: solution.date = datetime.datetime.utcnow() sat.compute(solution) #defaults to NOW pi = 3.14159265359 if sat.alt < 0: out_altitude = (180.0/pi)*sat.alt ser_altitude = int(0) out_azimuth = (180.0/pi)*sat.az ser_azimuth = int((180.0/pi)*sat.az*10) else: out_altitude = (180.0/pi)*sat.alt ser_altitude = int((180.0/pi)*sat.alt*10) out_azimuth = (180.0/pi)*sat.az ser_azimuth = int((180.0/pi)*sat.az*10) print("Alt:{0:.1f} Az:{1:.1f}".format(out_altitude, out_azimuth)) port.write("{0},{1}\n".format(ser_altitude, ser_azimuth)) port.flushInput() #this might be why the thing is crashing, input buffer fills up?? #print("Alt:{0} Az:{1}".format(ser_altitude, ser_azimuth)) time.sleep(1) except KeyboardInterrupt: port.write("{0},{1}\n".format(0, 1800)) time.sleep(1)
TLE
A sample TLE file would look like this, but note that the code will only load the FIRST THREE LINES but it is nice to have them all in one spot, so I just shuffle them up to the top as needed.
NOAA 19 [+] 1 33591U 09005A 16069.53289067 .00000138 00000-0 10001-3 0 9994 2 33591 99.0285 25.5538 0014613 136.4662 223.7665 14.12048620365077 Saudisat 1C 1 27607U 02058C 16069.10105181 .00000444 00000-0 83508-4 0 9996 2 27607 64.5542 106.6305 0076860 237.5124 121.8533 14.75091549710503 NOAA 15 [B] 1 25338U 98030A 16068.51495196 .00000095 00000-0 58860-4 0 9997 2 25338 98.7831 72.4648 0011644 115.9718 244.2663 14.25708308926640