diff --git a/opencmSensorboard/~opencmSensorboard.kicad_pcb.lck b/opencmSensorboard/~opencmSensorboard.kicad_pcb.lck deleted file mode 100644 index 33fa98a..0000000 --- a/opencmSensorboard/~opencmSensorboard.kicad_pcb.lck +++ /dev/null @@ -1 +0,0 @@ -{"hostname":"WS42","username":"philipp.kramer"} \ No newline at end of file diff --git a/prosthesis_controller/barometer.cpp b/prosthesis_controller/barometer.cpp new file mode 100644 index 0000000..49c242b --- /dev/null +++ b/prosthesis_controller/barometer.cpp @@ -0,0 +1,66 @@ +#include "Arduino.h" +#include "barometer.h" + +Adafruit_BMP280 bmp; // I2C + + +float barometer_temp; +float barometer_pressure; +float barometer_alt; + +float barometer_alt_calibrationpressure=0; //example: 1002.45 +bool barometer_alt_calibrated=false; + +void initBarometer() { + unsigned status; + Wire.begin(25,24); + status = bmp.begin(BMP280_ADDRESS_ALT, BMP280_CHIPID); + + //status = bmp.begin(); + if (!status) { + Serial.println(F("Could not find a valid BMP280 sensor")); + } + + /* Default settings from datasheet. */ + bmp.setSampling(Adafruit_BMP280::MODE_NORMAL, /* Operating Mode. */ + Adafruit_BMP280::SAMPLING_X2, /* Temp. oversampling */ + Adafruit_BMP280::SAMPLING_X16, /* Pressure oversampling */ + Adafruit_BMP280::FILTER_X16, /* Filtering. */ + Adafruit_BMP280::STANDBY_MS_500); /* Standby time. */ + +} + +void loopBarometer(unsigned long millis) { + static unsigned long last_barometerreading = 0; + if (millis - last_barometerreading > BAROMETER_UPDATE_INTERVAL) + { + last_barometerreading=millis; + barometer_temp=bmp.readTemperature(); + + + + if (!barometer_alt_calibrated) { //only read pressure for calibration + barometer_pressure=bmp.readPressure(); + } + + if (!barometer_alt_calibrated && millis>5000) { + + barometer_alt_calibrated=true; + barometer_alt_calibrationpressure=barometer_pressure/100.0; + } + + if (barometer_alt_calibrated) { + barometer_alt=bmp.readAltitude(barometer_alt_calibrationpressure); + } + } + + + +} + +float getBarometerHeight() { + return barometer_alt; +} +float getBarometerTemperature() { + return barometer_temp; +} diff --git a/prosthesis_controller/barometer.h b/prosthesis_controller/barometer.h new file mode 100644 index 0000000..adab325 --- /dev/null +++ b/prosthesis_controller/barometer.h @@ -0,0 +1,16 @@ +#ifndef BAROMETER_H_ +#define BAROMETER_H_ + + +#include +#include +#include //Adafruit BMP280 Library by Adafruit 2.6.8 + +#define BAROMETER_UPDATE_INTERVAL 1000/5 + +void initBarometer(); +void loopBarometer(unsigned long millis); +float getBarometerHeight(); +float getBarometerTemperature(); + +#endif \ No newline at end of file diff --git a/prosthesis_controller/behaviour.cpp b/prosthesis_controller/behaviour.cpp index 2b89823..bbf3340 100644 --- a/prosthesis_controller/behaviour.cpp +++ b/prosthesis_controller/behaviour.cpp @@ -10,66 +10,72 @@ float matrix_weights_main[SERVO_COUNT_MAIN][WEIGHT_COUNT]; //mapping outputs, se float matrix_weights_peripheralL[SERVO_COUNT_PERIPHERAL][WEIGHT_COUNT]; float matrix_weights_peripheralR[SERVO_COUNT_PERIPHERAL][WEIGHT_COUNT]; + +void updateMood(unsigned long millis,float gyroX,float gyroY,float gyroZ,bool bellyup, bool body_present, bool contact_main, bool contact_peripheralL, bool contact_peripheralR,float height,float temp_ambient,float temp_object,float pumpspeed, float servoerror) { + static unsigned long last_mood_update=0; + if (millis-last_mood_update>MOOD_UPDATE_INTERVAL) { + last_mood_update=millis; + mood.arousal=0; + mood.valence=0; + } +} + void updateMatrixWeights(unsigned long millis,bool bellyup, bool body_present, bool contact_main, bool contact_peripheralL, bool contact_peripheralR, float pitch, float roll){ - static unsigned long last_weights_update=0; if (millis-last_weights_update>WEIGHT_UPDATE_INTERVAL) { last_weights_update=millis; - //float map_mode=constrain(mapfloat(mood.wakefulness,0,0.2, 1,0),0,1); //0=pitchroll control, 1=noise - //float map_mode=constrain(mapfloat(mood.shakiness,0,0.2, 1,0),0,1); //0=pitchroll control, 1=noise - - /*float map_mode_noise=constrain(mapfloat(mood.wakefulness,0,0.2, 0,1),0,1); - float map_mode_rollpitch=constrain(mapfloat(mood.shakiness,0,0.5, 0,1),0,1); - float map_mode_slither=0; - float map_mode_sleeping=mood.loneliness;*/ + + //### Update Mode ### static float map_mode_rollpitch=0; static float map_mode_walking=0; static float map_mode_sleeping=0; static float map_mode_noise=0; + float aim_map_mode_rollpitch=0; + float aim_map_mode_walking=0; + float aim_map_mode_sleeping=0; + float aim_map_mode_noise=0; + - if (body_present) { - map_mode_rollpitch+=0.3 *WEIGHT_UPDATE_INTERVAL/1000.0; - map_mode_walking-=0.5 *WEIGHT_UPDATE_INTERVAL/1000.0; - map_mode_noise-=0.2 *WEIGHT_UPDATE_INTERVAL/1000.0; + if (body_present) { //attached + aim_map_mode_rollpitch=1.0; - }else{ - map_mode_rollpitch-=.2 *WEIGHT_UPDATE_INTERVAL/1000.0; - if (bellyup) { - map_mode_walking+=0.3 *WEIGHT_UPDATE_INTERVAL/1000.0; - map_mode_noise-=.2 *WEIGHT_UPDATE_INTERVAL/1000.0; + }else{ //detached + if (bellyup) { //belly up + aim_map_mode_walking=1.0; }else{ //sitting on a level survace - map_mode_walking-=0.1 *WEIGHT_UPDATE_INTERVAL/1000.0; - map_mode_noise+=0.3*WEIGHT_UPDATE_INTERVAL/1000.0; + aim_map_mode_noise=1.0; } } - - - map_mode_walking=constrain(map_mode_walking,0.0,1.0); - map_mode_rollpitch=constrain(map_mode_rollpitch,0.0,1.0); - map_mode_noise=constrain(map_mode_noise,0.0,1.0); + map_mode_rollpitch=interpolateTo(map_mode_rollpitch,aim_map_mode_rollpitch,WEIGHT_UPDATE_INTERVAL/1000.0,0.3); + map_mode_walking=interpolateTo(map_mode_walking,aim_map_mode_walking,WEIGHT_UPDATE_INTERVAL/1000.0,0.3); + map_mode_sleeping=interpolateTo(map_mode_sleeping,aim_map_mode_sleeping,WEIGHT_UPDATE_INTERVAL/1000.0,0.3); + map_mode_noise=interpolateTo(map_mode_noise,aim_map_mode_noise,WEIGHT_UPDATE_INTERVAL/1000.0,0.3); - + + /* Serial.print("Walking: \t"); Serial.println(map_mode_walking); Serial.print("RollPitch: \t"); Serial.println(map_mode_rollpitch); + Serial.print("Sleeping: \t"); Serial.println(map_mode_sleeping); Serial.print("Noise: \t"); Serial.println(map_mode_noise); Serial.println(); + */ - - float map_sum=map_mode_walking+map_mode_rollpitch+map_mode_noise; + float map_sum=map_mode_walking+map_mode_rollpitch+map_mode_sleeping+map_mode_noise; map_mode_walking/=map_sum; map_mode_rollpitch/=map_sum; + map_mode_sleeping/=map_sum; map_mode_noise/=map_sum; //divide mapping so the sum will be 1.0 - analogWrite(PIN_VIBRATION,contact_main*map_mode_noise*64); - Serial.print("Vibrt:"); Serial.println(contact_main*map_mode_noise*160); + analogWrite(PIN_VIBRATION,contact_main*map_mode_noise*64); //TODO, remove + //reset all weights for (uint8_t i=0;iaimvalue) { + result=aimvalue; + } + }else if (result>aimvalue){ + result=result-timestep*speed; + if (resultSERVO_UPDATE_INTERVAL/SERVO_COUNT){ + + //Sequentially set servo angles + if (millis-last_servo_update>SERVO_UPDATE_INTERVAL/SERVO_COUNT && millis-last_readservo_update>SERVO_MIN_COMMAND_TIME){ last_servo_update=millis; - dxl.setGoalPosition(servos[servoUpdateI].id, constrain((servos[servoUpdateI].offset_angle+servos[servoUpdateI].angle*servos[servoUpdateI].orientation) , servos[servoUpdateI].min_angle,servos[servoUpdateI].max_angle), UNIT_DEGREE); //asdf + dxl.setGoalPosition(servos[servoUpdateI].id, constrain((servos[servoUpdateI].offset_angle+servos[servoUpdateI].angle*servos[servoUpdateI].orientation) , servos[servoUpdateI].min_angle,servos[servoUpdateI].max_angle), UNIT_DEGREE); servoUpdateI++; servoUpdateI%=SERVO_COUNT; } + + //Sequentially read servo status + if (millis-last_readservo_update>SERVO_READUPDATE_INTERVAL/SERVO_COUNT && millis-last_servo_update>SERVO_MIN_COMMAND_TIME){ + last_readservo_update=millis; + + servos[servoReadI].actual_angle = dxl.getPresentPosition(servos[servoReadI].id, UNIT_DEGREE); + + servoReadI++; + servoReadI%=SERVO_COUNT; + } } +float getAverageServoPositionerror() +{ + float angleerror=0; + for (uint8_t i=0;i "); Serial.print(servos[i].offset_angle+servos[i].angle); - Serial.print("Servo"); Serial.print(i);Serial.print(" : "); Serial.print(servos[i].offset_angle+servos[i].angle); + Serial.print("Servo"); Serial.print(i);Serial.print(" : "); Serial.print(servos[i].actual_angle); Serial.print(" -> "); Serial.print(servos[i].offset_angle+servos[i].angle); Serial.println(); } + Serial.print("erroravg:"); Serial.print(getAverageServoPositionerror()); + Serial.println(); } diff --git a/prosthesis_controller/servo.h b/prosthesis_controller/servo.h index 670b893..44585d3 100644 --- a/prosthesis_controller/servo.h +++ b/prosthesis_controller/servo.h @@ -16,6 +16,8 @@ #define DXL_SERIAL Serial1 #define SERVO_UPDATE_INTERVAL 1000/50 +#define SERVO_READUPDATE_INTERVAL 1000/5 +#define SERVO_MIN_COMMAND_TIME 1 //should be less than any of the other servo intervals/SERVO_COUNT #define SERVO_COUNT 3 @@ -26,14 +28,15 @@ struct dxl_servo { int id; //int initial_speed; - float offset_angle; - float angle; - float min_angle; - float max_angle; - int orientation; - uint8_t mode=OP_CURRENT_BASED_POSITION; - float current; - uint16_t modelnumber; + float offset_angle; //constant offset. set this to match angle=0 to a straight arm + float angle; //commanded angle + float actual_angle; //angle read from servo + float min_angle; //soft angle limit + float max_angle; //soft angle limit + int orientation; //1.0 = forward. -1.0 = backwards + uint8_t mode=OP_CURRENT_BASED_POSITION; // OP_POSITION, OP_CURRENT_BASED_POSITION + float current; //when mode=OP_CURRENT_BASED_POSITION, set current for servo + uint16_t modelnumber; //Servo Model number for connection check at startup. use 0 to deactivate }; @@ -43,6 +46,7 @@ void scanDynamixel(); void changeID(uint8_t present_id, uint8_t new_id); void initServos(); void loopServos(unsigned long millis); +float getAverageServoPositionerror(); void printServoDebug(); diff --git a/prosthesis_controller/vacuum.cpp b/prosthesis_controller/vacuum.cpp index 002e5d3..5716b83 100644 --- a/prosthesis_controller/vacuum.cpp +++ b/prosthesis_controller/vacuum.cpp @@ -85,6 +85,10 @@ void loopVacuum(unsigned long millis) { } } +float getAveragePumpspeed(){ + return (vacuumPump1+vacuumPump2)/2.0; +} + void setVacuum(bool val) { if (val) { //True = turn off, False = Release pump2PID.SetMode(AUTOMATIC); diff --git a/prosthesis_controller/vacuum.h b/prosthesis_controller/vacuum.h index 3d8f697..48ab4f2 100644 --- a/prosthesis_controller/vacuum.h +++ b/prosthesis_controller/vacuum.h @@ -15,6 +15,6 @@ void loopVacuum(unsigned long millis); void setVacuum(bool val); void printVacuumValues(); long readHX710B(uint8_t outpin); - +float getAveragePumpspeed(); #endif /* VACUUM_H_ */ \ No newline at end of file