Browse Source

receive code from Ronny

Keisuke Sehara 3 years ago
commit
3ed53b731b
12 changed files with 2505 additions and 0 deletions
  1. 1 0
      .gitignore
  2. 1424 0
      Airtrack/Airtrack.ino
  3. 167 0
      Airtrack/actuator.h
  4. 158 0
      Airtrack/definitions.h
  5. 20 0
      Airtrack/leds.h
  6. 58 0
      Airtrack/mpr121.h
  7. 80 0
      Airtrack/pins.h
  8. 141 0
      Airtrack/reporter.h
  9. 212 0
      Airtrack/sensor.h
  10. 220 0
      Airtrack/stats.h
  11. 15 0
      LICENSE
  12. 9 0
      README.md

+ 1 - 0
.gitignore

@@ -0,0 +1 @@
+*.DS_Store

File diff suppressed because it is too large
+ 1424 - 0
Airtrack/Airtrack.ino


+ 167 - 0
Airtrack/actuator.h

@@ -0,0 +1,167 @@
+#ifndef ACTUATOR_MODULE
+#define ACTUATOR_MODULE
+
+#include "Arduino.h"
+#include "definitions.h"
+
+struct Actuator
+{
+  public:
+    enum State {
+      STILL,
+      PUSH,
+      PULL
+    };
+
+  private:
+  
+    PIN_TYPE motor_push_pin;
+    PIN_TYPE motor_pull_pin;
+
+    int max_distance_pwm;
+
+    State current_state;
+    bool change_required;
+
+    GlobalState* global_state;
+
+  public:
+
+    CONST_PIN_TYPE ANALOUGE_PIN = 1;
+
+    Actuator (PIN_TYPE motor_push_pin, PIN_TYPE motor_pull_pin,
+              int max_distance_pwm, GlobalState* global_state)
+    {
+        this->current_state = STILL;
+        this->motor_push_pin = motor_push_pin;
+        this->motor_pull_pin = motor_pull_pin;
+        this->max_distance_pwm = max_distance_pwm;
+        this->global_state = global_state;
+    }
+
+    void setup()
+    {
+        this->global_state->actuator_at_max_push = false;
+        // Serial.println("Setting up actiator");
+        this->setState(PULL);
+        // printState();
+        while (this->current_state != STILL)
+        {
+            this->motorLoop();
+            //Serial.print("Setup loop - current state: ");
+            //Serial.println(this->current_state);
+        }
+        //Serial.println("Setup loop done");
+    }
+
+    void setMaxDistance(int max_distance_pwm)
+    {
+      this->max_distance_pwm = max_distance_pwm;
+    }
+
+    void printState()
+    {
+      Serial.print("Actuator current state: ");
+      Serial.print(this->current_state);
+      Serial.print(" - and PWM value: ");
+      Serial.println(analogRead(ANALOUGE_PIN));
+    }
+
+    void setState(State state)
+    {
+      // Serial.print("Current state: ");
+      // Serial.println(this->current_state);
+      if (state != this->current_state)
+      {
+        this->current_state = state;
+        this->change_required = true;
+      }
+    }
+
+    int getMotorDist()
+    {
+      return analogRead(ANALOUGE_PIN);
+    }
+
+    void motorLoop()
+    {
+      // Serial.print("Motor loop - ");
+      //printState();
+      if (this->current_state == STILL)
+      {
+        return;
+      }
+      
+      #define MIN_DISTANCE 20 
+      int sensor_value = this->getMotorDist();
+      // if (sensor_value >= this->max_distance_pwm - 30) // Leave a bit of buffer
+      if (sensor_value >= this->max_distance_pwm)
+      {
+        this->global_state->actuator_at_max_push = true;
+      }
+      else
+      {
+        this->global_state->actuator_at_max_push = false;
+        if (sensor_value <= MIN_DISTANCE)
+        {
+          this->global_state->actuator_at_min_pull = true;
+        }
+        else
+        {
+          this->global_state->actuator_at_min_pull = false;
+        }
+
+      }
+
+      if (this->current_state == PUSH)
+      {
+          if (sensor_value >= this->max_distance_pwm)
+          {
+              this->enableStill();
+              this->current_state = STILL;
+              this->change_required = false;
+          }
+          
+          if (this->change_required)
+          {
+              this->enablePush();
+              this->change_required = false;
+          }
+      }
+      else if (this->current_state == PULL)
+      {
+          if (sensor_value <= MIN_DISTANCE) // Doesn't have to be completely retracted
+          {
+              this->enableStill();
+              this->current_state = STILL;
+              this->change_required = false;
+          }
+
+          if (this->change_required)
+          {
+              this->enablePull();
+              this->change_required = false;
+          }
+      }
+    }
+
+    void enablePush()
+    {
+       digitalWrite(this->motor_push_pin, HIGH);
+       digitalWrite(this->motor_pull_pin, LOW);
+    }
+
+    void enablePull()
+    {
+        digitalWrite(this->motor_push_pin, LOW);
+        digitalWrite(this->motor_pull_pin, HIGH);
+    }
+
+    void enableStill()
+    {
+       digitalWrite(this->motor_push_pin, LOW);
+       digitalWrite(this->motor_pull_pin, LOW);
+    }
+};
+
+#endif

