1
0
This commit is contained in:
Lukas Bachschwell 2017-12-03 22:04:39 +01:00
parent 16d38c6435
commit 7efec87cee
4 changed files with 107 additions and 121 deletions

View File

@ -6,7 +6,7 @@
void Hippie::init(int YL, int YR, int RL, int RR, int Buzzer) { void Hippie::init(int YL, int YR, int RL, int RR, int Buzzer) {
servo_pins[0] = YL; servo_pins[0] = YL;
servo_pins[1] = YR; servo_pins[1] = YR;
servo_pins[2] = RL; servo_pins[2] = RL;
@ -15,11 +15,11 @@ void Hippie::init(int YL, int YR, int RL, int RR, int Buzzer) {
attachServos(); attachServos();
isHippieResting=false; isHippieResting=false;
for (int i = 0; i < 4; i++) servo_position[i] = 90; for (int i = 0; i < 4; i++) servo_position[i] = 90;
//Buzzer & noise sensor pins: //Buzzer & noise sensor pins:
pinBuzzer = Buzzer; pinBuzzer = Buzzer;
pinMode(Buzzer,OUTPUT); pinMode(Buzzer,OUTPUT);
@ -95,14 +95,14 @@ void Hippie::_execute(int A[4], int O[4], int T, double phase_diff[4], float ste
} }
int cycles=(int)steps; int cycles=(int)steps;
//-- Execute complete cycles //-- Execute complete cycles
if (cycles >= 1) if (cycles >= 1)
for(int i = 0; i < cycles; i++) for(int i = 0; i < cycles; i++)
oscillateServos(A,O, T, phase_diff); oscillateServos(A,O, T, phase_diff);
//-- Execute the final not complete cycle //-- Execute the final not complete cycle
oscillateServos(A,O, T, phase_diff,(float)steps-cycles); oscillateServos(A,O, T, phase_diff,(float)steps-cycles);
} }
@ -156,15 +156,15 @@ void Hippie::jump(float steps, int T){
//-- Hippie Test Positions (bring feets and hips in certain position) //-- Hippie Test Positions (bring feets and hips in certain position)
//--------------------------------------------------------- //---------------------------------------------------------
void Hippie::test_pos(){ void Hippie::test_pos(){
int left_feet_up[4]={90,0,90,30}; //watch from view of robot: [3] = left leg ... by + value: turn right int left_feet_up[4]={90,0,90,30}; //watch from view of robot: [3] = left leg ... by + value: turn right
_moveServos(1000,left_feet_up); // [4] = right leg ... by + value: right side up _moveServos(1000,left_feet_up); // [4] = right leg ... by + value: right side up
} }
//--------------------------------------------------------- //---------------------------------------------------------
//-- Hippie gait: Walking (forward or backward) //-- Hippie gait: Walking (forward or backward)
//-- Parameters: //-- Parameters:
//-- * steps: Number of steps //-- * steps: Number of steps
//-- * T : Period //-- * T : Period
@ -182,11 +182,11 @@ void Hippie::walk(float steps, int T, int dir){
int A[4]= {30, 30, 40, 40}; //20 int A[4]= {30, 30, 40, 40}; //20
int O[4] = {0, 0, 4, 30}; //-4 int O[4] = {0, 0, 4, 30}; //-4
double phase_diff[4] = {0, 0, DEG2RAD(dir * -90), DEG2RAD(dir * -90)}; double phase_diff[4] = {0, 0, DEG2RAD(dir * -90), DEG2RAD(dir * -90)};
if ( dir == -1) { double phase_diff[4] = {0, 0, DEG2RAD(dir * 90), DEG2RAD(dir * 90)}; } if ( dir == -1) { double phase_diff[4] = {0, 0, DEG2RAD(dir * 90), DEG2RAD(dir * 90)}; }
//-- Let's oscillate the servos! //-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps); _execute(A, O, T, phase_diff, steps);
} }
@ -202,13 +202,13 @@ void Hippie::turn(float steps, int T, int dir){
//-- Same coordination than for walking (see Hippie::walk) //-- Same coordination than for walking (see Hippie::walk)
//-- The Amplitudes of the hip's oscillators are not igual //-- The Amplitudes of the hip's oscillators are not igual
//-- When the right hip servo amplitude is higher, the steps taken by //-- When the right hip servo amplitude is higher, the steps taken by
//-- the right leg are bigger than the left. So, the robot describes an //-- the right leg are bigger than the left. So, the robot describes an
//-- left arc //-- left arc
int A[4]= {30, 30, 20, 20}; int A[4]= {30, 30, 20, 20};
int O[4] = {0, 0, 4, 30}; int O[4] = {0, 0, 4, 30};
double phase_diff[4] = {0, 0, DEG2RAD(-90), DEG2RAD(-90)}; double phase_diff[4] = {0, 0, DEG2RAD(-90), DEG2RAD(-90)};
if (dir == LEFT) { if (dir == LEFT) {
A[0] = 50; //-- Left hip servo A[0] = 50; //-- Left hip servo
A[1] = 10; //-- Right hip servo A[1] = 10; //-- Right hip servo
} }
@ -217,9 +217,9 @@ void Hippie::turn(float steps, int T, int dir){
A[1] = 50; A[1] = 50;
A[2] = 40; A[2] = 40;
} }
//-- Let's oscillate the servos! //-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps); _execute(A, O, T, phase_diff, steps);
} }
@ -233,14 +233,14 @@ void Hippie::turn(float steps, int T, int dir){
void Hippie::bend (int steps, int T, int dir){ void Hippie::bend (int steps, int T, int dir){
//Parameters of all the movements. Default: Left bend //Parameters of all the movements. Default: Left bend
int bend1[4]={90, 90, 62, 35}; int bend1[4]={90, 90, 62, 35};
int bend2[4]={90, 90, 62, 105+60}; int bend2[4]={90, 90, 62, 105+60};
int homes[4]={90, 90, 90, 90}; int homes[4]={90, 90, 90, 90};
//Time of one bend, constrained in order to avoid movements too fast. //Time of one bend, constrained in order to avoid movements too fast.
//T=max(T, 600); //T=max(T, 600);
//Changes in the parameters if right direction is chosen //Changes in the parameters if right direction is chosen
if(dir==-1) if(dir==-1)
{ {
bend1[2]=180-35; bend1[2]=180-35;
@ -250,7 +250,7 @@ void Hippie::bend (int steps, int T, int dir){
} }
//Time of the bend movement. Fixed parameter to avoid falls //Time of the bend movement. Fixed parameter to avoid falls
int T2=800; int T2=800;
//Bend movement //Bend movement
for (int i=0;i<steps;i++) for (int i=0;i<steps;i++)
@ -276,11 +276,11 @@ void Hippie::new_walk(int dir, float steps, int T){
int Pos_B[4] = {90,90,180, 180}; int Pos_B[4] = {90,90,180, 180};
int Pos_C[4] = {90,45,90, 180}; int Pos_C[4] = {90,45,90, 180};
int Pos_D[4] = {45,45,90,90}; int Pos_D[4] = {45,45,90,90};
int Pos_E[4] = {45,45,30,30}; int Pos_E[4] = {45,45,30,30};
int Pos_F[4] = {150,150,30,90}; int Pos_F[4] = {150,150,30,90};
int Pos_G[4] = {150,150,90,90}; int Pos_G[4] = {150,150,90,90};
// run movements // run movements
for (int i=0;i<steps;i++) for (int i=0;i<steps;i++)
{ {
@ -293,23 +293,23 @@ void Hippie::new_walk(int dir, float steps, int T){
_moveServos(T/2, Pos_E); _moveServos(T/2, Pos_E);
_moveServos(T/2, Pos_F); _moveServos(T/2, Pos_F);
_moveServos(T/2, Pos_G); _moveServos(T/2, Pos_G);
//delay(T*3); //delay(T*3);
} }
} }
//Backwards //Backwards
if (dir == 2){ if (dir == 2){
int Pos_1[4] = {90,90,180, 90}; int Pos_1[4] = {90,90,180, 90};
int Pos_2[4] = {90,90,180, 180}; int Pos_2[4] = {90,90,180, 180};
int Pos_3[4] = {90,145,90, 180}; int Pos_3[4] = {90,145,90, 180};
int Pos_4[4] = {145,145,90,90}; int Pos_4[4] = {145,145,90,90};
int Pos_5[4] = {145,145,30,30}; int Pos_5[4] = {145,145,30,30};
int Pos_6[4] = {45,45,30,90}; int Pos_6[4] = {45,45,30,90};
int Pos_7[4] = {45,45,90,90}; int Pos_7[4] = {45,45,90,90};
// run movements // run movements
for (int i=0;i<steps;i++) for (int i=0;i<steps;i++)
{ {
@ -322,11 +322,11 @@ void Hippie::new_walk(int dir, float steps, int T){
_moveServos(T/2, Pos_5); _moveServos(T/2, Pos_5);
_moveServos(T/2, Pos_6); _moveServos(T/2, Pos_6);
_moveServos(T/2, Pos_7); _moveServos(T/2, Pos_7);
//delay(T*3); //delay(T*3);
} }
} }
} }
//-------------------------------------------------------- //--------------------------------------------------------
@ -344,7 +344,7 @@ void Hippie::new_turn(int dir, float steps, int T){
int Pos_C[4] = {0,90,30,90}; int Pos_C[4] = {0,90,30,90};
int Pos_D[4] = {0,90,90,90}; int Pos_D[4] = {0,90,90,90};
int Pos_E[4] = {90,90,90,90}; int Pos_E[4] = {90,90,90,90};
// run movements // run movements
for (int i=0;i<steps;i++) for (int i=0;i<steps;i++)
{ {
@ -353,10 +353,10 @@ void Hippie::new_turn(int dir, float steps, int T){
//delay(T); //delay(T);
_moveServos(T/2, Pos_C); _moveServos(T/2, Pos_C);
_moveServos(T/2, Pos_D); _moveServos(T/2, Pos_D);
_moveServos(T/2, Pos_E); _moveServos(T/2, Pos_E);
} }
} }
//RIGHT //RIGHT
if (dir==2) { if (dir==2) {
// Positions of turning // Positions of turning
@ -365,7 +365,7 @@ void Hippie::new_turn(int dir, float steps, int T){
int Pos_3[4] = {90,180,90, 180}; int Pos_3[4] = {90,180,90, 180};
int Pos_4[4] = {90,180,90,90}; int Pos_4[4] = {90,180,90,90};
int Pos_5[4] = {90,90,90,90}; int Pos_5[4] = {90,90,90,90};
// run movements // run movements
for (int i=0;i<steps;i++) for (int i=0;i<steps;i++)
{ {
@ -374,7 +374,7 @@ void Hippie::new_turn(int dir, float steps, int T){
//delay(T); //delay(T);
_moveServos(T/2, Pos_3); _moveServos(T/2, Pos_3);
_moveServos(T/2, Pos_4); _moveServos(T/2, Pos_4);
_moveServos(T/2, Pos_5); _moveServos(T/2, Pos_5);
} }
} }
} }
@ -392,13 +392,13 @@ void Hippie::shakeLeg (int steps,int T,int dir){
int numberLegMoves=4; int numberLegMoves=4;
//Parameters of all the movements. Default: Right leg //Parameters of all the movements. Default: Right leg
int shake_leg1[4]={90, 90, 58, 35-15}; int shake_leg1[4]={90, 90, 58, 35-15};
int shake_leg2[4]={90, 90, 58, 120+30}; int shake_leg2[4]={90, 90, 58, 120+30};
int shake_leg3[4]={90, 90, 58, 60-30}; int shake_leg3[4]={90, 90, 58, 60-30};
int homes[4]={90, 90, 90, 90}; int homes[4]={90, 90, 90, 90};
//Changes in the parameters if left leg is chosen //Changes in the parameters if left leg is chosen
if(dir==-1) if(dir==-1)
{ {
shake_leg1[2]=180-35; shake_leg1[2]=180-35;
shake_leg1[3]=180-58; shake_leg1[3]=180-58;
@ -407,19 +407,19 @@ void Hippie::shakeLeg (int steps,int T,int dir){
shake_leg3[2]=180-60; shake_leg3[2]=180-60;
shake_leg3[3]=180-58; shake_leg3[3]=180-58;
} }
//Time of the bend movement. Fixed parameter to avoid falls //Time of the bend movement. Fixed parameter to avoid falls
int T2=1000; int T2=1000;
//Time of one shake, constrained in order to avoid movements too fast. //Time of one shake, constrained in order to avoid movements too fast.
T=T-T2; T=T-T2;
T=max(T,200*numberLegMoves); T=max(T,200*numberLegMoves);
for (int j=0; j<steps;j++) for (int j=0; j<steps;j++)
{ {
//Bend movement //Bend movement
_moveServos(T2/2,shake_leg1); _moveServos(T2/2,shake_leg1);
_moveServos(T2/2,shake_leg2); _moveServos(T2/2,shake_leg2);
//Shake movement //Shake movement
for (int i=0;i<numberLegMoves;i++) for (int i=0;i<numberLegMoves;i++)
{ {
@ -428,7 +428,7 @@ void Hippie::shakeLeg (int steps,int T,int dir){
} }
_moveServos(500,homes); //Return to home position _moveServos(500,homes); //Return to home position
} }
delay(T); delay(T);
} }
@ -438,7 +438,7 @@ void Hippie::shakeLeg (int steps,int T,int dir){
//-- Parameters: //-- Parameters:
//-- * steps: Number of jumps //-- * steps: Number of jumps
//-- * T: Period //-- * T: Period
//-- * h: Jump height: SMALL / MEDIUM / BIG //-- * h: Jump height: SMALL / MEDIUM / BIG
//-- (or a number in degrees 0 - 90) //-- (or a number in degrees 0 - 90)
//--------------------------------------------------------- //---------------------------------------------------------
void Hippie::updown(float steps, int T, int h){ void Hippie::updown(float steps, int T, int h){
@ -450,9 +450,9 @@ void Hippie::updown(float steps, int T, int h){
int A[4]= {0, 0, h, h}; int A[4]= {0, 0, h, h};
int O[4] = {0, 0, h, -h+50}; int O[4] = {0, 0, h, -h+50};
double phase_diff[4] = {0, 0, DEG2RAD(-90), DEG2RAD(90)}; double phase_diff[4] = {0, 0, DEG2RAD(-90), DEG2RAD(90)};
//-- Let's oscillate the servos! //-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps); _execute(A, O, T, phase_diff, steps);
} }
@ -470,9 +470,9 @@ void Hippie::swing(float steps, int T, int h){
int A[4]= {0, 0, h, h}; int A[4]= {0, 0, h, h};
int O[4] = {0, 0, h/2-20, -h/2+50-20}; int O[4] = {0, 0, h/2-20, -h/2+50-20};
double phase_diff[4] = {0, 0, DEG2RAD(0), DEG2RAD(0)}; double phase_diff[4] = {0, 0, DEG2RAD(0), DEG2RAD(0)};
//-- Let's oscillate the servos! //-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps); _execute(A, O, T, phase_diff, steps);
} }
@ -490,18 +490,18 @@ void Hippie::tiptoeSwing(float steps, int T, int h){
int A[4]= {0, 0, h, h}; int A[4]= {0, 0, h, h};
int O[4] = {0, 0, h-20, -h+50}; int O[4] = {0, 0, h-20, -h+50};
double phase_diff[4] = {0, 0, 0, 0}; double phase_diff[4] = {0, 0, 0, 0};
//-- Let's oscillate the servos! //-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps); _execute(A, O, T, phase_diff, steps);
} }
//--------------------------------------------------------- //---------------------------------------------------------
//-- Hippie gait: Jitter //-- Hippie gait: Jitter
//-- Parameters: //-- Parameters:
//-- steps: Number of jitters //-- steps: Number of jitters
//-- T: Period of one jitter //-- T: Period of one jitter
//-- h: height (Values between 5 - 25) //-- h: height (Values between 5 - 25)
//--------------------------------------------------------- //---------------------------------------------------------
void Hippie::jitter(float steps, int T, int h){ void Hippie::jitter(float steps, int T, int h){
@ -514,9 +514,9 @@ void Hippie::jitter(float steps, int T, int h){
int A[4]= {h, h, 0, 0}; int A[4]= {h, h, 0, 0};
int O[4] = {0, 0, 0, 0}; int O[4] = {0, 0, 0, 0};
double phase_diff[4] = {DEG2RAD(-90), DEG2RAD(90), 0, 0}; double phase_diff[4] = {DEG2RAD(-90), DEG2RAD(90), 0, 0};
//-- Let's oscillate the servos! //-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps); _execute(A, O, T, phase_diff, steps);
} }
@ -525,7 +525,7 @@ void Hippie::jitter(float steps, int T, int h){
//-- Parameters: //-- Parameters:
//-- steps: Number of bends //-- steps: Number of bends
//-- T: Period of one bend //-- T: Period of one bend
//-- h: height (Values between 5 - 15) //-- h: height (Values between 5 - 15)
//--------------------------------------------------------- //---------------------------------------------------------
void Hippie::ascendingTurn(float steps, int T, int h){ void Hippie::ascendingTurn(float steps, int T, int h){
@ -537,9 +537,9 @@ void Hippie::ascendingTurn(float steps, int T, int h){
int A[4]= {h, h, h, h}; int A[4]= {h, h, h, h};
int O[4] = {0, 0, h+4, -h+40}; int O[4] = {0, 0, h+4, -h+40};
double phase_diff[4] = {DEG2RAD(-90), DEG2RAD(90), DEG2RAD(-90), DEG2RAD(90)}; double phase_diff[4] = {DEG2RAD(-90), DEG2RAD(90), DEG2RAD(-90), DEG2RAD(90)};
//-- Let's oscillate the servos! //-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps); _execute(A, O, T, phase_diff, steps);
} }
@ -562,14 +562,14 @@ void Hippie::moonwalker(float steps, int T, int h, int dir){
//-- is 60 degrees. //-- is 60 degrees.
//-- Both amplitudes are equal. The offset is half the amplitud plus a little bit of //-- Both amplitudes are equal. The offset is half the amplitud plus a little bit of
//- offset so that the robot tiptoe lightly //- offset so that the robot tiptoe lightly
int A[4]= {0, 0, h, h}; int A[4]= {0, 0, h, h};
int O[4] = {0, 0, h/2+2, -h/2 -2+60}; int O[4] = {0, 0, h/2+2, -h/2 -2+60};
int phi = -dir * 90; int phi = -dir * 90;
double phase_diff[4] = {0, 0, DEG2RAD(phi), DEG2RAD(-60 * dir + phi)}; double phase_diff[4] = {0, 0, DEG2RAD(phi), DEG2RAD(-60 * dir + phi)};
//-- Let's oscillate the servos! //-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps); _execute(A, O, T, phase_diff, steps);
} }
@ -586,9 +586,9 @@ void Hippie::crusaito(float steps, int T, int h, int dir){
int A[4]= {25, 25, h, h}; int A[4]= {25, 25, h, h};
int O[4] = {0, 0, h/2+ 4, -h/2 - 4+30}; int O[4] = {0, 0, h/2+ 4, -h/2 - 4+30};
double phase_diff[4] = {90, 90, DEG2RAD(0), DEG2RAD(-60 * dir)}; double phase_diff[4] = {90, 90, DEG2RAD(0), DEG2RAD(-60 * dir)};
//-- Let's oscillate the servos! //-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps); _execute(A, O, T, phase_diff, steps);
} }
@ -605,8 +605,7 @@ void Hippie::flapping(float steps, int T, int h, int dir){
int A[4]= {12+10, 12+10, h, h}; int A[4]= {12+10, 12+10, h, h};
int O[4] = {0, 0, h - 10, -h + 10+60}; int O[4] = {0, 0, h - 10, -h + 10+60};
double phase_diff[4] = {DEG2RAD(0), DEG2RAD(180), DEG2RAD(-90 * dir), DEG2RAD(90 * dir)}; double phase_diff[4] = {DEG2RAD(0), DEG2RAD(180), DEG2RAD(-90 * dir), DEG2RAD(90 * dir)};
//-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps);
}
//-- Let's oscillate the servos!
_execute(A, O, T, phase_diff, steps);
}

View File

@ -1,14 +1,8 @@
#ifndef Hippie_h #ifndef Hippie_h
#define Hippie_h #define Hippie_h
#include <ESP32_Servo.h>
#include <Oscillator.h> #include <Oscillator.h>
#include "Hippie_mouths.h"
#include "Hippie_sounds.h"
#include "Hippie_gestures.h"
//-- Constants //-- Constants
#define FORWARD 1 #define FORWARD 1
#define BACKWARD -1 #define BACKWARD -1
@ -18,11 +12,6 @@
#define MEDIUM 15 #define MEDIUM 15
#define BIG 30 #define BIG 30
#define PIN_Buzzer 10
#define PIN_Trigger 8
#define PIN_Echo 9
#define PIN_NoiseSensor A6
class Hippie class Hippie
{ {
@ -43,7 +32,7 @@ class Hippie
void home(); void home();
bool getRestState(); bool getRestState();
void setRestState(bool state); void setRestState(bool state);
//-- Predetermined Motion Functions //-- Predetermined Motion Functions
void jump(float steps=1, int T = 600); void jump(float steps=1, int T = 600);
@ -61,15 +50,15 @@ class Hippie
void moonwalker(float steps=1, int T=900, int h=50, int dir=LEFT); void moonwalker(float steps=1, int T=900, int h=50, int dir=LEFT);
void crusaito(float steps=1, int T=900, int h=20, int dir=FORWARD); void crusaito(float steps=1, int T=900, int h=20, int dir=FORWARD);
void flapping(float steps=1, int T=1000, int h=50, int dir=FORWARD); void flapping(float steps=1, int T=1000, int h=50, int dir=FORWARD);
void test_pos(); void test_pos();
void new_walk(int dir = FORWARD, float steps =4, int T=750); void new_walk(int dir = FORWARD, float steps =4, int T=750);
void new_turn(int dir = LEFT, float steps =2, int T=1000); void new_turn(int dir = LEFT, float steps =2, int T=1000);
private: private:
Oscillator servo[4]; Oscillator servo[4];
int servo_pins[4]; int servo_pins[4];
@ -77,7 +66,7 @@ class Hippie
int servo_position[4]; int servo_position[4];
int pinBuzzer; int pinBuzzer;
unsigned long final_time; unsigned long final_time;
unsigned long partial_time; unsigned long partial_time;
float increment[4]; float increment[4];
@ -89,5 +78,3 @@ class Hippie
}; };
#endif #endif

View File

@ -5,31 +5,31 @@
//-- (c) Juan Gonzalez-Gomez (Obijuan), Dec 2011 //-- (c) Juan Gonzalez-Gomez (Obijuan), Dec 2011
//-- GPL license //-- GPL license
//-------------------------------------------------------------- //--------------------------------------------------------------
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h" #include "Arduino.h"
#else
#include "WProgram.h"
#include <pins_arduino.h>
#endif
#include "Oscillator.h" #include "Oscillator.h"
#include <ESP32_Servo.h> #if defined(ESP32)
#include <ESP32_Servo.h>
#else
#include <Servo.h>
#endif
//-- This function returns true if another sample //-- This function returns true if another sample
//-- should be taken (i.e. the TS time has passed since //-- should be taken (i.e. the TS time has passed since
//-- the last sample was taken //-- the last sample was taken
bool Oscillator::next_sample() bool Oscillator::next_sample()
{ {
//-- Read current time //-- Read current time
_currentMillis = millis(); _currentMillis = millis();
//-- Check if the timeout has passed //-- Check if the timeout has passed
if(_currentMillis - _previousMillis > _TS) { if(_currentMillis - _previousMillis > _TS) {
_previousMillis = _currentMillis; _previousMillis = _currentMillis;
return true; return true;
} }
return false; return false;
} }
@ -39,9 +39,6 @@ bool Oscillator::next_sample()
void Oscillator::attach(int pin, bool rev) void Oscillator::attach(int pin, bool rev)
{ {
//-- If the oscillator is detached, attach it. //-- If the oscillator is detached, attach it.
//Serial.println("PANIIIIIIIIIIIIIIIIIC");
// Serial.println(!_servo.attached());
//if(!_servo.attached()){
//-- Attach the servo and move it to the home position //-- Attach the servo and move it to the home position
_servo.attach(pin); _servo.attach(pin);
@ -64,8 +61,7 @@ void Oscillator::attach(int pin, bool rev)
//-- Reverse mode //-- Reverse mode
_rev = rev; _rev = rev;
//}
} }
//-- Detach an oscillator from his servo //-- Detach an oscillator from his servo
@ -84,7 +80,7 @@ void Oscillator::SetT(unsigned int T)
{ {
//-- Assign the new period //-- Assign the new period
_T=T; _T=T;
//-- Recalculate the parameters //-- Recalculate the parameters
__N = _T/_TS; __N = _T/_TS;
_inc = 2*M_PI/__N; _inc = 2*M_PI/__N;
@ -107,10 +103,10 @@ void Oscillator::SetPosition(int position)
/*******************************************************************/ /*******************************************************************/
void Oscillator::refresh() void Oscillator::refresh()
{ {
//-- Only When TS milliseconds have passed, the new sample is obtained //-- Only When TS milliseconds have passed, the new sample is obtained
if (next_sample()) { if (next_sample()) {
//-- If the oscillator is not stopped, calculate the servo position //-- If the oscillator is not stopped, calculate the servo position
if (!_stop) { if (!_stop) {
//-- Sample the sine function and set the servo pos //-- Sample the sine function and set the servo pos

View File

@ -8,7 +8,11 @@
#ifndef Oscillator_h #ifndef Oscillator_h
#define Oscillator_h #define Oscillator_h
#include <ESP32_Servo.h> #if defined(ESP32)
#include <ESP32_Servo.h>
#else
#include <Servo.h>
#endif
//-- Macro for converting from degrees to radians //-- Macro for converting from degrees to radians
#ifndef DEG2RAD #ifndef DEG2RAD
@ -21,32 +25,32 @@ class Oscillator
Oscillator(int trim=0) {_trim=trim;}; Oscillator(int trim=0) {_trim=trim;};
void attach(int pin, bool rev =false); void attach(int pin, bool rev =false);
void detach(); void detach();
void SetA(unsigned int A) {_A=A;}; void SetA(unsigned int A) {_A=A;};
void SetO(unsigned int O) {_O=O;}; void SetO(unsigned int O) {_O=O;};
void SetPh(double Ph) {_phase0=Ph;}; void SetPh(double Ph) {_phase0=Ph;};
void SetT(unsigned int T); void SetT(unsigned int T);
void SetTrim(int trim){_trim=trim;}; void SetTrim(int trim){_trim=trim;};
int getTrim() {return _trim;}; int getTrim() {return _trim;};
void SetPosition(int position); void SetPosition(int position);
void Stop() {_stop=true;}; void Stop() {_stop=true;};
void Play() {_stop=false;}; void Play() {_stop=false;};
void Reset() {_phase=0;}; void Reset() {_phase=0;};
void refresh(); void refresh();
private: private:
bool next_sample(); bool next_sample();
private: private:
//-- Servo that is attached to the oscillator //-- Servo that is attached to the oscillator
Servo _servo; Servo _servo;
//-- Oscillators parameters //-- Oscillators parameters
unsigned int _A; //-- Amplitude (degrees) unsigned int _A; //-- Amplitude (degrees)
unsigned int _O; //-- Offset (degrees) unsigned int _O; //-- Offset (degrees)
unsigned int _T; //-- Period (miliseconds) unsigned int _T; //-- Period (miliseconds)
double _phase0; //-- Phase (radians) double _phase0; //-- Phase (radians)
//-- Internal variables //-- Internal variables
int _pos; //-- Current servo pos int _pos; //-- Current servo pos
int _trim; //-- Calibration offset int _trim; //-- Calibration offset
@ -54,10 +58,10 @@ class Oscillator
double _inc; //-- Increment of phase double _inc; //-- Increment of phase
double __N; //-- Number of samples double __N; //-- Number of samples
unsigned int _TS; //-- sampling period (ms) unsigned int _TS; //-- sampling period (ms)
long _previousMillis; long _previousMillis;
long _currentMillis; long _currentMillis;
//-- Oscillation mode. If true, the servo is stopped //-- Oscillation mode. If true, the servo is stopped
bool _stop; bool _stop;
@ -65,4 +69,4 @@ class Oscillator
bool _rev; bool _rev;
}; };
#endif #endif