mirror of
https://github.com/k3ng/k3ng_rotator_controller.git
synced 2024-12-18 20:57:56 +00:00
2018.04.21.01
Added OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE for FEATURE_STEPPER_MOTOR. Also added TimerOne library to Github.
This commit is contained in:
parent
9bf5fa1c33
commit
b1be2b7e6b
@ -371,6 +371,9 @@
|
||||
2018.03.14.01
|
||||
SET_I2C_BUS_SPEED in settings file; set I2C bus speed to help address I2C I/O time impact serial port performance
|
||||
|
||||
2018.04.21.01
|
||||
Added OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE for FEATURE_STEPPER_MOTOR. Also added TimerOne library to Github.
|
||||
|
||||
|
||||
All library files should be placed in directories likes \sketchbook\libraries\library1\ , \sketchbook\libraries\library2\ , etc.
|
||||
Anything rotator_*.* should be in the ino directory!
|
||||
@ -381,7 +384,7 @@
|
||||
|
||||
*/
|
||||
|
||||
#define CODE_VERSION "2018.03.14.01"
|
||||
#define CODE_VERSION "2018.04.21.01"
|
||||
|
||||
#include <avr/pgmspace.h>
|
||||
#include <EEPROM.h>
|
||||
@ -527,7 +530,11 @@
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
// #include <TimerFive.h>
|
||||
#ifdef OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
#include <TimerOne.h>
|
||||
#else
|
||||
#include <TimerFive.h>
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#include "rotator_language.h"
|
||||
@ -6853,8 +6860,13 @@ void initialize_interrupts(){
|
||||
#endif // FEATURE_EL_POSITION_PULSE_INPUT
|
||||
|
||||
#ifdef FEATURE_STEPPER_MOTOR
|
||||
Timer5.initialize(250); // 250 us = 4 khz rate
|
||||
Timer5.attachInterrupt(service_stepper_motor_pulse_pins);
|
||||
#ifdef OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
Timer1.initialize(250); // 250 us = 4 khz rate
|
||||
Timer1.attachInterrupt(service_stepper_motor_pulse_pins);
|
||||
#else
|
||||
Timer5.initialize(250); // 250 us = 4 khz rate
|
||||
Timer5.attachInterrupt(service_stepper_motor_pulse_pins);
|
||||
#endif
|
||||
#endif //FEATURE_STEPPER_MOTOR
|
||||
|
||||
|
||||
|
@ -17,7 +17,7 @@
|
||||
// #define FEATURE_RTC_DS1307
|
||||
// #define FEATURE_RTC_PCF8583
|
||||
// #define FEATURE_ETHERNET
|
||||
// #define FEATURE_STEPPER_MOTOR // requires Mega or an AVR with Timer 5 support
|
||||
// #define FEATURE_STEPPER_MOTOR // Requires TimerFive library to be copied to the Arduino libraries directory (If using OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE below, copy the TimeOne library)
|
||||
// #define FEATURE_AUTOCORRECT
|
||||
// #define FEATURE_TEST_DISPLAY_AT_STARTUP
|
||||
|
||||
@ -163,6 +163,7 @@
|
||||
// #define OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING // change OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING_STRING in settings file
|
||||
// #define OPTION_GPS_EXCLUDE_MISSING_LF_CR_HANDLING
|
||||
// #define OPTION_MORE_SERIAL_CHECKS
|
||||
// #define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
|
||||
/* ---------------------- debug stuff - don't touch unless you know what you are doing --------------------------- */
|
||||
|
||||
|
@ -54,6 +54,7 @@
|
||||
//#define OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING // change OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING_STRING in settings file
|
||||
//#define OPTION_GPS_EXCLUDE_MISSING_LF_CR_HANDLING
|
||||
//#define OPTION_MORE_SERIAL_CHECKS
|
||||
//#define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
|
||||
|
||||
/* ---------------------- debug stuff - don't touch unless you know what you are doing --------------------------- */
|
||||
|
@ -150,6 +150,7 @@
|
||||
//#define OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING // change OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING_STRING in settings file
|
||||
//#define OPTION_GPS_EXCLUDE_MISSING_LF_CR_HANDLING
|
||||
//#define OPTION_MORE_SERIAL_CHECKS
|
||||
//#define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
|
||||
/* ---------------------- debug stuff - don't touch unless you know what you are doing --------------------------- */
|
||||
|
||||
|
@ -23,7 +23,7 @@
|
||||
#define FEATURE_RTC_DS1307
|
||||
// #define FEATURE_RTC_PCF8583
|
||||
// #define FEATURE_ETHERNET
|
||||
// #define FEATURE_STEPPER_MOTOR // requires Mega or an AVR with Timer 5 support
|
||||
#define FEATURE_STEPPER_MOTOR // Requires TimerFive library to be copied to the Arduino libraries directory (If using OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE below, copy the TimeOne library)
|
||||
// #define FEATURE_AUTOCORRECT
|
||||
// #define FEATURE_TEST_DISPLAY_AT_STARTUP
|
||||
|
||||
@ -168,6 +168,7 @@
|
||||
// #define OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING // change OPTION_SEND_STRING_OUT_CONTROL_PORT_WHEN_INITIALIZING_STRING in settings file
|
||||
// #define OPTION_GPS_EXCLUDE_MISSING_LF_CR_HANDLING
|
||||
// #define OPTION_MORE_SERIAL_CHECKS
|
||||
#define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
|
||||
|
||||
// ######## ######## ###### ########
|
||||
|
@ -17,7 +17,7 @@
|
||||
//#define FEATURE_RTC_DS1307
|
||||
//#define FEATURE_RTC_PCF8583
|
||||
//#define FEATURE_ETHERNET
|
||||
#define FEATURE_STEPPER_MOTOR // requires this library: https://code.google.com/p/rogue-code/wiki/ToneLibraryDocumentation
|
||||
#define FEATURE_STEPPER_MOTOR // Requires TimerFive library to be copied to the Arduino libraries directory (If using OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE below, copy the TimeOne library)
|
||||
//#define FEATURE_AUTOCORRECT
|
||||
// #define FEATURE_TEST_DISPLAY_AT_STARTUP
|
||||
|
||||
@ -147,6 +147,7 @@
|
||||
//#define OPTION_SAVE_MEMORY_EXCLUDE_EXTENDED_COMMANDS
|
||||
//#define OPTION_GPS_EXCLUDE_MISSING_LF_CR_HANDLING
|
||||
//#define OPTION_MORE_SERIAL_CHECKS
|
||||
//#define OPTION_STEPPER_MOTOR_USE_TIMER_ONE_INSTEAD_OF_FIVE
|
||||
|
||||
/*
|
||||
|
||||
|
209
libraries/TimerOne/TimerOne.cpp
Executable file
209
libraries/TimerOne/TimerOne.cpp
Executable file
@ -0,0 +1,209 @@
|
||||
/*
|
||||
* Interrupt and PWM utilities for 16 bit Timer1 on ATmega168/328
|
||||
* Original code by Jesse Tane for http://labs.ideo.com August 2008
|
||||
* Modified March 2009 by Jérôme Despatis and Jesse Tane for ATmega328 support
|
||||
* Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop
|
||||
* Modified June 2011 by Lex Talionis to add a function to read the timer
|
||||
* Modified Oct 2011 by Andrew Richards to avoid certain problems:
|
||||
* - Add (long) assignments and casts to TimerOne::read() to ensure calculations involving tmp, ICR1 and TCNT1 aren't truncated
|
||||
* - Ensure 16 bit registers accesses are atomic - run with interrupts disabled when accessing
|
||||
* - Remove global enable of interrupts (sei())- could be running within an interrupt routine)
|
||||
* - Disable interrupts whilst TCTN1 == 0. Datasheet vague on this, but experiment shows that overflow interrupt
|
||||
* flag gets set whilst TCNT1 == 0, resulting in a phantom interrupt. Could just set to 1, but gets inaccurate
|
||||
* at very short durations
|
||||
* - startBottom() added to start counter at 0 and handle all interrupt enabling.
|
||||
* - start() amended to enable interrupts
|
||||
* - restart() amended to point at startBottom()
|
||||
* Modiied 7:26 PM Sunday, October 09, 2011 by Lex Talionis
|
||||
* - renamed start() to resume() to reflect it's actual role
|
||||
* - renamed startBottom() to start(). This breaks some old code that expects start to continue counting where it left off
|
||||
*
|
||||
* 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 3 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, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* See Google Code project http://code.google.com/p/arduino-timerone/ for latest
|
||||
*/
|
||||
#ifndef TIMERONE_cpp
|
||||
#define TIMERONE_cpp
|
||||
|
||||
#include "TimerOne.h"
|
||||
|
||||
TimerOne Timer1; // preinstatiate
|
||||
|
||||
ISR(TIMER1_OVF_vect) // interrupt service routine that wraps a user defined function supplied by attachInterrupt
|
||||
{
|
||||
Timer1.isrCallback();
|
||||
}
|
||||
|
||||
|
||||
void TimerOne::initialize(long microseconds)
|
||||
{
|
||||
TCCR1A = 0; // clear control register A
|
||||
TCCR1B = _BV(WGM13); // set mode 8: phase and frequency correct pwm, stop the timer
|
||||
setPeriod(microseconds);
|
||||
}
|
||||
|
||||
|
||||
void TimerOne::setPeriod(long microseconds) // AR modified for atomic access
|
||||
{
|
||||
|
||||
long cycles = (F_CPU / 2000000) * microseconds; // the counter runs backwards after TOP, interrupt is at BOTTOM so divide microseconds by 2
|
||||
if(cycles < RESOLUTION) clockSelectBits = _BV(CS10); // no prescale, full xtal
|
||||
else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS11); // prescale by /8
|
||||
else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS11) | _BV(CS10); // prescale by /64
|
||||
else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS12); // prescale by /256
|
||||
else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS12) | _BV(CS10); // prescale by /1024
|
||||
else cycles = RESOLUTION - 1, clockSelectBits = _BV(CS12) | _BV(CS10); // request was out of bounds, set as maximum
|
||||
|
||||
oldSREG = SREG;
|
||||
cli(); // Disable interrupts for 16 bit register access
|
||||
ICR1 = pwmPeriod = cycles; // ICR1 is TOP in p & f correct pwm mode
|
||||
SREG = oldSREG;
|
||||
|
||||
TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
|
||||
TCCR1B |= clockSelectBits; // reset clock select register, and starts the clock
|
||||
}
|
||||
|
||||
void TimerOne::setPwmDuty(char pin, int duty)
|
||||
{
|
||||
unsigned long dutyCycle = pwmPeriod;
|
||||
|
||||
dutyCycle *= duty;
|
||||
dutyCycle >>= 10;
|
||||
|
||||
oldSREG = SREG;
|
||||
cli();
|
||||
if(pin == 1 || pin == 9) OCR1A = dutyCycle;
|
||||
else if(pin == 2 || pin == 10) OCR1B = dutyCycle;
|
||||
SREG = oldSREG;
|
||||
}
|
||||
|
||||
void TimerOne::pwm(char pin, int duty, long microseconds) // expects duty cycle to be 10 bit (1024)
|
||||
{
|
||||
if(microseconds > 0) setPeriod(microseconds);
|
||||
if(pin == 1 || pin == 9) {
|
||||
DDRB |= _BV(PORTB1); // sets data direction register for pwm output pin
|
||||
TCCR1A |= _BV(COM1A1); // activates the output pin
|
||||
}
|
||||
else if(pin == 2 || pin == 10) {
|
||||
DDRB |= _BV(PORTB2);
|
||||
TCCR1A |= _BV(COM1B1);
|
||||
}
|
||||
setPwmDuty(pin, duty);
|
||||
resume(); // Lex - make sure the clock is running. We don't want to restart the count, in case we are starting the second WGM
|
||||
// and the first one is in the middle of a cycle
|
||||
}
|
||||
|
||||
void TimerOne::disablePwm(char pin)
|
||||
{
|
||||
if(pin == 1 || pin == 9) TCCR1A &= ~_BV(COM1A1); // clear the bit that enables pwm on PB1
|
||||
else if(pin == 2 || pin == 10) TCCR1A &= ~_BV(COM1B1); // clear the bit that enables pwm on PB2
|
||||
}
|
||||
|
||||
void TimerOne::attachInterrupt(void (*isr)(), long microseconds)
|
||||
{
|
||||
if(microseconds > 0) setPeriod(microseconds);
|
||||
isrCallback = isr; // register the user's callback with the real ISR
|
||||
TIMSK1 = _BV(TOIE1); // sets the timer overflow interrupt enable bit
|
||||
// might be running with interrupts disabled (eg inside an ISR), so don't touch the global state
|
||||
// sei();
|
||||
resume();
|
||||
}
|
||||
|
||||
void TimerOne::detachInterrupt()
|
||||
{
|
||||
TIMSK1 &= ~_BV(TOIE1); // clears the timer overflow interrupt enable bit
|
||||
// timer continues to count without calling the isr
|
||||
}
|
||||
|
||||
void TimerOne::resume() // AR suggested
|
||||
{
|
||||
TCCR1B |= clockSelectBits;
|
||||
}
|
||||
|
||||
void TimerOne::restart() // Depricated - Public interface to start at zero - Lex 10/9/2011
|
||||
{
|
||||
start();
|
||||
}
|
||||
|
||||
void TimerOne::start() // AR addition, renamed by Lex to reflect it's actual role
|
||||
{
|
||||
unsigned int tcnt1;
|
||||
|
||||
TIMSK1 &= ~_BV(TOIE1); // AR added
|
||||
GTCCR |= _BV(PSRSYNC); // AR added - reset prescaler (NB: shared with all 16 bit timers);
|
||||
|
||||
oldSREG = SREG; // AR - save status register
|
||||
cli(); // AR - Disable interrupts
|
||||
TCNT1 = 0;
|
||||
SREG = oldSREG; // AR - Restore status register
|
||||
resume();
|
||||
do { // Nothing -- wait until timer moved on from zero - otherwise get a phantom interrupt
|
||||
oldSREG = SREG;
|
||||
cli();
|
||||
tcnt1 = TCNT1;
|
||||
SREG = oldSREG;
|
||||
} while (tcnt1==0);
|
||||
|
||||
// TIFR1 = 0xff; // AR - Clear interrupt flags
|
||||
// TIMSK1 = _BV(TOIE1); // sets the timer overflow interrupt enable bit
|
||||
}
|
||||
|
||||
void TimerOne::stop()
|
||||
{
|
||||
TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); // clears all clock selects bits
|
||||
}
|
||||
|
||||
unsigned long TimerOne::read() //returns the value of the timer in microseconds
|
||||
{ //rember! phase and freq correct mode counts up to then down again
|
||||
unsigned long tmp; // AR amended to hold more than 65536 (could be nearly double this)
|
||||
unsigned int tcnt1; // AR added
|
||||
|
||||
oldSREG= SREG;
|
||||
cli();
|
||||
tmp=TCNT1;
|
||||
SREG = oldSREG;
|
||||
|
||||
char scale=0;
|
||||
switch (clockSelectBits)
|
||||
{
|
||||
case 1:// no prescalse
|
||||
scale=0;
|
||||
break;
|
||||
case 2:// x8 prescale
|
||||
scale=3;
|
||||
break;
|
||||
case 3:// x64
|
||||
scale=6;
|
||||
break;
|
||||
case 4:// x256
|
||||
scale=8;
|
||||
break;
|
||||
case 5:// x1024
|
||||
scale=10;
|
||||
break;
|
||||
}
|
||||
|
||||
do { // Nothing -- max delay here is ~1023 cycles. AR modified
|
||||
oldSREG = SREG;
|
||||
cli();
|
||||
tcnt1 = TCNT1;
|
||||
SREG = oldSREG;
|
||||
} while (tcnt1==tmp); //if the timer has not ticked yet
|
||||
|
||||
//if we are counting down add the top value to how far we have counted down
|
||||
tmp = ( (tcnt1>tmp) ? (tmp) : (long)(ICR1-tcnt1)+(long)ICR1 ); // AR amended to add casts and reuse previous TCNT1
|
||||
return ((tmp*1000L)/(F_CPU /1000L))<<scale;
|
||||
}
|
||||
|
||||
#endif
|
70
libraries/TimerOne/TimerOne.h
Executable file
70
libraries/TimerOne/TimerOne.h
Executable file
@ -0,0 +1,70 @@
|
||||
/*
|
||||
* Interrupt and PWM utilities for 16 bit Timer1 on ATmega168/328
|
||||
* Original code by Jesse Tane for http://labs.ideo.com August 2008
|
||||
* Modified March 2009 by Jérôme Despatis and Jesse Tane for ATmega328 support
|
||||
* Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop
|
||||
* Modified June 2011 by Lex Talionis to add a function to read the timer
|
||||
* Modified Oct 2011 by Andrew Richards to avoid certain problems:
|
||||
* - Add (long) assignments and casts to TimerOne::read() to ensure calculations involving tmp, ICR1 and TCNT1 aren't truncated
|
||||
* - Ensure 16 bit registers accesses are atomic - run with interrupts disabled when accessing
|
||||
* - Remove global enable of interrupts (sei())- could be running within an interrupt routine)
|
||||
* - Disable interrupts whilst TCTN1 == 0. Datasheet vague on this, but experiment shows that overflow interrupt
|
||||
* flag gets set whilst TCNT1 == 0, resulting in a phantom interrupt. Could just set to 1, but gets inaccurate
|
||||
* at very short durations
|
||||
* - startBottom() added to start counter at 0 and handle all interrupt enabling.
|
||||
* - start() amended to enable interrupts
|
||||
* - restart() amended to point at startBottom()
|
||||
* Modiied 7:26 PM Sunday, October 09, 2011 by Lex Talionis
|
||||
* - renamed start() to resume() to reflect it's actual role
|
||||
* - renamed startBottom() to start(). This breaks some old code that expects start to continue counting where it left off
|
||||
*
|
||||
* 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 3 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, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* See Google Code project http://code.google.com/p/arduino-timerone/ for latest
|
||||
*/
|
||||
#ifndef TIMERONE_h
|
||||
#define TIMERONE_h
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#define RESOLUTION 65536 // Timer1 is 16 bit
|
||||
|
||||
class TimerOne
|
||||
{
|
||||
public:
|
||||
|
||||
// properties
|
||||
unsigned int pwmPeriod;
|
||||
unsigned char clockSelectBits;
|
||||
char oldSREG; // To hold Status Register while ints disabled
|
||||
|
||||
// methods
|
||||
void initialize(long microseconds=1000000);
|
||||
void start();
|
||||
void stop();
|
||||
void restart();
|
||||
void resume();
|
||||
unsigned long read();
|
||||
void pwm(char pin, int duty, long microseconds=-1);
|
||||
void disablePwm(char pin);
|
||||
void attachInterrupt(void (*isr)(), long microseconds=-1);
|
||||
void detachInterrupt();
|
||||
void setPeriod(long microseconds);
|
||||
void setPwmDuty(char pin, int duty);
|
||||
void (*isrCallback)();
|
||||
};
|
||||
|
||||
extern TimerOne Timer1;
|
||||
#endif
|
26
libraries/TimerOne/examples/ISRBlink/ISRBlink.pde
Executable file
26
libraries/TimerOne/examples/ISRBlink/ISRBlink.pde
Executable file
@ -0,0 +1,26 @@
|
||||
#include <TimerOne.h>
|
||||
|
||||
void setup()
|
||||
{
|
||||
// Initialize the digital pin as an output.
|
||||
// Pin 13 has an LED connected on most Arduino boards
|
||||
pinMode(13, OUTPUT);
|
||||
|
||||
Timer1.initialize(100000); // set a timer of length 100000 microseconds (or 0.1 sec - or 10Hz => the led will blink 5 times, 5 cycles of on-and-off, per second)
|
||||
Timer1.attachInterrupt( timerIsr ); // attach the service routine here
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
// Main code loop
|
||||
// TODO: Put your regular (non-ISR) logic here
|
||||
}
|
||||
|
||||
/// --------------------------
|
||||
/// Custom ISR Timer Routine
|
||||
/// --------------------------
|
||||
void timerIsr()
|
||||
{
|
||||
// Toggle LED
|
||||
digitalWrite( 13, digitalRead( 13 ) ^ 1 );
|
||||
}
|
11
libraries/TimerOne/examples/ReadReciver/.svn/all-wcprops
Executable file
11
libraries/TimerOne/examples/ReadReciver/.svn/all-wcprops
Executable file
@ -0,0 +1,11 @@
|
||||
K 25
|
||||
svn:wc:ra_dav:version-url
|
||||
V 51
|
||||
/svn/!svn/ver/3/trunk/Release%20Quality/ReadReciver
|
||||
END
|
||||
ReadReciver.pde
|
||||
K 25
|
||||
svn:wc:ra_dav:version-url
|
||||
V 67
|
||||
/svn/!svn/ver/7/trunk/Release%20Quality/ReadReciver/ReadReciver.pde
|
||||
END
|
5
libraries/TimerOne/examples/ReadReciver/.svn/dir-prop-base
Executable file
5
libraries/TimerOne/examples/ReadReciver/.svn/dir-prop-base
Executable file
@ -0,0 +1,5 @@
|
||||
K 14
|
||||
bugtraq:number
|
||||
V 4
|
||||
true
|
||||
END
|
62
libraries/TimerOne/examples/ReadReciver/.svn/entries
Executable file
62
libraries/TimerOne/examples/ReadReciver/.svn/entries
Executable file
@ -0,0 +1,62 @@
|
||||
10
|
||||
|
||||
dir
|
||||
6
|
||||
https://lex-arduino-sketchbook.googlecode.com/svn/trunk/Release%20Quality/ReadReciver
|
||||
https://lex-arduino-sketchbook.googlecode.com/svn
|
||||
|
||||
|
||||
|
||||
2011-06-24T22:05:24.141546Z
|
||||
3
|
||||
lex.v.talionis@gmail.com
|
||||
has-props
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
c9f85be5-ce43-0359-81d1-43f08a9217a6
|
||||
|
||||
ReadReciver.pde
|
||||
file
|
||||
7
|
||||
|
||||
|
||||
|
||||
2011-06-25T03:21:57.149370Z
|
||||
7554a9104cd32bca8710cff214402bb2
|
||||
2011-06-25T03:22:33.720706Z
|
||||
7
|
||||
lex.v.talionis@gmail.com
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
3527
|
||||
|
114
libraries/TimerOne/examples/ReadReciver/.svn/text-base/ReadReciver.pde.svn-base
Executable file
114
libraries/TimerOne/examples/ReadReciver/.svn/text-base/ReadReciver.pde.svn-base
Executable file
@ -0,0 +1,114 @@
|
||||
/*
|
||||
Copyright 2011 Lex Talionis (Lex.V.Talionis at gmail)
|
||||
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 3 of the License, or (at your option) any
|
||||
later version.
|
||||
|
||||
This uses pin change interrupts and timer 1 to mesure the
|
||||
time between the rise and fall of 3 channels of PPM
|
||||
(Though often called PWM, see http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1253149521/all)
|
||||
on a typical RC car reciver. It could be extended to as
|
||||
many channels as you like.
|
||||
|
||||
*/
|
||||
#include <PinChangeInt.h> // http://www.arduino.cc/playground/Main/PinChangeInt
|
||||
#include <PinChangeIntConfig.h>
|
||||
#include <TimerOne.h> // http://www.arduino.cc/playground/Code/Timer1
|
||||
|
||||
#define NO_PORTB_PINCHANGES //PinChangeInt setup
|
||||
#define NO_PORTC_PINCHANGES //only port D pinchanges (see: http://www.arduino.cc/playground/Learning/Pins)
|
||||
#define PIN_COUNT 3 //number of channels attached to the reciver
|
||||
#define MAX_PIN_CHANGE_PINS PIN_COUNT
|
||||
|
||||
#define RC_TURN 3 //arduino pins attached to the reciver
|
||||
#define RC_FWD 2
|
||||
#define RC_FIRE 4
|
||||
byte pin[] = {RC_FWD, RC_TURN, RC_FIRE}; //for maximum efficency thise pins should be attached
|
||||
unsigned int time[] = {0,0,0}; // to the reciver's channels in the order listed here
|
||||
|
||||
byte state=0;
|
||||
byte burp=0; // a counter to see how many times the int has executed
|
||||
byte cmd=0; // a place to put our serial data
|
||||
byte i=0; // global counter for tracking what pin we are on
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
Serial.print("PinChangeInt ReciverReading test");
|
||||
Serial.println(); //warm up the serial port
|
||||
|
||||
Timer1.initialize(2200); //longest pulse in PPM is usally 2.1 milliseconds,
|
||||
//pick a period that gives you a little headroom.
|
||||
Timer1.stop(); //stop the counter
|
||||
Timer1.restart(); //set the clock to zero
|
||||
|
||||
for (byte i=0; i<3; i++)
|
||||
{
|
||||
pinMode(pin[i], INPUT); //set the pin to input
|
||||
digitalWrite(pin[i], HIGH); //use the internal pullup resistor
|
||||
}
|
||||
PCintPort::attachInterrupt(pin[i], rise,RISING); // attach a PinChange Interrupt to our first pin
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
cmd=Serial.read(); //while you got some time gimme a systems report
|
||||
if (cmd=='p')
|
||||
{
|
||||
Serial.print("time:\t");
|
||||
for (byte i=0; i<PIN_COUNT;i++)
|
||||
{
|
||||
Serial.print(i,DEC);
|
||||
Serial.print(":");
|
||||
Serial.print(time[i],DEC);
|
||||
Serial.print("\t");
|
||||
}
|
||||
Serial.print(burp, DEC);
|
||||
Serial.println();
|
||||
/* Serial.print("\t");
|
||||
Serial.print(clockCyclesToMicroseconds(Timer1.pwmPeriod), DEC);
|
||||
Serial.print("\t");
|
||||
Serial.print(Timer1.clockSelectBits, BIN);
|
||||
Serial.print("\t");
|
||||
Serial.println(ICR1, DEC);*/
|
||||
}
|
||||
cmd=0;
|
||||
|
||||
switch (state)
|
||||
{
|
||||
case RISING: //we have just seen a rising edge
|
||||
PCintPort::detachInterrupt(pin[i]);
|
||||
PCintPort::attachInterrupt(pin[i], fall, FALLING); //attach the falling end
|
||||
state=255;
|
||||
break;
|
||||
case FALLING: //we just saw a falling edge
|
||||
PCintPort::detachInterrupt(pin[i]);
|
||||
i++; //move to the next pin
|
||||
i = i % PIN_COUNT; //i ranges from 0 to PIN_COUNT
|
||||
PCintPort::attachInterrupt(pin[i], rise,RISING);
|
||||
state=255;
|
||||
break;
|
||||
/*default:
|
||||
//do nothing
|
||||
break;*/
|
||||
}
|
||||
}
|
||||
|
||||
void rise() //on the rising edge of the currently intresting pin
|
||||
{
|
||||
Timer1.restart(); //set our stopwatch to 0
|
||||
Timer1.start(); //and start it up
|
||||
state=RISING;
|
||||
// Serial.print('r');
|
||||
burp++;
|
||||
}
|
||||
|
||||
void fall() //on the falling edge of the signal
|
||||
{
|
||||
state=FALLING;
|
||||
|
||||
time[i]=Timer1.read(); // Needs Timer1-v2
|
||||
Timer1.stop();
|
||||
// Serial.print('f');
|
||||
}
|
114
libraries/TimerOne/examples/ReadReciver/ReadReciver.pde
Executable file
114
libraries/TimerOne/examples/ReadReciver/ReadReciver.pde
Executable file
@ -0,0 +1,114 @@
|
||||
/*
|
||||
Copyright 2011 Lex Talionis (Lex.V.Talionis at gmail)
|
||||
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 3 of the License, or (at your option) any
|
||||
later version.
|
||||
|
||||
This uses pin change interrupts and timer 1 to mesure the
|
||||
time between the rise and fall of 3 channels of PPM
|
||||
(Though often called PWM, see http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1253149521/all)
|
||||
on a typical RC car reciver. It could be extended to as
|
||||
many channels as you like.
|
||||
|
||||
*/
|
||||
#include <PinChangeInt.h> // http://www.arduino.cc/playground/Main/PinChangeInt
|
||||
#include <PinChangeIntConfig.h>
|
||||
#include <TimerOne.h> // http://www.arduino.cc/playground/Code/Timer1
|
||||
|
||||
#define NO_PORTB_PINCHANGES //PinChangeInt setup
|
||||
#define NO_PORTC_PINCHANGES //only port D pinchanges (see: http://www.arduino.cc/playground/Learning/Pins)
|
||||
#define PIN_COUNT 3 //number of channels attached to the reciver
|
||||
#define MAX_PIN_CHANGE_PINS PIN_COUNT
|
||||
|
||||
#define RC_TURN 3 //arduino pins attached to the reciver
|
||||
#define RC_FWD 2
|
||||
#define RC_FIRE 4
|
||||
byte pin[] = {RC_FWD, RC_TURN, RC_FIRE}; //for maximum efficency thise pins should be attached
|
||||
unsigned int time[] = {0,0,0}; // to the reciver's channels in the order listed here
|
||||
|
||||
byte state=0;
|
||||
byte burp=0; // a counter to see how many times the int has executed
|
||||
byte cmd=0; // a place to put our serial data
|
||||
byte i=0; // global counter for tracking what pin we are on
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
Serial.print("PinChangeInt ReciverReading test");
|
||||
Serial.println(); //warm up the serial port
|
||||
|
||||
Timer1.initialize(2200); //longest pulse in PPM is usally 2.1 milliseconds,
|
||||
//pick a period that gives you a little headroom.
|
||||
Timer1.stop(); //stop the counter
|
||||
Timer1.restart(); //set the clock to zero
|
||||
|
||||
for (byte i=0; i<3; i++)
|
||||
{
|
||||
pinMode(pin[i], INPUT); //set the pin to input
|
||||
digitalWrite(pin[i], HIGH); //use the internal pullup resistor
|
||||
}
|
||||
PCintPort::attachInterrupt(pin[i], rise,RISING); // attach a PinChange Interrupt to our first pin
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
cmd=Serial.read(); //while you got some time gimme a systems report
|
||||
if (cmd=='p')
|
||||
{
|
||||
Serial.print("time:\t");
|
||||
for (byte i=0; i<PIN_COUNT;i++)
|
||||
{
|
||||
Serial.print(i,DEC);
|
||||
Serial.print(":");
|
||||
Serial.print(time[i],DEC);
|
||||
Serial.print("\t");
|
||||
}
|
||||
Serial.print(burp, DEC);
|
||||
Serial.println();
|
||||
/* Serial.print("\t");
|
||||
Serial.print(clockCyclesToMicroseconds(Timer1.pwmPeriod), DEC);
|
||||
Serial.print("\t");
|
||||
Serial.print(Timer1.clockSelectBits, BIN);
|
||||
Serial.print("\t");
|
||||
Serial.println(ICR1, DEC);*/
|
||||
}
|
||||
cmd=0;
|
||||
|
||||
switch (state)
|
||||
{
|
||||
case RISING: //we have just seen a rising edge
|
||||
PCintPort::detachInterrupt(pin[i]);
|
||||
PCintPort::attachInterrupt(pin[i], fall, FALLING); //attach the falling end
|
||||
state=255;
|
||||
break;
|
||||
case FALLING: //we just saw a falling edge
|
||||
PCintPort::detachInterrupt(pin[i]);
|
||||
i++; //move to the next pin
|
||||
i = i % PIN_COUNT; //i ranges from 0 to PIN_COUNT
|
||||
PCintPort::attachInterrupt(pin[i], rise,RISING);
|
||||
state=255;
|
||||
break;
|
||||
/*default:
|
||||
//do nothing
|
||||
break;*/
|
||||
}
|
||||
}
|
||||
|
||||
void rise() //on the rising edge of the currently intresting pin
|
||||
{
|
||||
Timer1.restart(); //set our stopwatch to 0
|
||||
Timer1.start(); //and start it up
|
||||
state=RISING;
|
||||
// Serial.print('r');
|
||||
burp++;
|
||||
}
|
||||
|
||||
void fall() //on the falling edge of the signal
|
||||
{
|
||||
state=FALLING;
|
||||
|
||||
time[i]=Timer1.read(); // Needs Timer1-v2
|
||||
Timer1.stop();
|
||||
// Serial.print('f');
|
||||
}
|
32
libraries/TimerOne/keywords.txt
Executable file
32
libraries/TimerOne/keywords.txt
Executable file
@ -0,0 +1,32 @@
|
||||
#######################################
|
||||
# Syntax Coloring Map For TimerOne
|
||||
#######################################
|
||||
|
||||
#######################################
|
||||
# Datatypes (KEYWORD1)
|
||||
#######################################
|
||||
|
||||
TimerOne KEYWORD1
|
||||
|
||||
#######################################
|
||||
# Methods and Functions (KEYWORD2)
|
||||
#######################################
|
||||
|
||||
initialize KEYWORD2
|
||||
start KEYWORD2
|
||||
stop KEYWORD2
|
||||
restart KEYWORD2
|
||||
resume KEYWORD2
|
||||
read KEYWORD2
|
||||
pwm KEYWORD2
|
||||
disablePwm KEYWORD2
|
||||
attachInterrupt KEYWORD2
|
||||
detachInterrupt KEYWORD2
|
||||
setPeriod KEYWORD2
|
||||
setPwmDuty KEYWORD2
|
||||
|
||||
#######################################
|
||||
# Constants (LITERAL1)
|
||||
#######################################
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user