+ 158 - 0
Airtrack/definitions.h

@@ -0,0 +1,158 @@
+#ifndef DEFINITIONS_MODULE
+#define DEFINITIONS_MODULE
+
+#import <Arduino.h>
+
+// CONST_PIN_TYPE types cannot change their values after first declartion
+// typedef static const unsigned int CONST_PIN_TYPE;
+#define CONST_PIN_TYPE static const unsigned int // typedef is not working, dedbug later
+
+typedef unsigned int PIN_TYPE;
+typedef int16_t ANGLE;
+typedef unsigned int LANE_ID;
+
+struct SensorTouched
+{
+  bool change_happened;
+  bool left_sensor;
+  bool right_sensor;
+
+  SensorTouched(bool left_touched, bool right_touched)
+  {
+    this->change_happened = false;
+    this->left_sensor = left_touched;
+    this->right_sensor = right_touched;
+  }
+};
+
+struct SubjectLocation
+{
+    bool block_detected;
+    ANGLE angle;
+    uint16_t x;
+    uint16_t y;
+};
+
+struct Lane
+{
+   LANE_ID lane_id;
+   PIN_TYPE reward_sensor;
+   ANGLE region_start_angle;
+   ANGLE region_end_angle;
+
+};
+
+struct MotorDurationEntry
+{
+    bool activated;
+    PIN_TYPE motor_id;
+    long int activation_time;
+    long int timeout_period;
+};
+
+struct GlobalState
+{
+  int Servo1_pos = 0;
+  bool Servo1_dir = true;
+
+  
+   static const LANE_ID NUM_OF_LANES = 4;
+   Lane lanes[NUM_OF_LANES];
+   // Guaranteed bound value must be divisble by num of lanes
+   static const int GUARANTEED_RANDOM_BOUND = NUM_OF_LANES*1;
+   LANE_ID lane_shuffle_list[GUARANTEED_RANDOM_BOUND];
+   size_t shuffle_list_index;
+   bool was_inside_lane;
+   LANE_ID current_lane;
+   LANE_ID reward_lane_id;
+   bool reward_direction;
+   bool rotation;
+   SubjectLocation last_subject_location;
+   bool actuator_at_max_push;
+   bool actuator_at_min_pull;
+   static const long int MAX_PUSH_TIMEOUT = 1000;
+   static const long int MAX_PUSH_WAIT = 100;
+   static const long int ALLOWED_REWARD_TIMEOUT = 1000;
+   static const long int NO_REWARD_TIMEOUT = 100;
+   static const long int PEIZO_TIMEOUT = 1000;
+   long int motor_timeout_duration;
+   long int max_push_current_duration;
+   bool actuator_duration_activated;
+   bool chose_new_lane;
+   bool reward_given;
+   bool in_first_lane;
+   MotorDurationEntry *peizo_motor_entry;
+
+   LANE_ID last_reported_lane; // Initially report non existing lane
+   byte last_reported_light_status; // Assign any random initial value 
+   byte last_reported_actuator_status; // It's type is Actuator::State
+   bool reported_motor_max_distance;
+   bool reported_motor_min_distance;
+   bool reported_motor_max_wait;
+   bool sensor_was_touched;
+
+   // Change to fit the number of motors that you have in your system
+   static const size_t MOTOR_DURATION_ENTERIES_SIZE = 6;
+   MotorDurationEntry motor_duration_entries[MOTOR_DURATION_ENTERIES_SIZE];
+
+   int actuator_max_pwm_distance = 700;
+   static const long int SOLENOID_DURATION = 200;
+
+   unsigned int trial_number;
+
+   static const long int SAME_SENSOR_MAX_THRESHOLD = 5;
+   static const long int FORCE_OTHER_SENSOR = 3;
+   static const long int FEEDBACK_AUTOMATED_REWARD_THRESHOLD = 3;
+   bool last_sensor_touched_left;
+   unsigned int same_sensor_touch_count;
+   bool in_force_sensor_mode;
+   bool is_force_sensor_left;
+   int miss_or_wrong_touch_count;
+
+   bool is_automated_reward;
+
+   long int delayed_report;
+};
+
+struct DistancesStruct
+{
+    uint16_t x_threshold_min;
+    uint16_t x_threshold_max;
+    uint16_t y_threshold_min;
+    uint16_t y_threshold_max;
+    uint16_t y_motor_threshold;
+
+    DistancesStruct ()
+    {
+        this->x_threshold_min = 100;
+        this->x_threshold_max = 350;
+        this->y_threshold_min = 2;
+        this->y_threshold_max = 80;
+        this->y_motor_threshold = 45;
+    }
+} Distances;
+
+
+
+struct StatsMessage
+{
+  byte event_id;
+  char* msg;
+  short parameter;
+
+  StatsMessage(byte event_id, char* msg, short parameter)
+  {
+      this->event_id = event_id;
+      this->msg = msg;
+      this->parameter = parameter;
+  }
+
+  StatsMessage(byte event_id, char* msg)
+  {
+      this->event_id = event_id;
+      this->msg = msg;
+      this->parameter = -1;
+    }
+};
+
+#endif

