Skip to content

Instantly share code, notes, and snippets.

@careyi3
Last active November 2, 2022 15:28
Show Gist options
  • Save careyi3/a8263c71228d08e47e6d3a42d361b15d to your computer and use it in GitHub Desktop.
Save careyi3/a8263c71228d08e47e6d3a42d361b15d to your computer and use it in GitHub Desktop.
**THIS IS THE OLD CODE, NEW CODE HERE: https://github.com/careyi3/rover ** Autonomous Rover code: https://youtu.be/fp2pbrHLsrE

Rover

**THIS IS THE OLD CODE, NEW CODE HERE: https://github.com/careyi3/rover **

To run as a service copy rover.service to the location /lib/systemd/system/. From here then run the following two commands.

sudo systemctl enable rover
sudo systemctl start rover

Now, once the rover boots, the start script will be executed and the rovers firmware will be booted and run in the background.

#include <HCSR04.h>
#include <MovingAverage.h>
const int FILTER_LENGTH = 10;
char commands[5] = "FBLRS";
char message[4];
char command;
int value;
HCSR04 hc(8, 12);
MovingAverage filter(FILTER_LENGTH);
void noOp() {}
void forwardCallback(char command, int value)
{
driveLeft(value, true);
driveRight(value, true);
}
void backwardsCallback(char command, int value)
{
driveLeft(value, false);
driveRight(value, false);
}
void leftCallback(char command, int value)
{
driveLeft(value, false);
driveRight(value, true);
}
void rightCallback(char command, int value)
{
driveLeft(value, true);
driveRight(value, false);
}
void stopCallback(char command, int value)
{
analogWrite(9, 0);
analogWrite(10, 0);
analogWrite(11, 0);
analogWrite(13, 0);
}
void driveLeft(int speed, bool direction)
{
if (direction)
{
analogWrite(10, speed);
analogWrite(9, 0);
}
else
{
analogWrite(10, 0);
analogWrite(9, speed);
}
}
void driveRight(int speed, bool direction)
{
if (direction)
{
analogWrite(11, speed);
analogWrite(13, 0);
}
else
{
analogWrite(11, 0);
analogWrite(13, speed);
}
}
void (*callbacks[5])(char command, int value) = {
forwardCallback, // F
backwardsCallback, // B
leftCallback, // L
rightCallback, // R
stopCallback // S
};
void setup()
{
for(int i = 0; i < FILTER_LENGTH; i++)
{
filter.addSample(hc.dist());
}
Serial.begin(921600);
}
void loop()
{
if (Serial.available() > 0)
{
Serial.readBytesUntil("\n", message, 4);
while (Serial.available() > 0 && !isValidCommand(Serial.peek()))
{
Serial.read();
}
handleMessage();
}
writeSensorData();
//delay(50);
}
void writeSensorData()
{
Serial.print("D");
Serial.println(filter.addSample(hc.dist()));
Serial.flush();
}
void handleMessage()
{
command = message[0];
value = atoi(&message[1]);
bool valid = true;
if (!isValidCommand(command))
{
valid = false;
Serial.println("E:C");
Serial.flush();
}
if (!isValidValue(value))
{
valid = false;
Serial.println("E:V");
Serial.flush();
}
if (valid)
{
int idx = commandIndex(command);
Serial.println("A");
Serial.flush();
(*callbacks[idx])(command, value);
}
}
bool isValidCommand(char command)
{
return commandIndex(command) != -1;
}
bool isValidValue(int value)
{
return value >= 0 && value <= 255;
}
int commandIndex(char command)
{
int idx = -1;
for (int i = 0; i < 5; i++)
{
if (command == commands[i])
{
idx = i;
}
}
return idx;
}
[Unit]
Description=Run rover firmware on boot
[Service]
Type=simple
User=pi
WorkingDirectory=/home/pi/workspace/rover/pi
ExecStart=/home/pi/workspace/rover/pi/start
Restart=always
[Install]
WantedBy=multi-user.target
require 'pry'
require 'serialport'
require 'readline'
sem = Mutex.new
ser = SerialPort.new("/dev/ttyACM0", 921600, 8, 1, SerialPort::NONE)
#ser = SerialPort.new("/dev/tty.usbmodem101", 921600, 8, 1, SerialPort::NONE)
data = nil
reader = Thread.new {
line = nil
while line == nil
line = ser.readline
sem.synchronize {
puts "<- " + line
if line[0] == 'D'
data = line
end
}
line = nil
end
}
def handleData(sem, data)
dist = 0
sem.synchronize {
if data != nil
dist = data[1..-1].to_f
end
}
dist
end
def runCommands(ser, command)
puts "-> " + command
ser.write("#{command}\n")
end
forward = false
turning = false
dist_old = 0
dt = 0
dist = 0
while true
t1 = Time.now
dist_old = dist
dist = handleData(sem, data)
if dist <= 45
unless turning
turn_command = [true, false].sample ? 'L100' : 'R100'
runCommands(ser, turn_command)
forward = false
turning = true
sleep(0.5)
end
else
#unless forward
dist_offset = dist >= 40 ? dist - 40 : 0
throttle = 60 + dist_offset
runCommands(ser, "F#{throttle}")
forward = true
turning = false
#end
end
sleep(0.01)
t2 = Time.now
dt = t2 - t1
end
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment