mirror of
https://github.com/digistump/DigistumpArduino.git
synced 2025-09-17 17:32:25 -07:00
added updated tinypinchange and associated libraries to support PRO
This commit is contained in:
@@ -0,0 +1,208 @@
|
||||
#include "SoftRcPulseOut.h"
|
||||
/*
|
||||
Update 01/03/2013: add support for DigiSpark (http://digistump.com): automatic Timer selection (RC Navy: p.loussouarn.free.fr)
|
||||
|
||||
English: by RC Navy (2012)
|
||||
=======
|
||||
<SoftRcPulseOut>: a library mainly based on the <SoftwareServo> library, but with a better pulse generation to limit jitter.
|
||||
It supports the same methods as <SoftwareServo>.
|
||||
It also support Pulse Width order given in microseconds. The current Pulse Width can also be read in microseconds.
|
||||
The refresh method can admit an optionnal argument (force). If SoftRcPulseOut::refresh(1) is called, the refresh is forced even if 20 ms are not elapsed.
|
||||
http://p.loussouarn.free.fr
|
||||
|
||||
Francais: par RC Navy (2012)
|
||||
========
|
||||
<SoftRcPulseOut>: une librairie majoritairement basee sur la librairie <SoftwareServo>, mais avec une meilleure generation des impulsions pour limiter la gigue.
|
||||
Elle supporte les memes methodes que <SoftwareServo>.
|
||||
Elle supporte egalement une consigne de largeur d'impulsion passee en microseconde. La largeur de l'impulsion courante peut egalement etre lue en microseconde.
|
||||
La methode refresh peut admettre un parametre optionnel (force). Si SoftRcPulseOut::resfresh(1) est appelee, le refresh est force meme si 20 ms ne se sont pas ecoulee.
|
||||
http://p.loussouarn.free.fr
|
||||
*/
|
||||
|
||||
/* Automatic Timer selection (at compilation time) */
|
||||
#ifndef TIMER_TO_USE_FOR_MILLIS //This symbol is not defined arduino standard core and is defined in core_build_options.h in DigiStump version
|
||||
#define SOFT_RC_PULSE_OUT_TCNT TCNT0 //For arduino standard core of UNO/MEGA, etc
|
||||
#else
|
||||
#if (TIMER_TO_USE_FOR_MILLIS==1)
|
||||
#define SOFT_RC_PULSE_OUT_TCNT TCNT1 //For example for ATtiny85
|
||||
#else
|
||||
#define SOFT_RC_PULSE_OUT_TCNT TCNT0 //For example for ATtiny84
|
||||
#endif
|
||||
#endif
|
||||
|
||||
SoftRcPulseOut *SoftRcPulseOut::first;
|
||||
|
||||
#define NO_ANGLE (0xff)
|
||||
|
||||
SoftRcPulseOut::SoftRcPulseOut() : pin(0),angle(NO_ANGLE),pulse0(0),min16(34),max16(150),next(0)
|
||||
{}
|
||||
|
||||
void SoftRcPulseOut::setMinimumPulse(uint16_t t)
|
||||
{
|
||||
min16 = t/16;
|
||||
}
|
||||
|
||||
void SoftRcPulseOut::setMaximumPulse(uint16_t t)
|
||||
{
|
||||
max16 = t/16;
|
||||
}
|
||||
|
||||
uint8_t SoftRcPulseOut::attach(int pinArg)
|
||||
{
|
||||
pin = pinArg;
|
||||
angle = NO_ANGLE;
|
||||
pulse0 = 0;
|
||||
next = first;
|
||||
first = this;
|
||||
digitalWrite(pin,0);
|
||||
pinMode(pin,OUTPUT);
|
||||
return 1;
|
||||
}
|
||||
|
||||
void SoftRcPulseOut::detach()
|
||||
{
|
||||
for ( SoftRcPulseOut **p = &first; *p != 0; p = &((*p)->next) ) {
|
||||
if ( *p == this) {
|
||||
*p = this->next;
|
||||
this->next = 0;
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void SoftRcPulseOut::write(int angleArg)
|
||||
{
|
||||
if ( angleArg < 0) angleArg = 0;
|
||||
if ( angleArg > 180) angleArg = 180;
|
||||
angle = angleArg;
|
||||
// bleh, have to use longs to prevent overflow, could be tricky if always a 16MHz clock, but not true
|
||||
// That 64L on the end is the TCNT0 prescaler, it will need to change if the clock's prescaler changes,
|
||||
// but then there will likely be an overflow problem, so it will have to be handled by a human.
|
||||
#ifdef TIMER0_TICK_EVERY_X_CYCLES
|
||||
pulse0 = (min16*16L*clockCyclesPerMicrosecond() + (max16-min16)*(16L*clockCyclesPerMicrosecond())*angle/180L)/TIMER0_TICK_EVERY_X_CYCLES;
|
||||
#else
|
||||
pulse0 = (min16*16L*clockCyclesPerMicrosecond() + (max16-min16)*(16L*clockCyclesPerMicrosecond())*angle/180L)/64L;
|
||||
#endif
|
||||
}
|
||||
|
||||
void SoftRcPulseOut::write_us(int PulseWidth_us)
|
||||
{
|
||||
SoftRcPulseOut::write(map(PulseWidth_us,min16*16,max16*16,0,180));
|
||||
}
|
||||
|
||||
uint8_t SoftRcPulseOut::read()
|
||||
{
|
||||
return angle;
|
||||
}
|
||||
|
||||
uint8_t SoftRcPulseOut::read_us()
|
||||
{
|
||||
return map(angle,0,180,min16*16,max16*16);
|
||||
}
|
||||
|
||||
uint8_t SoftRcPulseOut::attached()
|
||||
{
|
||||
for ( SoftRcPulseOut *p = first; p != 0; p = p->next ) {
|
||||
if ( p == this) return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t SoftRcPulseOut::refresh(bool force /* = false */)
|
||||
{
|
||||
uint8_t RefreshDone=0;
|
||||
uint8_t count = 0, i = 0;
|
||||
uint16_t base = 0;
|
||||
SoftRcPulseOut *p;
|
||||
static unsigned long lastRefresh = 0;
|
||||
unsigned long m = millis();
|
||||
if(!force)
|
||||
{
|
||||
// if we haven't wrapped millis, and 20ms have not passed, then don't do anything
|
||||
if ( m >= lastRefresh && m < lastRefresh + 20) return(RefreshDone);
|
||||
}
|
||||
RefreshDone=1; //Ok: Refresh will be performed
|
||||
lastRefresh = m;
|
||||
|
||||
for ( p = first; p != 0; p = p->next ) if ( p->pulse0) count++;
|
||||
if ( count == 0) return(RefreshDone);
|
||||
|
||||
// gather all the SoftRcPulseOuts in an array
|
||||
SoftRcPulseOut *s[count];
|
||||
for ( p = first; p != 0; p = p->next ) if ( p->pulse0) s[i++] = p;
|
||||
|
||||
// bubblesort the SoftRcPulseOuts by pulse time, ascending order
|
||||
s[0]->ItMasked=0;
|
||||
for(;;)
|
||||
{
|
||||
uint8_t moved = 0;
|
||||
for ( i = 1; i < count; i++)
|
||||
{
|
||||
s[i]->ItMasked=0;
|
||||
if ( s[i]->pulse0 < s[i-1]->pulse0)
|
||||
{
|
||||
SoftRcPulseOut *t = s[i];
|
||||
s[i] = s[i-1];
|
||||
s[i-1] = t;
|
||||
moved = 1;
|
||||
}
|
||||
}
|
||||
if ( !moved) break;
|
||||
}
|
||||
for ( i = 1; i < count; i++)
|
||||
{
|
||||
if ( abs(s[i]->pulse0 - s[i-1]->pulse0)<=5)
|
||||
{
|
||||
s[i]->ItMasked=1; /* 2 consecutive Pulses are close each other, so do not unmask interrupts between Pulses */
|
||||
}
|
||||
}
|
||||
// turn on all the pins
|
||||
// Note the timing error here... when you have many SoftwareServos going, the
|
||||
// ones at the front will get a pulse that is a few microseconds too long.
|
||||
// Figure about 4uS/SoftRcPulseOut after them. This could be compensated, but I feel
|
||||
// it is within the margin of error of software SoftRcPulseOuts that could catch
|
||||
// an extra interrupt handler at any time.
|
||||
noInterrupts();
|
||||
for ( i = 0; i < count; i++) digitalWrite( s[i]->pin, 1);
|
||||
interrupts();
|
||||
|
||||
uint8_t start = SOFT_RC_PULSE_OUT_TCNT;
|
||||
uint8_t now = start;
|
||||
uint8_t last = now;
|
||||
|
||||
// Now wait for each pin's time in turn..
|
||||
for ( i = 0; i < count; i++)
|
||||
{
|
||||
uint16_t go = start + s[i]->pulse0;
|
||||
uint16_t it = go - 4; /* 4 Ticks is OK for UNO @ 16MHz */ /* Mask Interruptions just before setting down the pin */
|
||||
|
||||
// loop until we reach or pass 'go' time
|
||||
for (;;)
|
||||
{
|
||||
now = SOFT_RC_PULSE_OUT_TCNT;
|
||||
if ( now < last) base += 256;
|
||||
last = now;
|
||||
if(!s[i]->ItMasked)
|
||||
{
|
||||
if( base + now > it)
|
||||
{
|
||||
noInterrupts();
|
||||
s[i]->ItMasked=1;
|
||||
}
|
||||
}
|
||||
if ( base + now > go)
|
||||
{
|
||||
digitalWrite( s[i]->pin,0);
|
||||
if((i+1)<count)
|
||||
{
|
||||
if(!s[i+1]->ItMasked)
|
||||
{
|
||||
interrupts();
|
||||
}
|
||||
}else interrupts();
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
return(RefreshDone);
|
||||
}
|
@@ -0,0 +1,59 @@
|
||||
#ifndef SoftRcPulseOut_h
|
||||
#define SoftRcPulseOut_h
|
||||
|
||||
/*
|
||||
Update 01/03/2013: add support for DigiSpark (http://digistump.com): automatic Timer selection (RC Navy: p.loussouarn.free.fr)
|
||||
|
||||
English: by RC Navy (2012)
|
||||
=======
|
||||
<SoftRcPulseOut>: a library mainly based on the <SoftwareServo> library, but with a better pulse generation to limit jitter.
|
||||
It supports the same methods as <SoftwareServo>.
|
||||
It also support Pulse Width order given in microseconds. The current Pulse Width can also be read in microseconds.
|
||||
The refresh method can admit an optionnal argument (force). If SoftRcPulseOut::refresh(1) is called, the refresh is forced even if 20 ms are not elapsed.
|
||||
http://p.loussouarn.free.fr
|
||||
|
||||
Francais: par RC Navy (2012)
|
||||
========
|
||||
<SoftRcPulseOut>: une librairie majoritairement basee sur la librairie <SoftwareServo>, mais avec une meilleure generation des impulsions pour limiter la gigue.
|
||||
Elle supporte les memes methodes que <SoftwareServo>.
|
||||
Elle supporte egalement une consigne de largeur d'impulsion passee en microseconde. La largeur de l'impulsion courante peut egalement etre lue en microseconde.
|
||||
La methode refresh peut admettre un parametre optionnel (force). Si SoftRcPulseOut::resfresh(1) est appelee, le refresh est force meme si 20 ms ne se sont pas ecoulee.
|
||||
http://p.loussouarn.free.fr
|
||||
*/
|
||||
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
#else
|
||||
#include "WProgram.h"
|
||||
#endif
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
class SoftRcPulseOut
|
||||
{
|
||||
private:
|
||||
boolean ItMasked;
|
||||
uint8_t pin;
|
||||
uint8_t angle; // in degrees
|
||||
uint16_t pulse0; // pulse width in TCNT0 counts
|
||||
uint8_t min16; // minimum pulse, 16uS units (default is 34)
|
||||
uint8_t max16; // maximum pulse, 16uS units, 0-4ms range (default is 150)
|
||||
class SoftRcPulseOut *next;
|
||||
static SoftRcPulseOut* first;
|
||||
public:
|
||||
SoftRcPulseOut();
|
||||
uint8_t attach(int); // attach to a pin, sets pinMode, returns 0 on failure, won't
|
||||
// position the servo until a subsequent write() happens
|
||||
void detach();
|
||||
void write(int); // specify the angle in degrees, 0 to 180
|
||||
void write_us(int); // specify the angle in microseconds, 500 to 2500
|
||||
uint8_t read(); // return the current angle
|
||||
uint8_t read_us(); // return the current pulse with in microseconds
|
||||
uint8_t attached();
|
||||
void setMinimumPulse(uint16_t); // pulse length for 0 degrees in microseconds, 540uS default
|
||||
void setMaximumPulse(uint16_t); // pulse length for 180 degrees in microseconds, 2400uS default
|
||||
static uint8_t refresh(bool force = false); // must be called at least every 50ms or so to keep servo alive
|
||||
// you can call more often, it won't happen more than once every 20ms
|
||||
};
|
||||
|
||||
#endif
|
@@ -0,0 +1,37 @@
|
||||
// Controlling a servo position using a potentiometer (variable resistor)
|
||||
// by Michal Rinott <http://people.interaction-ivrea.it/m.rinott>
|
||||
// Adapted to SoftRcPulseOut library by RC Navy (http://p.loussouarn.free.fr)
|
||||
// This sketch can work with ATtiny and Arduino UNO, MEGA, etc...
|
||||
|
||||
#include <SoftRcPulseOut.h>
|
||||
|
||||
SoftRcPulseOut myservo; // create servo object to control a servo
|
||||
|
||||
#if defined(__AVR_ATtiny24__) || defined(__AVR_ATtiny44__) || defined(__AVR_ATtiny84__) || defined(__AVR_ATtiny25__) || defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__)
|
||||
//Here is the POT_PIN definition for ATtiny, they do NOT need a 'A' prefix for Analogic definition
|
||||
#define POT_PIN 2 // --analog pin-- (not digital) used to connect the potentiometer
|
||||
#else
|
||||
//Here is the POT_PIN definition for Arduino UNO, MEGA, they do need a 'A' prefix for Analogic definition
|
||||
#define POT_PIN A2 // --analog pin-- (not digital) used to connect the potentiometer
|
||||
#endif
|
||||
|
||||
#define SERVO_PIN 3 // --digital pin-- (not analog) used to connect the servo
|
||||
|
||||
#define REFRESH_PERIOD_MS 20
|
||||
|
||||
int val; // variable to read the value from the analog pin
|
||||
|
||||
void setup()
|
||||
{
|
||||
myservo.attach(SERVO_PIN); // attaches the servo on pin defined by SERVO_PIN to the servo object
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
val = analogRead(POT_PIN); // reads the value of the potentiometer (value between 0 and 1023)
|
||||
val = map(val, 0, 1023, 0, 179); // scale it to use it with the servo (value between 0 and 180)
|
||||
myservo.write(val); // sets the servo position according to the scaled value
|
||||
delay(REFRESH_PERIOD_MS); // waits for the servo to get there
|
||||
SoftRcPulseOut::refresh(); // generates the servo pulse
|
||||
}
|
||||
|
@@ -0,0 +1,60 @@
|
||||
// This SoftwareServo library example sketch was initially delivered without any comments.
|
||||
// Below my own comments for SoftRcPulseOut library: by RC Navy (http://p.loussouarn.free.fr)
|
||||
// Controlling the position of 2 servos using the Arduino built-in hardware UART (Arduino Serial object).
|
||||
// This sketch do NOT work with an ATtinyX4 and ATtinyX5 since they do not have a built-in harware UART (no Arduino Serial object).
|
||||
|
||||
// The command (issued in the Arduino Serial Console or in a Terminal) is:
|
||||
// S=P with:
|
||||
// S=A for Servo1 and S=B for Servo2
|
||||
// P=Position number x 20° (Possible positions are from 0 to 9 which correspond to from 0° to 180°)
|
||||
// Ex:
|
||||
// A=7 sets Servo1 at 7 x 20 =140°
|
||||
// B=3 sets Servo2 at 3 x 20 =60°
|
||||
|
||||
#include <SoftRcPulseOut.h>
|
||||
|
||||
SoftRcPulseOut servo1;
|
||||
SoftRcPulseOut servo2;
|
||||
|
||||
void setup()
|
||||
{
|
||||
pinMode(13,OUTPUT);
|
||||
servo1.attach(2);
|
||||
servo1.setMaximumPulse(2200);
|
||||
servo2.attach(4);
|
||||
servo2.setMaximumPulse(2200);
|
||||
Serial.begin(9600);
|
||||
Serial.print("Ready");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
static int value = 0;
|
||||
static char CurrentServo = 0;
|
||||
|
||||
if ( Serial.available()) {
|
||||
char ch = Serial.read();
|
||||
switch(ch) {
|
||||
case 'A':
|
||||
CurrentServo='A';
|
||||
digitalWrite(13,LOW);
|
||||
break;
|
||||
case 'B':
|
||||
CurrentServo='B';
|
||||
digitalWrite(13,HIGH);
|
||||
break;
|
||||
case '0' ... '9':
|
||||
value=(ch-'0')*20;
|
||||
if (CurrentServo=='A')
|
||||
{
|
||||
servo1.write(value);
|
||||
}
|
||||
else if (CurrentServo=='B')
|
||||
{
|
||||
servo2.write(value);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
SoftRcPulseOut::refresh();
|
||||
}
|
@@ -0,0 +1,100 @@
|
||||
/*
|
||||
This sketch demonstrates how to use <SoftRcPulseIn> library to get RC pulses from a receiver and to use <SoftRcPulseOut> library to drive 2 servos.
|
||||
The first servo will follow the order, and the second one will have a reverted motion.
|
||||
Please notice this sketch is fully asynchronous: no blocking functions such as delay() or pulseIn() are used.
|
||||
Tested on arduino UNO, ATtiny84, ATtiny85 and Digispark rev2 (Model A).
|
||||
RC Navy 2013
|
||||
http://p.loussouarn.free.fr
|
||||
*/
|
||||
|
||||
#include <SoftRcPulseIn.h>
|
||||
#include <SoftRcPulseOut.h>
|
||||
#include <TinyPinChange.h> /* Needed for <SoftRcPulseIn> library */
|
||||
|
||||
#define RX_CHANNEL_PIN 2
|
||||
|
||||
#define SERVO1_PIN 3
|
||||
#define SERVO2_PIN 4
|
||||
|
||||
#define LED_PIN 1//1 on Digispark rev2 (Model A), change to pin 0 for Digispark rev1 (Model B), change to 13 for UNO
|
||||
|
||||
#define LED_HALF_PERIOD_MS 250
|
||||
|
||||
#define PULSE_MAX_PERIOD_MS 30 /* To refresh the servo in case of pulse extinction */
|
||||
|
||||
#define NOW 1
|
||||
|
||||
#define NEUTRAL_US 1500 /* Default position in case of no pulse at startup */
|
||||
|
||||
enum {NORMAL=0, INVERTED, SERVO_NB}; /* Trick: use an enumeration to declare the index of the servos AND the amount of servos */
|
||||
|
||||
|
||||
SoftRcPulseIn RxChannelPulse; /* RxChannelPulse is an objet of SoftRcPulseIn type */
|
||||
SoftRcPulseOut ServoMotor[SERVO_NB]; /* Table Creation for 2 objets of SoftRcPulseOut type */
|
||||
|
||||
/* Possible values to compute a shifting average fin order to smooth the recieved pulse witdh */
|
||||
#define AVG_WITH_1_VALUE 0
|
||||
#define AVG_WITH_2_VALUES 1
|
||||
#define AVG_WITH_4_VALUES 2
|
||||
#define AVG_WITH_8_VALUES 3
|
||||
#define AVG_WITH_16_VALUES 4
|
||||
|
||||
#define AVERAGE_LEVEL AVG_WITH_4_VALUES /* Choose here the average level among the above listed values */
|
||||
/* Higher is the average level, more the system is stable (jitter suppression), but lesser is the reaction */
|
||||
|
||||
/* Macro for average */
|
||||
#define AVERAGE(ValueToAverage,LastReceivedValue,AverageLevelInPowerOf2) ValueToAverage=(((ValueToAverage)*((1<<(AverageLevelInPowerOf2))-1)+(LastReceivedValue))/(1<<(AverageLevelInPowerOf2)))
|
||||
|
||||
/* Variables */
|
||||
uint32_t LedStartMs=millis();
|
||||
uint32_t RxPulseStartMs=millis();
|
||||
boolean LedState=HIGH;
|
||||
|
||||
void setup()
|
||||
{
|
||||
#if !defined(__AVR_ATtiny24__) && !defined(__AVR_ATtiny44__) && !defined(__AVR_ATtiny84__) && !defined(__AVR_ATtiny25__) && !defined(__AVR_ATtiny45__) && !defined(__AVR_ATtiny85__)
|
||||
Serial.begin(9600);
|
||||
Serial.print("SoftRcPulseIn library V");Serial.print(SoftRcPulseIn::LibTextVersionRevision());Serial.print(" demo"); /* For arduino UNO which has an hardware UART, display the library version in the console */
|
||||
#endif
|
||||
RxChannelPulse.attach(RX_CHANNEL_PIN);
|
||||
ServoMotor[NORMAL].attach(SERVO1_PIN); /* enumeration is used a index for the ServoMotor[] table */
|
||||
ServoMotor[INVERTED].attach(SERVO2_PIN); /* enumeration is used a index for the ServoMotor[]table */
|
||||
pinMode(LED_PIN, OUTPUT);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
static uint16_t Width_us=NEUTRAL_US; /* Static to keep the value at the next loop */
|
||||
|
||||
/* Receiver pulse acquisition and command of 2 servos, one in the direct direction, one in the inverted direction */
|
||||
if(RxChannelPulse.available())
|
||||
{
|
||||
AVERAGE(Width_us,RxChannelPulse.width_us(),AVERAGE_LEVEL);
|
||||
ServoMotor[NORMAL].write_us(Width_us); /* Direct Signal */
|
||||
ServoMotor[INVERTED].write_us((NEUTRAL_US*2)-Width_us); /* Inverted Signal */
|
||||
SoftRcPulseOut::refresh(NOW); /* NOW argument (=1) allows to synchronize outgoing pulses with incoming pulses */
|
||||
RxPulseStartMs=millis(); /* Restart the Chrono for Pulse */
|
||||
#if !defined(__AVR_ATtiny24__) && !defined(__AVR_ATtiny44__) && !defined(__AVR_ATtiny84__) && !defined(__AVR_ATtiny25__) && !defined(__AVR_ATtiny45__) && !defined(__AVR_ATtiny85__)
|
||||
Serial.print("Pulse=");Serial.println(Largeur_us); /* For arduino UNO which has an hardware UART, display the library version in the console */
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Check for pulse extinction */
|
||||
if(millis()-RxPulseStartMs>=PULSE_MAX_PERIOD_MS)
|
||||
{
|
||||
/* Refresh the servos with the last known position in order to avoid "flabby" servos */
|
||||
SoftRcPulseOut::refresh(NOW); /* Immediate refresh of outgoing pulses */
|
||||
RxPulseStartMs=millis(); /* Restart the Chrono for Pulse */
|
||||
}
|
||||
}
|
||||
|
||||
/* Blink LED Management */
|
||||
if(millis()-LedStartMs>=LED_HALF_PERIOD_MS)
|
||||
{
|
||||
digitalWrite(LED_PIN, LedState);
|
||||
LedState=!LedState; /* At the next loop, if the half period is elapsed, the LED state will be inverted */
|
||||
LedStartMs=millis(); /* Restart the Chrono for the LED */
|
||||
}
|
||||
|
||||
}
|
@@ -0,0 +1,37 @@
|
||||
// Sweep
|
||||
// by BARRAGAN <http://barraganstudio.com>
|
||||
// Adapted to SoftRcPulseOut library by RC Navy (http://p.loussouarn.free.fr)
|
||||
// This sketch can work with ATtiny and Arduino UNO, MEGA, etc...
|
||||
// This example code is in the public domain.
|
||||
|
||||
#include <SoftRcPulseOut.h>
|
||||
|
||||
SoftRcPulseOut myservo; // create servo object to control a servo
|
||||
// a maximum of eight servo objects can be created
|
||||
#define SERVO_PIN 3
|
||||
|
||||
#define REFRESH_PERIOD_MS 20
|
||||
|
||||
int pos = 0; // variable to store the servo position
|
||||
|
||||
void setup()
|
||||
{
|
||||
myservo.attach(SERVO_PIN); // attaches the servo on pin defined by SERVO_PIN to the servo object
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
for(pos = 0; pos < 180; pos += 1) // goes from 0 degrees to 180 degrees
|
||||
{ // in steps of 1 degree
|
||||
myservo.write(pos); // tell servo to go to position in variable 'pos'
|
||||
delay(REFRESH_PERIOD_MS); // waits 20ms for refresh period
|
||||
SoftRcPulseOut::refresh(1); // generates the servo pulse
|
||||
}
|
||||
for(pos = 180; pos>=1; pos-=1) // goes from 180 degrees to 0 degrees
|
||||
{
|
||||
myservo.write(pos); // tell servo to go to position in variable 'pos'
|
||||
delay(REFRESH_PERIOD_MS); // waits 20ms for for refresh period
|
||||
SoftRcPulseOut::refresh(1); // generates the servo pulse
|
||||
}
|
||||
}
|
@@ -0,0 +1,73 @@
|
||||
// This sketch demonstrates how to command 2 servos through the USB of the Digispark.
|
||||
// It uses:
|
||||
// - <SoftRcPulseOut> library to easily generates the RC pulses for the servos.
|
||||
// - <DigiUSB> library to communicate with the PC
|
||||
// By RC Navy (http://p.loussouarn.free.fr)
|
||||
|
||||
// The command (issued in the DigiUSB Monitor or the digiterm) is:
|
||||
// S=P with:
|
||||
// S=A for ServoA and S=B for ServoB
|
||||
// P=Position number x 20° (Possible positions are from 0 to 9 which correspond to from 0° to 180°)
|
||||
// Ex:
|
||||
// A=7 sets Servo1 at 7 x 20 =140°
|
||||
// B=3 sets Servo2 at 3 x 20 =60°
|
||||
// Once the servo selected, just type the value between 0 and 9
|
||||
// Please, note this sketch is derived from the SerialServo example of <SoftwareServo> library.
|
||||
|
||||
#include <DigiUSB.h>
|
||||
#include <SoftRcPulseOut.h>
|
||||
|
||||
#define LED_PIN 1 /* Builtin Led on Rev2 ModelA Digispark */
|
||||
#define SERVO_A_PIN 2
|
||||
/* /!\ Do not use Pin 3 (used by USB) /!\ */
|
||||
/* /!\ Do not use Pin 4 (used by USB) /!\ */
|
||||
#define SERVO_B_PIN 5
|
||||
|
||||
SoftRcPulseOut ServoA;
|
||||
SoftRcPulseOut ServoB;
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
pinMode(LED_PIN,OUTPUT);
|
||||
ServoA.attach(SERVO_A_PIN);
|
||||
ServoB.attach(SERVO_B_PIN);
|
||||
DigiUSB.begin();
|
||||
DigiUSB.println(" Ready");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
static int value = 0;
|
||||
static char CurrentServo = 0;
|
||||
|
||||
if ( DigiUSB.available()) {
|
||||
char ch = DigiUSB.read();
|
||||
switch(ch) {
|
||||
case 'A':
|
||||
CurrentServo='A';
|
||||
digitalWrite(LED_PIN,LOW);
|
||||
break;
|
||||
case 'B':
|
||||
CurrentServo='B';
|
||||
digitalWrite(LED_PIN,HIGH);
|
||||
break;
|
||||
case '0' ... '9':
|
||||
value=(ch-'0')*20;
|
||||
if (CurrentServo=='A')
|
||||
{
|
||||
ServoA.write(value);
|
||||
}
|
||||
else if (CurrentServo=='B')
|
||||
{
|
||||
ServoB.write(value);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
DigiUSB.refresh();
|
||||
SoftRcPulseOut::refresh();
|
||||
/*
|
||||
Put here your non-blocking code
|
||||
*/
|
||||
}
|
@@ -0,0 +1,53 @@
|
||||
// Controlling a servo position using a potentiometer (variable resistor)
|
||||
// by Michal Rinott <http://people.interaction-ivrea.it/m.rinott>
|
||||
// Adapted to SoftRcPulseOut library by RC Navy (http://p.loussouarn.free.fr)
|
||||
// This sketch can work with ATtiny and Arduino UNO, MEGA, etc...
|
||||
|
||||
#include <SoftRcPulseOut.h>
|
||||
|
||||
SoftRcPulseOut myservo; // create servo object to control a servo
|
||||
|
||||
#if defined(__AVR_ATtiny24__) || defined(__AVR_ATtiny44__) || defined(__AVR_ATtiny84__) || defined(__AVR_ATtiny25__) || defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__)
|
||||
//Here is the POT_PIN definition for ATtiny, they do NOT need a 'A' prefix for Analogic definition
|
||||
#define POT_PIN 2 // --analog pin-- (not digital) used to connect the potentiometer
|
||||
#else
|
||||
//Here is the POT_PIN definition for Arduino UNO, MEGA, they do need a 'A' prefix for Analogic definition
|
||||
#define POT_PIN A2 // --analog pin-- (not digital) used to connect the potentiometer
|
||||
#endif
|
||||
|
||||
#define SERVO_PIN 3 // --digital pin-- (not analog) used to connect the servo
|
||||
|
||||
#define REFRESH_PERIOD_MS 20
|
||||
|
||||
|
||||
#define MOY_SUR_1_VALEUR 0
|
||||
#define MOY_SUR_2_VALEURS 1
|
||||
#define MOY_SUR_4_VALEURS 2
|
||||
#define MOY_SUR_8_VALEURS 3
|
||||
#define MOY_SUR_16_VALEURS 4
|
||||
#define MOY_SUR_32_VALEURS 5
|
||||
|
||||
#define TAUX_DE_MOYENNAGE MOY_SUR_4_VALEURS /* Choisir ici le taux de moyennage parmi les valeurs precedentes possibles listees ci-dessus */
|
||||
/* Plus le taux est élevé, plus le système est stable (diminution de la gigue), mais moins il est réactif */
|
||||
|
||||
#define MOYENNE(Valeur_A_Moyenner,DerniereValeurRecue,TauxDeMoyEnPuissanceDeDeux) Valeur_A_Moyenner=((((Valeur_A_Moyenner)*((1<<(TauxDeMoyEnPuissanceDeDeux))-1)+(DerniereValeurRecue))/(1<<(TauxDeMoyEnPuissanceDeDeux)))+(TauxDeMoyEnPuissanceDeDeux-1))
|
||||
|
||||
int val; // variable to read the value from the analog pin
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
||||
myservo.attach(SERVO_PIN); // attaches the servo on pin defined by SERVO_PIN to the servo object
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
static int ValMoyennee;
|
||||
val = analogRead(POT_PIN); // reads the value of the potentiometer (value between 0 and 1023)
|
||||
val = map(val, 0, 1023, 0, 179); // scale it to use it with the servo (value between 0 and 180)
|
||||
MOYENNE(ValMoyennee,val,TAUX_DE_MOYENNAGE);//If there is lots of noise: average with TAUX_DE_MOYENNAGE
|
||||
myservo.write(ValMoyennee); // sets the servo position according to the scaled value
|
||||
delay(REFRESH_PERIOD_MS); // waits for the servo to get there
|
||||
SoftRcPulseOut::refresh(); // generates the servo pulse
|
||||
}
|
||||
|
@@ -0,0 +1,27 @@
|
||||
#######################################
|
||||
# Syntax Coloring Map SoftRcPulseOut
|
||||
#######################################
|
||||
|
||||
#######################################
|
||||
# Datatypes (KEYWORD1)
|
||||
#######################################
|
||||
|
||||
SoftRcPulseOut KEYWORD1
|
||||
|
||||
#######################################
|
||||
# Methods and Functions (KEYWORD2)
|
||||
#######################################
|
||||
attach KEYWORD2
|
||||
detach KEYWORD2
|
||||
write KEYWORD2
|
||||
write_us KEYWORD2
|
||||
read KEYWORD2
|
||||
read_us KEYWORD2
|
||||
attached KEYWORD2
|
||||
setMinimumPulse KEYWORD2
|
||||
setMaximumPulse KEYWORD2
|
||||
refresh KEYWORD2
|
||||
|
||||
#######################################
|
||||
# Constants (LITERAL1)
|
||||
#######################################
|
Reference in New Issue
Block a user