+ 20 - 0
Airtrack/leds.h

@@ -0,0 +1,20 @@
+#ifndef LEDS_MODULE
+#define LEDS_MODULE
+
+#import <Arduino.h>
+#include "definitions.h"
+
+struct LedsStruct
+{
+    // CONST_PIN_TYPE Unused = 1;
+
+    CONST_PIN_TYPE SensorLeft = 18;
+    CONST_PIN_TYPE SensorRight = 19;
+
+    //CONST_PIN_TYPE Solenoid = 9;
+
+    // CONST_PIN_TYPE ActuatorPush = 10;
+    // CONST_PIN_TYPE ActuatorPull = 11;
+} Leds;
+
+#endif

+ 58 - 0
Airtrack/mpr121.h

@@ -0,0 +1,58 @@
+/*
+    MPR121.h
+	April 8, 2010
+	by: Jim Lindblom
+*/
+
+// MPR121 Register Defines
+#define MHD_R	0x2B
+#define NHD_R	0x2C
+#define	NCL_R 	0x2D
+#define	FDL_R	0x2E
+#define	MHD_F	0x2F
+#define	NHD_F	0x30
+#define	NCL_F	0x31
+#define	FDL_F	0x32
+#define	ELE0_T	0x41
+#define	ELE0_R	0x42
+#define	ELE1_T	0x43
+#define	ELE1_R	0x44
+#define	ELE2_T	0x45
+#define	ELE2_R	0x46
+#define	ELE3_T	0x47
+#define	ELE3_R	0x48
+#define	ELE4_T	0x49
+#define	ELE4_R	0x4A
+#define	ELE5_T	0x4B
+#define	ELE5_R	0x4C
+#define	ELE6_T	0x4D
+#define	ELE6_R	0x4E
+#define	ELE7_T	0x4F
+#define	ELE7_R	0x50
+#define	ELE8_T	0x51
+#define	ELE8_R	0x52
+#define	ELE9_T	0x53
+#define	ELE9_R	0x54
+#define	ELE10_T	0x55
+#define	ELE10_R	0x56
+#define	ELE11_T	0x57
+#define	ELE11_R	0x58
+#define	FIL_CFG	0x5D
+#define	ELE_CFG	0x5E
+#define GPIO_CTRL0	0x73
+#define	GPIO_CTRL1	0x74
+#define GPIO_DATA	0x75
+#define	GPIO_DIR	0x76
+#define	GPIO_EN		0x77
+#define	GPIO_SET	0x78
+#define	GPIO_CLEAR	0x79
+#define	GPIO_TOGGLE	0x7A
+#define	ATO_CFG0	0x7B
+#define	ATO_CFGU	0x7D
+#define	ATO_CFGL	0x7E
+#define	ATO_CFGT	0x7F
+
+
+// Global Constants
+#define TOU_THRESH	0x10
+#define	REL_THRESH	0x02

+ 80 - 0
Airtrack/pins.h

