#include <FlexCAN_T4.h>
#include <iostream>
#include <vector>
#include <string.h>
#include <Servo.h>
using namespace std;
using std::vector;
FlexCAN_T4<CAN2, RX_SIZE_256, TX_SIZE_64> kneeT; // Create a constructor with CAN functionality called kneeT.
vector<int> messageData = {}; // This vector will record incoming messages' data code.
// below are the hip, knee, and ankle average gait cycles for both legs across multiple patients
vector<double> hipData = { 36.45843373, 36.34337349, 36.21204819, 35.81927711, 34.88192771, 33.43493976, 31.65421687, 29.63674699, 27.49638554, 25.32108434,
23.15722892, 20.98493976, 18.78795181, 16.57650602, 14.35421687, 12.18313253, 10.08012048, 8.055421687, 6.112048193, 4.222891566, 2.389759036, 0.6295180723,
-1.015060241, -2.506626506, -3.78373494, -4.742168675, -5.255421687, -5.195783133, -4.463253012, -2.888554217, -0.3813253012, 2.972891566, 6.884337349, 11,
15.06686747, 18.93192771, 22.48253012, 25.68012048, 28.47168675, 30.87590361, 32.91566265, 34.6, 35.91686747, 36.85240964, 37.3873494, 37.52168675, 37.28253012,
36.84096386, 36.40361446, 36.11506024, 35.96204819 };
vector<double> kneeData = { 5.518072289, 7.887951807, 11.02771084, 14.40662651, 17.21204819, 18.94578313, 19.66445783, 19.55722892, 18.9186747, 17.99216867, 16.90421687,
15.70963855, 14.46325301, 13.20783133, 11.9873494, 10.82710843, 9.759036145, 8.775903614, 7.91746988, 7.225301205, 6.796987952, 6.724096386, 7.123493976, 8.042168675,
9.525903614, 11.63373494, 14.44638554, 18.0746988, 22.60301205, 28.00542169, 34.11626506, 40.60301205, 46.95180723, 52.51024096, 56.75963855, 59.41927711, 60.49216867,
60.04518072, 58.17951807, 55.04216867, 50.76445783, 45.53313253, 39.51686747, 32.90722892, 25.95421687, 19.00421687, 12.61204819, 7.522891566, 4.478915663, 3.826506024,
5.181325301 };
vector<double> ankleData = { -2.145180723, -4.090963855, -5.821084337, -5.834939759, -4.324698795, -2.265060241, -0.2759036145, 1.428915663, 2.871686747, 4.134939759, 5.219277108,
6.124096386, 6.860843373, 7.481325301, 8.036144578, 8.569277108, 9.094578313, 9.593975904, 10.05903614, 10.48192771, 10.8626506, 11.1939759, 11.43373494, 11.45963855,
11.08614458, 10.08614458, 8.101807229, 4.703614458, -0.4301204819, -7.043975904, -13.85180723, -18.85060241, -20.57108434, -19.22710843, -16.18313253, -12.66506024, -9.265662651,
-6.192168675, -3.589759036, -1.497590361, 0.05542168675, 1.087951807, 1.580722892, 1.58313253, 1.137951807, 0.4355421687, -0.3343373494, -0.9879518072, -1.426506024, -1.822289157,
-2.802409639 };
// We need to convert the data from doubles to integers because our servo motors cannot read the data precisely
// Therefore, integer type vectors with empty elements are made. Vectors can automatically resize.
vector<int> hip = {};
vector<int> knee = {};
vector<int> ankle = {};
// Set the offsets for your starting motor angle, since the motors may not all start at the same position.
int hipOffset = 90;
int kneeOffset = 90;
int ankleOffset = 90;
Servo KneeMotor; // We are creating a constructor called "Knee"
int controlPin = 2; // The data pin from the Teensy to Servo Motor is 2.
// Gait Cycle Stuff goes here:
int cycle = 0; // Start the cycle count at zero.
int gaitType = 1; // Placeholder rn but 1 = normal and all other numbers are abnormal gaits.
int gaitDuration = 1000; // Apparently the average gait cycle for men is between 0.97 to 1.08s. Here, we'll just the since number of 1000 to represent 1 second.
int gaitInterval = gaitDuration / kneeData.size(); // This provides the time between each data point of a gait cycle.
// Since there is a dumb mismatch, we need to setup a ratio to make sure the servo motors actually go to the correct angle.
double motorRatio = 0.6; // Right now, 180 is actually 300 for the servo motor, which means 180/360 = 0.6.
int whiteLED = 33; // Pin for white LED.
void setup(void) {
Serial.begin(115200); // You want a high baud rate to make sure you pick up all the information you need.
// Teensy 4.1 is fast enough that there won't be stability issues.
delay(400); // A moment for the serial to set up before CAN protocols.
kneeT.begin();
kneeT.setBaudRate(500000);
kneeT.setMaxMB(16);
kneeT.enableFIFO();
kneeT.enableFIFOInterrupt();
kneeT.onReceive(canSniff);
kneeT.mailboxStatus();
kneeT.enableMBInterrupts();
pinMode(whiteLED, OUTPUT); // Sets the white LED as an output.
KneeMotor.attach(controlPin, 500, 2500); // Allows the MCU to equate the "Knee" to the physical Knee Servo Motor. Also, the 500 is 0 degrees and 2500 is 300 degrees.
for(int i = 0; i < hipData.size(); i++) {
// here the double vectors from the original data are converted to integers
// every loop changes one element and pushes it back to the new integer vector
hip.push_back(int(hipData[i]));
knee.push_back(int(kneeData[i]));
ankle.push_back(int(ankleData[i]));
}
// We are using the knee motor here as our example:
KneeMotor.write(motorRatio * (hipData[0] + kneeOffset));
// uncomment the below section if you need to confirm if the data is indeed the same size and to show the data
/*
for(int i = 0; i < hip.size(); i++){
Serial.print(hip[i]);
Serial.print(" ,");
}
Serial.println();
Serial.println(hip.size());
for(int i = 0; i < knee.size(); i++){
Serial.print(knee[i]);
Serial.print(" ,");
}
Serial.println();
Serial.println(knee.size());
for(int i = 0; i < ankle.size(); i++){
Serial.print(ankle[i]);
Serial.print(" ,");
}
Serial.println();
Serial.println(ankle.size());
delay(2000); // Time for user to check the readings first before the rest of the program runs
*/
delay(1000); // Give the motor 1 second to get into position before we run it.
}
void canSniff(const CAN_message_t &msg) {
Serial.print("MB "); Serial.print(msg.mb);
Serial.print(" OVERRUN: "); Serial.print(msg.flags.overrun);
Serial.print(" LEN: "); Serial.print(msg.len);
Serial.print(" EXT: "); Serial.print(msg.flags.extended);
Serial.print(" RTR: "); Serial.print(msg.flags.remote);
Serial.print(" TS: "); Serial.print(msg.timestamp);
Serial.print(" ID: "); Serial.print(msg.id, HEX);
Serial.print(" Buffer: ");
for ( uint8_t i = 0; i < msg.len; i++ ) {
if ( msg.id == 0x101 ) {
Serial.print(msg.buf[i], HEX); Serial.print(" ");
messageData.push_back(msg.buf[i]);
Serial.print(messageData.back()); Serial.print(" ");
}
} Serial.println();
static uint32_t _time = millis();
Serial.print("Time between frames: ");
Serial.println(millis() - _time);
_time = millis();
}
void loop() {
for(int i = 0; i < knee.size(); i++) {
if (messageData.back() == 0) {
i = i - 1;
digitalWrite(whiteLED,LOW);
} else {
digitalWrite(whiteLED,HIGH);
}
KneeMotor.write(motorRatio * (hip[i] + kneeOffset));
//Serial.print(hip[i]); // Print the angle the interval and motor output shaft is at.
//Serial.print(", ");
delay(gaitInterval*4); // The motor has trouble catching up to speed, since it takes one second to reach 60 degrees and the knee gait does it in 0.5 seconds.
}
Serial.println();
Serial.print("Next Cycle is ");
Serial.print(cycle); // Will print out which cycle this is.
Serial.println();
// This is optional but it's demonstrate that the cycle has ended and is returning the cycle back to its starting position.
/*
delay(2000);
KneeMotor.write(motorRatio * (hip[0] + kneeOffset));
delay(2000); // Once the motor returns to its original position, the motor can start the gait cycle again.
*/
}