Implementing serial communication (works) and light fades (not yet).
This commit is contained in:
parent
3e740fba89
commit
300050a80f
5 changed files with 144 additions and 206 deletions
|
@ -5,7 +5,7 @@ enum Command {
|
|||
RECEIVED = 3,
|
||||
|
||||
MOTOR_H = 'H',
|
||||
MOTOR_V = 'M',
|
||||
MOTOR_V = 'V',
|
||||
|
||||
BACKLIGHT = 'B',
|
||||
FRONTLIGHT = 'F',
|
||||
|
|
|
@ -1,66 +0,0 @@
|
|||
#include <Arduino.h>
|
||||
#include "Commands.h"
|
||||
|
||||
/**
|
||||
* @brief Read one byte from Serial and cast it to a Command
|
||||
*
|
||||
* @return Command
|
||||
*/
|
||||
Command read_command(HardwareSerial &serial);
|
||||
|
||||
/**
|
||||
* @brief Wait for the number of bytes to be available on Serial
|
||||
*
|
||||
* @param num_bytes
|
||||
* @param timeout_ms
|
||||
*/
|
||||
void wait_for_bytes(HardwareSerial &serial, int num_bytes, unsigned long timeout_ms);
|
||||
|
||||
/**
|
||||
* @brief Read one byte
|
||||
*
|
||||
* @return int8_t
|
||||
*/
|
||||
int8_t read_i8(HardwareSerial &serial);
|
||||
|
||||
/**
|
||||
* @brief Read two bytes and convert to signed 16bit integer
|
||||
*
|
||||
* @return int16_t
|
||||
*/
|
||||
int16_t read_i16(HardwareSerial &serial);
|
||||
|
||||
/**
|
||||
* @brief Read four bytes and convert to signed 32bit integer
|
||||
*
|
||||
* @return int32_t
|
||||
*/
|
||||
int32_t read_i32(HardwareSerial &serial);
|
||||
|
||||
/**
|
||||
* @brief Write one byte corresponding to a Command
|
||||
*
|
||||
* @param cmd
|
||||
*/
|
||||
void write_command(HardwareSerial &serial, Command cmd);
|
||||
|
||||
/**
|
||||
* @brief Write a signed 8bit integer
|
||||
*
|
||||
* @param num
|
||||
*/
|
||||
void write_i8(HardwareSerial &serial, int8_t num);
|
||||
|
||||
/**
|
||||
* @brief Write a signed 16bit integer
|
||||
*
|
||||
* @param num
|
||||
*/
|
||||
void write_i16(HardwareSerial &serial, int16_t num);
|
||||
|
||||
/**
|
||||
* @brief Write a signed 32bit integer
|
||||
*
|
||||
* @param num
|
||||
*/
|
||||
void write_i32(HardwareSerial &serial, int32_t num);
|
|
@ -13,5 +13,7 @@ platform = teensy
|
|||
board = teensy41
|
||||
framework = arduino
|
||||
upload_protocol = teensy-cli
|
||||
lib_deps = adafruit/Adafruit NeoPixel@^1.10.1
|
||||
lib_deps =
|
||||
adafruit/Adafruit NeoPixel@^1.10.1
|
||||
gitlab-simple-serial-protocol/SimpleSerialProtocol@^2.4.0
|
||||
src_filter = +<*> -<.git/> -<.svn/> -<example/> -<examples/> -<test/> -<tests/> -<scratch*>
|
||||
|
|
|
@ -1,111 +0,0 @@
|
|||
#include "Serial_Comm.h"
|
||||
|
||||
/**
|
||||
* @brief Read one byte from Serial and cast it to a Command
|
||||
*
|
||||
* @return Command
|
||||
*/
|
||||
Command read_command(HardwareSerial &serial) {
|
||||
return (Command) serial.read();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Wait for the number of bytes to be available on Serial
|
||||
*
|
||||
* @param num_bytes
|
||||
* @param timeout_ms
|
||||
*/
|
||||
void wait_for_bytes(HardwareSerial &serial, int num_bytes, unsigned long timeout_ms) {
|
||||
uint32_t startTime = millis();
|
||||
// Wait for incoming bytes or exit if timeout
|
||||
while ((serial.available() < num_bytes) && (millis() - startTime < timeout_ms)){
|
||||
// NOOP.
|
||||
}
|
||||
}
|
||||
|
||||
void read_signed_bytes(HardwareSerial &serial, int8_t* buffer, size_t n)
|
||||
{
|
||||
size_t i = 0;
|
||||
int c;
|
||||
while (i < n)
|
||||
{
|
||||
c = serial.read();
|
||||
if (c < 0) break;
|
||||
*buffer++ = (int8_t) c; // buffer[i] = (int8_t)c;
|
||||
i++;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read one byte
|
||||
*
|
||||
* @return int8_t
|
||||
*/
|
||||
int8_t read_i8(HardwareSerial &serial) {
|
||||
wait_for_bytes(serial, 1, 500);
|
||||
return (int8_t) serial.read();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read two bytes and convert to signed 16bit integer
|
||||
*
|
||||
* @return int16_t
|
||||
*/
|
||||
int16_t read_i16(HardwareSerial &serial) {
|
||||
int8_t buffer[2];
|
||||
wait_for_bytes(serial, 2, 500);
|
||||
read_signed_bytes(serial, buffer, 2);
|
||||
return (((int16_t) buffer[0]) & 0xff) | (((int16_t) buffer[1]) << 8 & 0xff00);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read four bytes and convert to signed 32bit integer
|
||||
*
|
||||
* @return int32_t
|
||||
*/
|
||||
int32_t read_i32(HardwareSerial &serial) {
|
||||
int8_t buffer[4];
|
||||
wait_for_bytes(serial, 4, 200); // Wait for 4 bytes with a timeout of 200 ms
|
||||
read_signed_bytes(serial, buffer, 4);
|
||||
return (((int32_t) buffer[0]) & 0xff) | (((int32_t) buffer[1]) << 8 & 0xff00) | (((int32_t) buffer[2]) << 16 & 0xff0000) | (((int32_t) buffer[3]) << 24 & 0xff000000);
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Write one byte corresponding to a Command
|
||||
*
|
||||
* @param cmd
|
||||
*/
|
||||
void write_command(HardwareSerial &serial, Command cmd) {
|
||||
uint8_t* c = (uint8_t*) &cmd;
|
||||
serial.write(c, sizeof(uint8_t));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Write a signed 8bit integer
|
||||
*
|
||||
* @param num
|
||||
*/
|
||||
void write_i8(HardwareSerial &serial, int8_t num) {
|
||||
serial.write(num);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Write a signed 16bit integer
|
||||
*
|
||||
* @param num
|
||||
*/
|
||||
void write_i16(HardwareSerial &serial, int16_t num) {
|
||||
int8_t buffer[2] = {(int8_t) (num & 0xff), (int8_t) (num >> 8)};
|
||||
serial.write((uint8_t*)&buffer, 2*sizeof(int8_t));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Write a signed 32bit integer
|
||||
*
|
||||
* @param num
|
||||
*/
|
||||
void write_i32(HardwareSerial &serial, int32_t num) {
|
||||
int8_t buffer[4] = {(int8_t) (num & 0xff), (int8_t) (num >> 8 & 0xff), (int8_t) (num >> 16 & 0xff), (int8_t) (num >> 24 & 0xff)};
|
||||
serial.write((uint8_t*)&buffer, 4*sizeof(int8_t));
|
||||
}
|
165
src/main.cpp
165
src/main.cpp
|
@ -1,7 +1,9 @@
|
|||
#include <Arduino.h>
|
||||
#include <Adafruit_NeoPixel.h>
|
||||
#include <SimpleSerialProtocol.h>
|
||||
#include "Commands.h"
|
||||
#include "Motor.h"
|
||||
#include "Serial_Comm.h"
|
||||
// #include "Serial_Comm.h"
|
||||
|
||||
// Vertical motor top
|
||||
#define VERT_UP_PWM 3
|
||||
|
@ -42,6 +44,8 @@
|
|||
#define LED_BACK 14
|
||||
#define LED_COUNT_BACK 72
|
||||
|
||||
void on_serial_error(uint8_t errorNum);
|
||||
|
||||
volatile int32_t hor_pos;
|
||||
volatile int32_t vert_pos;
|
||||
|
||||
|
@ -64,6 +68,15 @@ int led_n;
|
|||
u_int8_t brightness;
|
||||
u_int8_t color;
|
||||
|
||||
bool serial_connected;
|
||||
|
||||
// inintialize hardware constants
|
||||
const long BAUDRATE = 115200; // speed of serial connection
|
||||
const long CHARACTER_TIMEOUT = 500; // wait max 500 ms between single chars to be received
|
||||
|
||||
// Create instance. Pass Serial instance. Define command-id-range within Simple Serial Protocol is listening (here: a - z)
|
||||
SimpleSerialProtocol ssp(Serial1, BAUDRATE, CHARACTER_TIMEOUT, on_serial_error, 0, 'Z'); // ASCII: 'a' - 'z' (26 byes of RAM is reserved)
|
||||
|
||||
int32_t count(int pinA, int pinB) {
|
||||
if (digitalRead(pinA)) return digitalRead(pinB) ? -1 : 1;
|
||||
else return digitalRead(pinB) ? 1 : -1;
|
||||
|
@ -77,10 +90,11 @@ void vert_count() {
|
|||
vert_pos += count(VERT_CNT_INNER, VERT_CNT_OUTER);
|
||||
}
|
||||
|
||||
/*
|
||||
Generic motor control (full speed). Call every 10us for good results.
|
||||
/**
|
||||
* @brief Generic motor control (full speed). Call every 10us for good results.
|
||||
*
|
||||
*/
|
||||
void mot_control(Motor mot1, Motor mot2, int32_t pos, int32_t aim) {
|
||||
void mot_control(Motor &mot1, Motor &mot2, int32_t pos, int32_t aim) {
|
||||
if (pos < aim) {
|
||||
mot1.run(255, false);
|
||||
mot2.run(127, false);
|
||||
|
@ -94,6 +108,113 @@ void mot_control(Motor mot1, Motor mot2, int32_t pos, int32_t aim) {
|
|||
}
|
||||
}
|
||||
|
||||
uint8_t color_value(uint8_t col_from, uint8_t col_to, uint32_t cur_time, uint32_t duration) {
|
||||
float_t perc = (float) cur_time / (float) duration;
|
||||
float_t col = (float) (col_to - col_from) * perc;
|
||||
return (uint8_t) (col + 0.5);
|
||||
}
|
||||
|
||||
void led_fade(Adafruit_NeoPixel &led, int8_t to_R, int8_t to_G, int8_t to_B, int8_t to_W, uint32_t time_ms) {
|
||||
uint32_t startcol = led.getPixelColor(0);
|
||||
Serial.printf("col = %i \n", startcol);
|
||||
uint8_t from_W = (startcol & 0xff000000) >> 24;
|
||||
uint8_t from_R = (startcol & 0x00ff0000) >> 16;
|
||||
uint8_t from_G = (startcol & 0x0000ff00) >> 8;
|
||||
uint8_t from_B = (startcol & 0x000000ff);
|
||||
|
||||
Serial.printf("r = %i, g = %i, b = %i, w = %i \n", from_R, from_G, from_B, from_W);
|
||||
|
||||
uint32_t start_time = millis();
|
||||
uint32_t end_time = start_time + time_ms;
|
||||
|
||||
while (millis() < end_time) {
|
||||
u_int32_t cur_time = millis() - start_time;
|
||||
uint32_t color = led.Color(color_value(from_R, to_R, cur_time, time_ms),
|
||||
color_value(from_G, to_G, cur_time, time_ms),
|
||||
color_value(from_B, to_B, cur_time, time_ms),
|
||||
color_value(from_W, to_W, cur_time, time_ms));
|
||||
led.fill(color);
|
||||
led.show();
|
||||
// Serial.printf("t = %i, c = %i \n", cur_time, color);
|
||||
}
|
||||
}
|
||||
|
||||
void on_serial_error(uint8_t errno) {
|
||||
Serial.printf("SSP error %i \n", errno);
|
||||
ssp.writeCommand(ERROR);
|
||||
ssp.writeInt8(errno);
|
||||
ssp.writeEot();
|
||||
}
|
||||
|
||||
void serial_received() {
|
||||
ssp.writeCommand(RECEIVED);
|
||||
ssp.writeEot();
|
||||
}
|
||||
|
||||
void serial_hello() {
|
||||
ssp.readEot();
|
||||
|
||||
if (!serial_connected) {
|
||||
ssp.writeCommand(HELLO);
|
||||
serial_connected = true;
|
||||
Serial.println("Connection established.");
|
||||
}
|
||||
else {
|
||||
ssp.writeCommand(ALREADY_CONNECTED);
|
||||
Serial.println("Handshake complete.");
|
||||
}
|
||||
|
||||
ssp.writeEot();
|
||||
}
|
||||
|
||||
void serial_backlight() {
|
||||
uint8_t r = ssp.readUnsignedInt8();
|
||||
uint8_t g = ssp.readUnsignedInt8();
|
||||
uint8_t b = ssp.readUnsignedInt8();
|
||||
uint8_t w = ssp.readUnsignedInt8();
|
||||
uint32_t t = ssp.readUnsignedInt32();
|
||||
ssp.readEot();
|
||||
Serial.printf("Received BACKLIGHT (%i, %i, %i, %i, %i) \n", r, g, b, w, t);
|
||||
led_fade(led_back, r, g, b, w, t);
|
||||
serial_received();
|
||||
}
|
||||
|
||||
void serial_frontlight() {
|
||||
ssp.readEot();
|
||||
Serial.println("Received FRONTLIGHT");
|
||||
serial_received();
|
||||
}
|
||||
|
||||
void serial_motor_v() {
|
||||
ssp.readEot();
|
||||
Serial.println("Received MOTOR_V");
|
||||
serial_received();
|
||||
}
|
||||
|
||||
void serial_motor_h() {
|
||||
ssp.readEot();
|
||||
Serial.println("Received MOTOR_H");
|
||||
serial_received();
|
||||
}
|
||||
|
||||
void serial_record() {
|
||||
ssp.readEot();
|
||||
Serial.println("Received RECORD");
|
||||
serial_received();
|
||||
}
|
||||
|
||||
void serial_rewind() {
|
||||
ssp.readEot();
|
||||
Serial.println("Received REWIND");
|
||||
serial_received();
|
||||
}
|
||||
|
||||
void serial_userinteract() {
|
||||
ssp.readEot();
|
||||
Serial.println("Received USER_INTERACT");
|
||||
serial_received();
|
||||
}
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
Serial1.begin(115200);
|
||||
|
@ -142,29 +263,21 @@ void setup() {
|
|||
|
||||
led_front.begin();
|
||||
led_front.show();
|
||||
|
||||
serial_connected = false;
|
||||
|
||||
ssp.init();
|
||||
ssp.registerCommand(HELLO, serial_hello);
|
||||
ssp.registerCommand(ALREADY_CONNECTED, serial_hello);
|
||||
ssp.registerCommand(BACKLIGHT, serial_backlight);
|
||||
ssp.registerCommand(FRONTLIGHT, serial_frontlight);
|
||||
ssp.registerCommand(MOTOR_H, serial_motor_h);
|
||||
ssp.registerCommand(MOTOR_V, serial_motor_v);
|
||||
ssp.registerCommand(RECORD, serial_record);
|
||||
ssp.registerCommand(REWIND, serial_rewind);
|
||||
ssp.registerCommand(USER_INTERACT, serial_userinteract);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
if (Serial1.available() > 0) {
|
||||
Serial.printf("Serial1.available = %i \n", Serial1.available());
|
||||
Command cmd = read_command(Serial1);
|
||||
switch (cmd)
|
||||
{
|
||||
case HELLO:
|
||||
{
|
||||
Serial.println("Received HELLO");
|
||||
break;
|
||||
}
|
||||
case MOTOR_H:
|
||||
{
|
||||
Serial.println("Received MOTOR_H");
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
Serial.println("Received something.");
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
ssp.loop();
|
||||
}
|
Loading…
Reference in a new issue