@@ -0,0 +1,80 @@
+#ifndef PINS_MODULE
+#define PINS_MODULE
+
+#import <Arduino.h>
+#include "definitions.h"
+
+struct PinStruct
+{
+
+#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // If Arduiono Uno is used
+    #pragma message("Compiling airtrack for Arduino Uno - PWM pins has no effect")
+    #define NO_EFFECT_PIN 13
+    #define USE_PIN(PIN_NUM)  NO_EFFECT_PIN
+    #define ARDUINO_UNO
+#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) // If Arduino Mega is used
+    #pragma message("Compiling airtrack for Arduino Mega - Using PWM pins")
+    #define USE_PIN(PIN_NUM)  PIN_NUM
+    #define ARDUINO_MEGA
+#else
+    #warning "Unknown Arduino board type, PWM works might not work or conflict"
+    #define USE_PIN(PIN_NUM)  PIN_NUM
+#endif 
+
+
+#ifdef ARDUINO_UNO 
+    // Pins configuration for arduino uno
+    CONST_PIN_TYPE Sensor = 2;
+
+    CONST_PIN_TYPE ActuatorPush = 4;
+    CONST_PIN_TYPE ActuatorPull = 3;
+
+    CONST_PIN_TYPE SolenoidLeft = 5;
+    CONST_PIN_TYPE SolenoidRight = 8;
+
+    CONST_PIN_TYPE LaneLight = 6;
+
+    CONST_PIN_TYPE PeizoTone = 7;
+
+#else #if def ARDUINO_MEGA
+    // Pins configuration for arduino mega
+    CONST_PIN_TYPE Sensor = 38;
+
+    CONST_PIN_TYPE ActuatorPush = 30;
+    CONST_PIN_TYPE ActuatorPull = 32;
+
+    // 26 and 28 are free
+
+    CONST_PIN_TYPE SolenoidLeft = 22;
+    CONST_PIN_TYPE SolenoidRight = 24;
+
+    CONST_PIN_TYPE LaneLight = 27;
+    CONST_PIN_TYPE LaneLight2 = A14;
+
+    CONST_PIN_TYPE PeizoTone = 29;
+#endif #endif
+
+
+    // Has no effect except on arduino mega
+    CONST_PIN_TYPE PWM_CurrentLaneNum = USE_PIN(8);
+    CONST_PIN_TYPE PWM_CorrectLaneNum = USE_PIN(8);
+    CONST_PIN_TYPE PWM_LaneState = USE_PIN(4);
+    CONST_PIN_TYPE PWM_PixyX = USE_PIN(8);
+    CONST_PIN_TYPE PWM_PixyY = USE_PIN(8);
+    CONST_PIN_TYPE PWM_PixyAngle = USE_PIN(8);
+    CONST_PIN_TYPE PWM_LaneLed = USE_PIN(8);
+    
+    CONST_PIN_TYPE PWM_RotationDirection = USE_PIN(9);
+    CONST_PIN_TYPE PWM_LickDirection = USE_PIN(10);
+    CONST_PIN_TYPE PWM_DecisionResult = USE_PIN(11);
+    CONST_PIN_TYPE PWM_RewardResult = USE_PIN(12);
+    //CONST_PIN_TYPE PWM_RewardState = USE_PIN(13);
+    CONST_PIN_TYPE PWM_PiezoAlarm = USE_PIN(44);
+    CONST_PIN_TYPE PWM_Solenoid = USE_PIN(45);
+    CONST_PIN_TYPE PWM_Actuator = USE_PIN(46);
+
+    CONST_PIN_TYPE OutOfFirstLane = USE_PIN(39);
+    CONST_PIN_TYPE InCorrecctLane = USE_PIN(41);
+} Pins;
+
+#endif

+ 141 - 0
Airtrack/reporter.h

@@ -0,0 +1,141 @@
+#ifndef REPORTER_MODULE
+#define REPORTER_MODULE
+
+#import <Arduino.h>
+#include "definitions.h"
+
+#define PWM_(INDEX, TOTAL)  (byte)((255.0/TOTAL)*INDEX)
+
+
+void reportPWM (PIN_TYPE pwm_pin, byte value)
+{
+    #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) // If Arduino Mega is used
+        analogWrite(pwm_pin, value);
+    #endif
+}   
+
+
+struct CurrentLaneNumPWM { enum : byte
+{
+    Unknown = 0,
+    Lane1 = PWM_(1,4),
+    Lane2 = PWM_(2,4),
+    Lane3 = PWM_(3,4),
+    Lane4 = PWM_(4,4)
+};};
+
+struct CorrectLaneNumPWM { enum : byte
+{
+    Unknown = 0,
+    Lane1 = PWM_(1,4),
+    Lane2 = PWM_(2,4),
+    Lane3 = PWM_(3,4),
+    Lane4 = PWM_(4,4)
+};};
+
+struct LaneStatePwm { enum : byte
+{
+    Unknown = 0,
+    InsideLane = PWM_(1,2),
+    OutsideLane = PWM_(2,2),
+};};
+
+// Copied from "TPixy.h"
+// Pixy x-y position values
+#define PIXY_MIN_X                  0L
+#define PIXY_MAX_X                  319L
+#define PIXY_MIN_Y                  0L
+#define PIXY_MAX_Y                  199L
+struct PixyXPwmStruct 
+{
+    byte convert (float x) /*x is uint16_t*/
+    {
+        return (byte)((x / PIXY_MAX_X) * 255);
+    }
+} PixyXPwm;
+struct PixyYPwmStruct
+{ 
+    byte convert (float y) /*y is uint16_t*/
+    {
+        return (byte)((y / PIXY_MAX_Y) * 255);
+    }
+} PixyYPwm;
+struct PixyAnglePwmStruct
+{
+    byte convert (int angle) /*angle is int16_t*/
+    {
+        angle = (angle + 360) % 360;
+        return (byte)((angle / 360.0) * 255);
+    }
+} PixyAnglePwm;
+
+struct LaneLedPwm { enum : byte
+{
+    Off = PWM_(0,1),
+    On = PWM_(1,1),
+};};
+
+struct RotationDirectionPwm { enum : byte
+{
+    Unknown = 0,
+    Clockwise = PWM_(1,2),
+    AntiClockwise = PWM_(2,2),
+    // MIXED = PWM_(3,3),
+};};
+
+struct LickDirectionPwm { enum : byte
+{
+    Unknown = 0,
+    Untouched = PWM_(1,3),
+    Right = PWM_(2,3),
+    Left = PWM_(3,3),
+};};
+
+struct DecisionResultPwm { enum : byte
+{
+    Unknown = 0,
+    Correct = PWM_(1,3),
+    Wrong = PWM_(2,3),
+    Miss = PWM_(3,3),
+};};
+
+struct RewardResultPwm { enum : byte
+{
+    Unknown = 0,
+    Given = PWM_(1,3),
+    NotGiven = PWM_(2,3),
+    AutomatedGiven = PWM_(3,3),
+};};
+
+struct RewardStatePwm { enum : byte
+{
+    Unknown = 0,
+    Normal = PWM_(1,3),
+    ForcedLeft = PWM_(2,3),
+    ForcedRight = PWM_(3,3),
+};};
+
+struct PiezoAlarmPwm { enum : byte
+{
+    Off = PWM_(0,1),
+    On = PWM_(1,1),
+};};
+
+struct SolenoidPwm { enum : byte
+{
+    Unknown = 0,
+    LeftOpen = PWM_(1,3),
+    BothOff = PWM_(2,3),
+    RightOpen = PWM_(3,3),
+};};
+
+struct ActuatorPwm { enum : byte
+{
+    Unknown = 0,
+    MaxDistance = PWM_(1,4),
+    Pushing = PWM_(2,4),
+    Retracting = PWM_(3,4),
+    MinDistance = PWM_(4,4),
+};};
+
+#endif

+ 212 - 0
Airtrack/sensor.h

@@ -0,0 +1,212 @@
+#ifndef SENSOR_MODULE
+#define SENSOR_MODULE
+
+#import <Arduino.h>
+// #include "I2C/I2C.cpp"
+#include <Wire.h>
+#include "mpr121.h"
+#include "definitions.h"
+
+struct Sensor
+{
+  private:
+  
+    PIN_TYPE interrupt_pin;
+
+  public:
+
+    CONST_PIN_TYPE LEFT_ANALOUGE_PIN = 9;
+    CONST_PIN_TYPE RIGHT_ANALOUGE_PIN = 2;
+
+
+    Sensor (PIN_TYPE sensor_interrupt_pin)
+    {
+        this->interrupt_pin = sensor_interrupt_pin;
+    }
+
+    SensorTouched readInput()
+    {
+      // Serial.print("Checking for interrupt on pin: ");
+      // Serial.println(this->interrupt_pin);
+
+      SensorTouched sensor_touched = SensorTouched(false, false);
+      if (!digitalRead(this->interrupt_pin))
+      {
+        //read the touch state from the MPR121
+        Wire.requestFrom(0x5A,2);
+        //I2c.read(0x5A,2); 
+    
+        byte LSB = Wire.read(); // I2c.receive();
+        byte MSB = Wire.read(); // I2c.receive();
+        
+        uint16_t touched = ((MSB << 8) | LSB); //16bits that make up the touch states
+ 
+        // Serial.print("Checking for interrupt. variable touched: ");
+        // Serial.println(touched);
+        // We run the next commented out for loop to check for each pin,
+        // but we already know which pins are possible so no need for the loop
+        /*
+        for (int i=0; i < 12; i++)
+        {  // Check what electrodes were pressed
+            if(touched & (1<<i))
+            {
+            }
+        }
+        */
+
+        sensor_touched.change_happened = false;
+        if(touched & (1<<LEFT_ANALOUGE_PIN))
+        {
+          sensor_touched.left_sensor = true;
+        }
+        else
+        {
+          sensor_touched.left_sensor = false; 
+        }
+
+        if(touched & (1<<RIGHT_ANALOUGE_PIN))
+        {
+          sensor_touched.right_sensor = true;
+        }
+        else
+        {
+          sensor_touched.right_sensor = false; 
+        }
+
+        if (sensor_touched.left_sensor || sensor_touched.right_sensor)
+        {
+          sensor_touched.change_happened = true;
+        }
+      }
+      if (sensor_touched.change_happened)
+      {
+        //Serial.print("Returning sensor_touched: change_happened: ");
+        //Serial.print(sensor_touched.change_happened ? "true" : "false");
+        //Serial.print(" left_sensor: ");
+        //Serial.print(sensor_touched.left_sensor ? "touched" : "untouched");
+        //Serial.print(" right_sensor: ");
+        //Serial.println(sensor_touched.right_sensor ? "touch" : "untouched");
+      }
+      return sensor_touched;
+    }
+
+    void setup()
+    {
+      static bool initialize_once = false;       
+      if (!initialize_once)
+      {
+        this->setupOnce();
+        initialize_once = true;
+      }
+    }
+
+  private:
+    void setupOnce(void)
+    {
+      //Serial.print("Setting up sensor on pin: ");
+      //Serial.println(this->interrupt_pin);
+      pinMode(this->interrupt_pin, INPUT);
+      digitalWrite(this->interrupt_pin, HIGH); //enable pullup resistor 
+
+      Wire.begin();
+      // I2c.begin();
+      // I2c.timeOut(3000);
+
+      //Serial.println("Setting 0x00 register");
+      set_register(0x5A, ELE_CFG, 0x00); 
+      
+      //Serial.println("Setting Section A");
+      // Section A - Controls filtering when data is > baseline.
+      set_register(0x5A, MHD_R, 0x01);
+      set_register(0x5A, NHD_R, 0x01);
+      set_register(0x5A, NCL_R, 0x00);
+      set_register(0x5A, FDL_R, 0x00);
+
+      //Serial.println("Setting Section B");
+      // Section B - Controls filtering when data is < baseline.
+      set_register(0x5A, MHD_F, 0x01);
+      set_register(0x5A, NHD_F, 0x01);
+      set_register(0x5A, NCL_F, 0xFF);
+      set_register(0x5A, FDL_F, 0x02);
+      
+      // Section C - Sets touch and release thresholds for each electrode
+      // #define NEW_TOU_THRESH TOU_THRESH // 0x10
+      // #define NEW_REL_THRESH REL_THRESH // 0x02
+      #define NEW_TOU_THRESH 0x09
+      #define NEW_REL_THRESH 0x35
+
+      set_register(0x5A, ELE0_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE0_R, NEW_REL_THRESH);
+     
+      set_register(0x5A, ELE1_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE1_R, NEW_REL_THRESH);
+      
+      set_register(0x5A, ELE2_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE2_R, NEW_REL_THRESH);
+      
+      set_register(0x5A, ELE3_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE3_R, NEW_REL_THRESH);
+      
+      set_register(0x5A, ELE4_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE4_R, NEW_REL_THRESH);
+      
+      set_register(0x5A, ELE5_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE5_R, NEW_REL_THRESH);
+      
+      set_register(0x5A, ELE6_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE6_R, NEW_REL_THRESH);
+      
+      set_register(0x5A, ELE7_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE7_R, NEW_REL_THRESH);
+      
+      set_register(0x5A, ELE8_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE8_R, NEW_REL_THRESH);
+
+      #define NEW_TOU_THRESH_SPECIAL 0x01
+      #define NEW_REL_THRESH_SPECIAL 0x35
+
+      set_register(0x5A, ELE9_T, NEW_TOU_THRESH_SPECIAL);
+      set_register(0x5A, ELE9_R, NEW_REL_THRESH_SPECIAL);
+      
+      set_register(0x5A, ELE10_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE10_R, NEW_REL_THRESH);
+      
+      set_register(0x5A, ELE11_T, NEW_TOU_THRESH);
+      set_register(0x5A, ELE11_R, NEW_REL_THRESH);
+      
+      //Serial.println("Setting Section D");
+      // Section D
+      // Set the Filter Configuration
+      // Set ESI2
+      set_register(0x5A, FIL_CFG, 0x04);
+      
+      // Section E
+      // Electrode Configuration
+      // Set ELE_CFG to 0x00 to return to standby mode
+      set_register(0x5A, ELE_CFG, 0x0C);  // Enables all 12 Electrodes
+      
+      
+      // Section F
+      // Enable Auto Config and auto Reconfig
+      /*set_register(0x5A, ATO_CFG0, 0x0B);
+      set_register(0x5A, ATO_CFGU, 0xC9);  // USL = (Vdd-0.7)/vdd*256 = 0xC9 @3.3V   set_register(0x5A, ATO_CFGL, 0x82);  // LSL = 0.65*USL = 0x82 @3.3V
+      set_register(0x5A, ATO_CFGT, 0xB5);*/  // Target = 0.9*USL = 0xB5 @3.3V
+      set_register(0x5A, ELE_CFG, 0x0C);
+    }
+
+    void set_register(int address, unsigned char r, unsigned char v)
+    {
+        // Serial.println("Beginnig transimittion");
+        Wire.beginTransmission(address);
+        //Serial.print("Writing r:");
+        Wire.write(r);
+        //Serial.println( I2c.write((uint8_t)address, r) );
+        //Serial.print("Writing v: ");
+        Wire.write(v);
+        //Serial.println( I2c.write((uint8_t)address, v) );
+        //Serial.println("ending transimittion");
+        Wire.endTransmission();
+    }
+};
+
+#endif

+ 220 - 0
Airtrack/stats.h

@@ -0,0 +1,220 @@
+#ifndef STATS_MODULE
+#define STATS_MODULE
+
+
+#import <Arduino.h>
+#include "definitions.h"
+#include "pins.h"
+#include "reporter.h"
+
+struct StatsStruct
+{
+    StatsMessage ENTERED_LANE(short lane) 
+    {
+      reportPWM(Pins.PWM_LaneState, LaneStatePwm::InsideLane);
+      return StatsMessage(0, "Entered lane\0", lane + 1);
+    }
+
+    StatsMessage EXITED_LANE(short lane) 
+    {
+        reportPWM(Pins.PWM_LaneState, LaneStatePwm::OutsideLane);
+        return StatsMessage(1, "Exited lane\0", lane + 1);
+    }
+
+    StatsMessage MOTOR_PUSHED()
+    {
+        reportPWM(Pins.PWM_Actuator, ActuatorPwm::Pushing);
+        return StatsMessage(10, "Motor is pushed\0");
+    }
+
+    StatsMessage MOTOR_PULLED()
+    {
+        reportPWM(Pins.PWM_Actuator, ActuatorPwm::Retracting);
+        return StatsMessage(11, "Motor is pulled\0");
+    }
+
+    StatsMessage MOTOR_MAX_RANGE()
+    {
+        reportPWM(Pins.PWM_Actuator, ActuatorPwm::MaxDistance);
+        return StatsMessage(12, "Motor is at max distance\0");
+    }
+    StatsMessage MOTOR_MIN_RANGE()
+    {
+        reportPWM(Pins.PWM_Actuator, ActuatorPwm::MinDistance);
+        return StatsMessage(13, "Motor is at min distance\0");
+    }
+    StatsMessage MOTOR_WAIT_DONE()
+    {
+        return StatsMessage(14, "Motor wait time is is done.\0");
+    }
+
+    StatsMessage ENTERED_LANE_RANGE(short lane) 
+    {
+        lane++; // Make lanes start from 1 instead of zero
+        // TODO: Create a function to take care of this
+        switch (lane)
+        {
+            case 1:
+                reportPWM(Pins.PWM_CurrentLaneNum, CurrentLaneNumPWM::Lane1);
+                break;
+            case 2:
+                reportPWM(Pins.PWM_CurrentLaneNum, CurrentLaneNumPWM::Lane2);
+                break;
+            case 3:
+                reportPWM(Pins.PWM_CurrentLaneNum, CurrentLaneNumPWM::Lane3);
+                break;
+            case 4:
+                reportPWM(Pins.PWM_CurrentLaneNum, CurrentLaneNumPWM::Lane4);
+                break;
+            default:
+                reportPWM(Pins.PWM_CurrentLaneNum, CurrentLaneNumPWM::Unknown);
+        }
+        return StatsMessage(20, "Entered rotation range of lane\0", lane);
+    }
+
+    StatsMessage CORRECT_SENSOR_TOUCHED() 
+    {
+        reportPWM(Pins.PWM_DecisionResult, DecisionResultPwm::Correct);
+        return StatsMessage(30, "Correct sensor touched\0");
+    }
+    StatsMessage WRONG_SENSOR_TOUCHED()
+    {
+        reportPWM(Pins.PWM_DecisionResult, DecisionResultPwm::Wrong);
+        return StatsMessage(31, "Wrong sensor touched\0");
+    }
+
+    StatsMessage RIGHT_SENSOR_TOUCHED()
+    {
+        reportPWM(Pins.PWM_LickDirection, LickDirectionPwm::Right);
+        return StatsMessage(35, "R-located sensor touched\0");
+    }
+    StatsMessage LEFT_SENSOR_TOUCHED()
+    {
+        reportPWM(Pins.PWM_LickDirection, LickDirectionPwm::Left);
+        return StatsMessage(36, "L-located sensor touched\0");
+    }
+    void REPORT_SENSORS_UNTOUCHED ()
+    {
+        reportPWM(Pins.PWM_LickDirection, LickDirectionPwm::Untouched);
+    }
+
+    // Next one is not reported yet
+    StatsMessage OTHER_SENSOR_TOUCHED(short sensor)
+    {
+        return StatsMessage(37, "Other sensor touched - Sensor nr.\0", sensor);
+    }
+
+    StatsMessage REWARD_GIVEN(bool automated_mode)
+    {
+        if (automated_mode)
+        {
+            reportPWM(Pins.PWM_RewardResult, RewardResultPwm::AutomatedGiven);
+            return StatsMessage(44, "Giving reward automatically\0");
+        }
+        else
+        {
+            reportPWM(Pins.PWM_RewardResult, RewardResultPwm::Given);
+            return StatsMessage(40, "Giving reward\0");   
+        }
+    }
+    StatsMessage REWARD_NOT_GIVEN()
+    {
+        reportPWM(Pins.PWM_RewardResult, RewardResultPwm::NotGiven);
+        return StatsMessage(41, "Not giving reward\0");
+    }
+    StatsMessage MISS_DECISION()
+    {
+        reportPWM(Pins.PWM_DecisionResult, DecisionResultPwm::Miss);
+        return StatsMessage(42, "No Decision was made in time\0");
+    }
+
+    StatsMessage NEW_LANE(short lane) 
+    {
+        // reset trial based PWMs
+        reportPWM(Pins.PWM_DecisionResult, DecisionResultPwm::Unknown);
+        reportPWM(Pins.PWM_RewardResult, RewardResultPwm::Unknown);
+
+        lane++; // Make lanes start from 1 instead of zero
+        reportPWM(Pins.PWM_CorrectLaneNum, lane);
+        return StatsMessage(50, "New lane chosen\0", lane);
+    }
+    StatsMessage NEW_TRIAL(short trial)
+    {
+        return StatsMessage(55, "Trial number\0", trial);
+    }
+
+    StatsMessage LIGHT_ON() 
+    {
+        // TEMP: Move this to its own stats
+        reportPWM(Pins.InCorrecctLane, LaneLedPwm::Off);
+        reportPWM(Pins.PWM_LaneLed, LaneLedPwm::On);
+        return StatsMessage(60, "Cue light turned on\0");
+    }
+    StatsMessage LIGHT_OFF()
+    {
+        // TEMP: Move this to its own stats
+        reportPWM(Pins.InCorrecctLane, LaneLedPwm::On);
+        reportPWM(Pins.PWM_LaneLed, LaneLedPwm::Off);
+        return StatsMessage(61, "Cue light turned off\0");
+    }
+
+    StatsMessage SOLENOID_RIGHT_ON()
+    {
+        reportPWM(Pins.PWM_Solenoid, SolenoidPwm::RightOpen);
+        return StatsMessage(70, "R-located solenoid turned on\0");
+    }
+    StatsMessage SOLENOID_RIGHT_OFF()
+    {
+        reportPWM(Pins.PWM_Solenoid, SolenoidPwm::BothOff);
+        return StatsMessage(71, "R-located solenoid turned off\0");
+    }
+    StatsMessage SOLENOID_LEFT_ON()
+    {
+        reportPWM(Pins.PWM_Solenoid, SolenoidPwm::LeftOpen);
+        return StatsMessage(72, "L-located solenoid turned on\0");
+    }
+    StatsMessage SOLENOID_LEFT_OFF()
+    {
+        reportPWM(Pins.PWM_Solenoid, SolenoidPwm::BothOff);
+        return StatsMessage(73, "L-located solenoid turned off\0");
+    }
+
+    StatsMessage FORCE_SENSOR_ON(bool is_left)
+    {
+        char* msg;
+        if (is_left)
+        {
+            // TODO: change PWM in next trial
+            //reportPWM(Pins.PWM_RewardState, RewardStatePwm::ForcedLeft);
+            msg = (char*)"Force sensor mode on (left)\0";
+        }
+        else
+        {
+            //reportPWM(Pins.PWM_RewardState, RewardStatePwm::ForcedRight);
+            msg = (char*)"Force sensor mode on (right)\0";
+        }
+        return StatsMessage(80, msg, is_left);
+    }
+    StatsMessage FORCE_SENSOR_OFF()
+    {
+        //reportPWM(Pins.PWM_RewardState, RewardStatePwm::Normal);
+        return StatsMessage(81, "Force sensor mode is off\0");
+    }
+    StatsMessage FEEDBACK_AUTOMATED_ON()
+    {
+        return StatsMessage(82, "Feedback automated on\0");
+    }
+    StatsMessage FEEDBACK_AUTOMATED_OFF()
+    {
+        return StatsMessage(83, "Feedback automated off\0");
+    }
+
+    void REPORT_PIXY_POSITION (SubjectLocation location)
+    {
+        reportPWM(Pins.PWM_PixyX, PixyXPwm.convert(location.x));
+        reportPWM(Pins.PWM_PixyY, PixyYPwm.convert(location.y));
+        reportPWM(Pins.PWM_PixyAngle, PixyAnglePwm.convert(location.angle));
+    }
+} Stats;
+
+#endif

+ 15 - 0
LICENSE

@@ -0,0 +1,15 @@
+Copyright (C) 2019-2020 Ronny Bergmann
+
+This program is free software; you can redistribute it and/or modify
+it under the terms of the GNU General Public License as published by
+the Free Software Foundation; either version 2 of the License, or
+(at your option) any later version.
+
+This program is distributed in the hope that it will be useful,
+but WITHOUT ANY WARRANTY; without even the implied warranty of
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+GNU General Public License for more details.
+
+You should have received a copy of the GNU General Public License along
+with this program; if not, write to the Free Software Foundation, Inc.,
+51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.

+ 9 - 0
README.md

@@ -0,0 +1,9 @@
+# Arduino code for Airtrack
+
+The Airtrack Arduino code that generates analog outputs of the position and the angle of the platform.
+
+This is a fork of [the original Airtrack codebase](https://github.com/larkum-lab/airtrack).
+
+## License
+
+Copyright (c) 2019-2020 Ronny Bergmann, GPL v2