mirror of
https://github.com/digistump/DigistumpArduino.git
synced 2025-09-17 17:32:25 -07:00
Initial import of support files for all Digistump boards - Digispark, Pro, DigiX - including libraries, examples, tools, and other support files for the Arduino IDE
This commit is contained in:
@@ -0,0 +1,192 @@
|
||||
/*
|
||||
Sketch using <RcSeq> library, for automatically dropping a pneumatic Zodiac at sea and returning for it back to the deck of a supply vessel.
|
||||
The sequence is launched after sending the 'g' (Go) character at the USB interface.
|
||||
|
||||
In this example, the declared sequence is:
|
||||
1) The crane lifts the pneumatic Zodiac from the deck to the air and stops
|
||||
2) The crane rotates (90°) to locate the pneumatic Zodiac above the sea
|
||||
3) The crane drops down the pneumatic Zodiac at sea level
|
||||
4) The crane stops during 6 seconds
|
||||
5) The crane lifts up the pneumatic Zodiac from sea level to the air and stops
|
||||
6) The crane rotates (90°) to locate the pneumatic Zodiac above the deck
|
||||
7) The crane drops down the pneumatic Zodiac on the deck and stops. The sequence ends.
|
||||
This sequence uses:
|
||||
- 2 commands from USB interface ('g' and 't' characters from Digiterm or Digi Monitor)
|
||||
- 2 servos (a "ROTATION" servo for the crane rotation and an "UP/DOWN" servo to drop and lift the pneumatic Zodiac)
|
||||
|
||||
IMPORTANT:
|
||||
=========
|
||||
For this sketch, which is using <DigiUSB> library:
|
||||
1) Comment "#define RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT" in "arduino-1.xx\libraries\RcSeq.h".
|
||||
This will disable the code to manage incoming RC pulses and save some flash memory.
|
||||
2) Replace #define RING_BUFFER_SIZE 128 with #define RING_BUFFER_SIZE 32 in "arduino-1.xx\libraries\DigisparkUSB\DigiUSB.h".
|
||||
3) The sequence will be launch by sending "g" character through USB link (using Digiterm or Digi Monitor).
|
||||
To check all the sequence is performed asynchronously, you can send 't' to toggle the LED during servo motion!
|
||||
If step 1) and 2) are not done, this sketch won't compile because won't fit in programm memory of the DigiSpark!
|
||||
|
||||
RC Navy 2013
|
||||
http://p.loussouarn.free.fr
|
||||
*/
|
||||
|
||||
static void ToggleLed(void); /* Declare Short Action: Toggle a LED */
|
||||
|
||||
/*************************************************/
|
||||
/* STEP #1: Include the needed libraries */
|
||||
/*************************************************/
|
||||
#include <DigiUSB.h> /* The Servo Sequence will be launched by sending "g" character (Go) at the USB interface */
|
||||
#include <RcSeq.h>
|
||||
#include <SoftRcPulseOut.h>
|
||||
|
||||
#define LED_PIN 1
|
||||
|
||||
/*****************************************************************/
|
||||
/* STEP #2: Enumeration of the servos used in the sequence */
|
||||
/*****************************************************************/
|
||||
enum {ROTATION_SERVO=0, UP_DOWN_SERVO , SERVO_NB};
|
||||
|
||||
/*****************************************************************/
|
||||
/* STEP #3: Servos Digital Pins assignment */
|
||||
/*****************************************************************/
|
||||
#define UP_DOWN_SERVO_PIN 2
|
||||
/* /!\ Do not use Pin 3 (used by USB) /!\ */
|
||||
/* /!\ Do not use Pin 4 (used by USB) /!\ */
|
||||
#define ROTATION_SERVO_PIN 5
|
||||
|
||||
/**************************************************************************************/
|
||||
/* STEP #4: Declaration of the angles of the servos for the different motions (in °) */
|
||||
/**************************************************************************************/
|
||||
#define UP_DOWN_ON_DECK_POS 120 /* Zodiac on the deck */
|
||||
#define UP_DOWN_ON_AIR_POS 180 /* Zodiac in the air */
|
||||
#define UP_DOWN_ON_SEA_POS 0 /* Zodiac at sea level */
|
||||
|
||||
#define ROTATION_ABOVE_DECK_POS 90 /* crane at deck side */
|
||||
#define ROTATION_ABOVE_SEA_POS 0 /* crane at sea side */
|
||||
|
||||
|
||||
/***************************************************************************************************************************************/
|
||||
/* STEP #5: Do a temporal diagram showing the start up and the duration of each motions of each servo */
|
||||
/***************************************************************************************************************************************/
|
||||
/*
|
||||
All the start up values (time stamp) have as reference the moment of the sequence startup order (t=0).
|
||||
|
||||
UP_DOWN_SERVO MOTION ROTATION_SERVO MOTION UP_DOWN_SERVO MOTION NO MOTION MOUVEMENT(WAITING) UP_DOWN_SERVO MOTION ROTATION_SERVO MOTION UP_DOWN_SERVO MOTION
|
||||
Order <--DECK_TO_AIR_DURATION_MS--> <--DECK_TO_SEA_ROTATION_DURATION_MS--> <--AIR_TO_SEA_FALLING_DURATION_MS--> <--DELAY_BEFORE_RISING_UP_MS--> <--SEA_TO_AIR_RISING_DURATION_MS--> <--SEA_TO_DECK_ROTATION_DURATION_MS--> <--AIR_TO_DECK_FALLING_DURATION_MS-->
|
||||
|-------------------|-----------------------------|--------------------------------------|------------------------------------|-------------------------------|-----------------------------------|--------------------------------------|-------------------------------------|-->Time Axis
|
||||
0 START_UP_DECK_TO_AIR_MS START_UP_DECK_TO_SEA_ROTATION_MS START_UP_AIR_TO_SEA_FALLING_MS START_UP_SEA_TO_AIR_RISING_MS START_UP_SEA_TO_DECK_ROTATION_MS START_UP_AIR_TO_DECK_FALLING_MS
|
||||
*/
|
||||
|
||||
/**************************************************************************************************************************************************/
|
||||
/* STEP #6: With the help of the temporal diagram, declare start up time, the motion duration of servo and optional delay */
|
||||
/**************************************************************************************************************************************************/
|
||||
/* Tune below all the motion duration. Do not forget to add a trailer 'UL' for each value to force them in Unsigned Long type */
|
||||
#define START_UP_DECK_TO_AIR_MS 0UL /* 0 for immediate start up, but you can put a delay here. Ex: 2000UL, will delay the startup of the whole sequence after 2 seconds */
|
||||
#define DECK_TO_AIR_DURATION_MS 3000UL
|
||||
|
||||
#define START_UP_DECK_TO_SEA_ROTATION_MS (START_UP_DECK_TO_AIR_MS + DECK_TO_AIR_DURATION_MS)
|
||||
#define DECK_TO_SEA_ROTATION_DURATION_MS 3000UL
|
||||
|
||||
#define START_UP_AIR_TO_SEA_FALLING_MS (START_UP_DECK_TO_SEA_ROTATION_MS + DECK_TO_SEA_ROTATION_DURATION_MS)
|
||||
#define AIR_TO_SEA_FALLING_DURATION_MS 9000UL
|
||||
|
||||
#define DELAY_BEFORE_RISING_UP_MS 6000UL
|
||||
|
||||
#define START_UP_SEA_TO_AIR_RISING_MS (START_UP_AIR_TO_SEA_FALLING_MS + AIR_TO_SEA_FALLING_DURATION_MS + DELAY_BEFORE_RISING_UP_MS)
|
||||
#define SEA_TO_AIR_RISING_DURATION_MS 9000UL
|
||||
|
||||
#define START_UP_SEA_TO_DECK_ROTATION_MS (START_UP_SEA_TO_AIR_RISING_MS + SEA_TO_AIR_RISING_DURATION_MS)
|
||||
#define SEA_TO_DECK_ROTATION_DURATION_MS 3000UL
|
||||
|
||||
|
||||
#define START_UP_AIR_TO_DECK_FALLING_MS (START_UP_SEA_TO_DECK_ROTATION_MS + SEA_TO_DECK_ROTATION_DURATION_MS)
|
||||
#define AIR_TO_DECK_FALLING_DURATION_MS 3000UL
|
||||
|
||||
/********************************************************************************************************************/
|
||||
/* STEP #7: Declare here the percentage of motion to be performed at half speed for servo start up and stop */
|
||||
/********************************************************************************************************************/
|
||||
#define START_STOP_PER_CENT 5L /* Percentage of motion performed at half speed for servo start and servo stop (Soft start and Soft stop) */
|
||||
/* Note: due to the lack of programm memory on the DigiSpark, this feature is not used */
|
||||
|
||||
/************************************************************************************************************/
|
||||
/* STEP #11: Use a "SequenceSt_t" structure table to declare the servo sequence */
|
||||
/* For each table entry, arguments are: */
|
||||
/* - Servo Index */
|
||||
/* - Initial Servo Position in ° */
|
||||
/* - Final Servo Position in ° */
|
||||
/* - Motion Start Time Stamp in ms */
|
||||
/* - Motion duration in ms between initial and final position */
|
||||
/* - Percentage of motion performed at half speed for servo start and servo stop (Soft start and Soft stop) */
|
||||
/* Note: START_STOP_PER_CENT not used (MOTION_WITHOUT_SOFT_START_AND_STOP() macro used) */
|
||||
/************************************************************************************************************/
|
||||
SequenceSt_t ZodiacSequence[] PROGMEM = {
|
||||
SHORT_ACTION_TO_PERFORM(ToggleLed, START_UP_DECK_TO_AIR_MS) /* Switch ON the Led at the beginning of the sequence */
|
||||
SHORT_ACTION_TO_PERFORM(ToggleLed, START_UP_AIR_TO_DECK_FALLING_MS+AIR_TO_DECK_FALLING_DURATION_MS) /* Switch OFF the Led at the beginning of the sequence: You are not obliged to put this line at the end of the table */
|
||||
/* 1) The crane lifts the pneumatic Zodiac from the deck to the air and stops */
|
||||
MOTION_WITHOUT_SOFT_START_AND_STOP(UP_DOWN_SERVO, UP_DOWN_ON_DECK_POS, UP_DOWN_ON_AIR_POS, START_UP_DECK_TO_AIR_MS, DECK_TO_AIR_DURATION_MS)
|
||||
/* 2) The crane rotates (90°) to locate the pneumatic Zodiac above the sea */
|
||||
MOTION_WITHOUT_SOFT_START_AND_STOP(ROTATION_SERVO, ROTATION_ABOVE_DECK_POS, ROTATION_ABOVE_SEA_POS, START_UP_DECK_TO_SEA_ROTATION_MS, DECK_TO_SEA_ROTATION_DURATION_MS)
|
||||
/* 3) The crane drops down the pneumatic Zodiac at sea level */
|
||||
MOTION_WITHOUT_SOFT_START_AND_STOP(UP_DOWN_SERVO, UP_DOWN_ON_AIR_POS, UP_DOWN_ON_SEA_POS, START_UP_AIR_TO_SEA_FALLING_MS, AIR_TO_SEA_FALLING_DURATION_MS)
|
||||
/* 4) The crane stops during 6 seconds and 5) The crane lifts up the pneumatic Zodiac from sea level to the air and stops */
|
||||
MOTION_WITHOUT_SOFT_START_AND_STOP(UP_DOWN_SERVO, UP_DOWN_ON_SEA_POS, UP_DOWN_ON_AIR_POS, START_UP_SEA_TO_AIR_RISING_MS, SEA_TO_AIR_RISING_DURATION_MS)
|
||||
/* 6) The crane rotates (90°) to locate the pneumatic Zodiac above the deck */
|
||||
MOTION_WITHOUT_SOFT_START_AND_STOP(ROTATION_SERVO, ROTATION_ABOVE_SEA_POS, ROTATION_ABOVE_DECK_POS, START_UP_SEA_TO_DECK_ROTATION_MS, SEA_TO_DECK_ROTATION_DURATION_MS)
|
||||
/* 7) The crane drops down the pneumatic Zodiac on the deck and stops. The sequence ends. */
|
||||
MOTION_WITHOUT_SOFT_START_AND_STOP(UP_DOWN_SERVO, UP_DOWN_ON_AIR_POS, UP_DOWN_ON_DECK_POS, START_UP_AIR_TO_DECK_FALLING_MS, AIR_TO_DECK_FALLING_DURATION_MS)
|
||||
};
|
||||
|
||||
void setup()
|
||||
{
|
||||
pinMode(LED_PIN, OUTPUT);
|
||||
|
||||
DigiUSB.begin();
|
||||
|
||||
/***************************************************************************/
|
||||
/* STEP #9: Init <RcSeq> library */
|
||||
/***************************************************************************/
|
||||
RcSeq_Init();
|
||||
|
||||
/****************************************************************************************/
|
||||
/* STEP #10: declare the servo command signals with their digital pin number */
|
||||
/****************************************************************************************/
|
||||
RcSeq_DeclareServo(UP_DOWN_SERVO, UP_DOWN_SERVO_PIN);
|
||||
RcSeq_DeclareServo(ROTATION_SERVO, ROTATION_SERVO_PIN);
|
||||
|
||||
/**************************************************************************************************************************/
|
||||
/* STEP #11: declare the sequence command signal (0), the stick level (0), and the sequence to call */
|
||||
/**************************************************************************************************************************/
|
||||
RcSeq_DeclareCommandAndSequence(0, 0, RC_SEQUENCE(ZodiacSequence)); /* 0,0 since there's no RC command */
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
char RxChar;
|
||||
|
||||
/***********************************************************************************************************************************/
|
||||
/* STEP #12: call the refresh function inside the loop() to catch RC commands and to manage the servo positions */
|
||||
/***********************************************************************************************************************************/
|
||||
RcSeq_Refresh();
|
||||
|
||||
/****************************************************************************************************************/
|
||||
/* STEP #13: the sequence can be launched directly by calling the RcSeq_LaunchSequence() function */
|
||||
/****************************************************************************************************************/
|
||||
if(DigiUSB.available())
|
||||
{
|
||||
RxChar=DigiUSB.read();
|
||||
if(RxChar=='g') /* Go ! */
|
||||
{
|
||||
RcSeq_LaunchSequence(ZodiacSequence);
|
||||
}
|
||||
if(RxChar=='t') /* Toggle LED ! */
|
||||
{
|
||||
RcSeq_LaunchShortAction(ToggleLed); /* You can toggle LED during Servo Motion! */
|
||||
}
|
||||
}
|
||||
DigiUSB.refresh();
|
||||
}
|
||||
|
||||
static void ToggleLed(void)
|
||||
{
|
||||
static boolean Status=LOW;
|
||||
Status=!Status; /* Toggle Status */
|
||||
digitalWrite(LED_PIN, Status);
|
||||
}
|
@@ -0,0 +1,123 @@
|
||||
#include <RcSeq.h>
|
||||
#include <TinyPinChange.h>
|
||||
#include <SoftRcPulseIn.h>
|
||||
#include <SoftRcPulseOut.h>
|
||||
|
||||
/*
|
||||
This sketch demonstrates how to easily transform a proportionnal RC channel into 5 digital commands with an ATtiny85.
|
||||
RC Navy (2013)
|
||||
http://P.loussouarn.free.fr
|
||||
|
||||
COMMMAND OF 5 digital outputs from 5 push button replacing a potentiometer in the RC transmitter:
|
||||
================================================================================================
|
||||
Output pins: #1, #2, #3, #4, #5 of an ATtiny85 or a Digispark
|
||||
The receiver output channel is connected to pin#0 of an ATtiny85 or a Digispark
|
||||
A furtive pressure on the push button on the transmitter toggles the corresponding output on the ATtiny85 or a Digispark
|
||||
connected to the receiver output channel.
|
||||
Version with RcSeq library inspired by: http://bateaux.trucs.free.fr/huit_sorties.html
|
||||
|
||||
Modification at RC Transmitter side:
|
||||
===================================
|
||||
Custom keyboard with push buttons
|
||||
=================================
|
||||
Stick Potentiometer 1K 1K 1K 1K 1K 1K
|
||||
=================== .--###---+---###---+---###---+---###---+---###---+---###---.
|
||||
.-. .--. .-. | _.| _.| _.| _.| _.| |
|
||||
|O|--' | |O|-' PB1 |_| PB2 |_| PB3 |_| PB4 |_| PB5 |_| | PB# = Push Button #
|
||||
| | # Replaced with | | '| '| '| '| '| |
|
||||
|O|----># ============> |O|----------+---------+---------+---------+---------+---###---+
|
||||
| | # | | 100K |
|
||||
|O|-- | |O|------------------------------------------------------------'
|
||||
'-' '--' '-'
|
||||
|
||||
|
||||
At RC Receiver side: (The following sketch is related to this ATtiny85 or Digispark)
|
||||
===================
|
||||
|
||||
.---------------.
|
||||
| |
|
||||
| ,------+------.
|
||||
| | VDD |1
|
||||
| | +-- LED, Relay, etc...
|
||||
| | |
|
||||
| | |2
|
||||
| | +-- LED, Relay, etc...
|
||||
| | |
|
||||
| | ATtiny85 |3
|
||||
| | or +-- LED, Relay, etc...
|
||||
.------------. | | Digispark |
|
||||
| |-----' 0| |4
|
||||
| Channel#1|--------------+ +-- LED, Relay, etc...
|
||||
| |-----. | |
|
||||
| RC | | | |5
|
||||
| RECEIVER | | | +-- LED, Relay, etc...
|
||||
| | | | GND |
|
||||
| |- | '------+------'
|
||||
| Channel#2|- | |
|
||||
| |- '---------------'
|
||||
'------------'
|
||||
|
||||
Note:
|
||||
====
|
||||
- Decoupling capacitors are not drawn.
|
||||
- This sketch can easily be extended to 8 outputs by using an ATtiny84 which has more pins.
|
||||
- This sketch cannot work if you are using DigiUSB library as this one monopolizes the "pin change interrupt vector" (which is very time sensitive).
|
||||
- On the other side, its possible to communicate with exterior world by using <SoftSerial>, a library mainly derived from <SoftwareSerial>, but which
|
||||
allow to share the pin change interrupt vector through the <TinyPinChange> library.
|
||||
|
||||
================================================================================================*/
|
||||
|
||||
/* Channel Declaration */
|
||||
enum {RC_CHANNEL, RC_CHANNEL_NB}; /* Here, as there is a single channel, we could used a simple "#define RC_CHANNEL 0" rather an enumeration */
|
||||
|
||||
//==============================================================================================
|
||||
/* Channel Signal of the Receiver */
|
||||
#define RX_CHANNEL_SIGNAL_PIN 0
|
||||
|
||||
//==============================================================================================
|
||||
/* Declaration of the custom keyboard": the pulse width of the push buttons do not need to be equidistant */
|
||||
enum {PUSH_BUTTON1, PUSH_BUTTON2, PUSH_BUTTON3, PUSH_BUTTON4, PUSH_BUTTON5, PUSH_BUTTON_NBR};
|
||||
#define TOLERANCE 40 /* Tolerance +/- (in microseconds): CAUTION, no overlap allowed between 2 adjacent active areas . active area width = 2 x TOLERANCE (us) */
|
||||
KeyMap_t CustomKeyboard[] PROGMEM ={ {CENTER_VALUE_US(1100,TOLERANCE)}, /* PUSH_BUTTON1: +/-40 us */
|
||||
{CENTER_VALUE_US(1300,TOLERANCE)}, /* PUSH_BUTTON2: +/-40 us */
|
||||
{CENTER_VALUE_US(1500,TOLERANCE)}, /* PUSH_BUTTON3: +/-40 us */
|
||||
{CENTER_VALUE_US(1700,TOLERANCE)}, /* PUSH_BUTTON4: +/-40 us */
|
||||
{CENTER_VALUE_US(1900,TOLERANCE)}, /* PUSH_BUTTON5: +/-40 us */
|
||||
};
|
||||
|
||||
//==============================================================================================
|
||||
/* Trick: a macro to write a single time the ToggleAction#() function */
|
||||
#define DECLARE_TOGGLE_ACTION(Idx) \
|
||||
void ToggleAction##Idx(void) \
|
||||
{ \
|
||||
static boolean Etat=HIGH; \
|
||||
digitalWrite(Idx, Etat); \
|
||||
Etat=!Etat; \
|
||||
}
|
||||
|
||||
/* Declaration of the actions using the DECLARE_TOGGLE_ACTION(Idx) macro with Idx = The number of the action and the pin number (The ##Idx will be automatically replaced with the Idx value */
|
||||
DECLARE_TOGGLE_ACTION(1)
|
||||
DECLARE_TOGGLE_ACTION(2)
|
||||
DECLARE_TOGGLE_ACTION(3)
|
||||
DECLARE_TOGGLE_ACTION(4)
|
||||
DECLARE_TOGGLE_ACTION(5)
|
||||
|
||||
//==============================================================================================
|
||||
void setup()
|
||||
{
|
||||
RcSeq_Init();
|
||||
RcSeq_DeclareSignal(RC_CHANNEL, RX_CHANNEL_SIGNAL_PIN); /* RC_CHANNEL Channel is assigned to RX_CHANNEL_SIGNAL_PIN pin */
|
||||
RcSeq_DeclareCustomKeyboard(RC_CHANNEL, RC_CUSTOM_KEYBOARD(CustomKeyboard)); /* The CustomKeyboard map is assigned to the RC_CHANNEL Channel */
|
||||
RcSeq_DeclareCommandAndShortAction(RC_CHANNEL, PUSH_BUTTON1, ToggleAction1);pinMode(1,OUTPUT); /* The ToggleAction1 is assigned to the PUSH_BUTTON1 push button #1 */
|
||||
RcSeq_DeclareCommandAndShortAction(RC_CHANNEL, PUSH_BUTTON2, ToggleAction2);pinMode(2,OUTPUT); /* The ToggleAction2 is assigned to the PUSH_BUTTON1 push button #2 */
|
||||
RcSeq_DeclareCommandAndShortAction(RC_CHANNEL, PUSH_BUTTON3, ToggleAction3);pinMode(3,OUTPUT); /* The ToggleAction3 is assigned to the PUSH_BUTTON1 push button #3 */
|
||||
RcSeq_DeclareCommandAndShortAction(RC_CHANNEL, PUSH_BUTTON4, ToggleAction4);pinMode(4,OUTPUT); /* The ToggleAction4 is assigned to the PUSH_BUTTON1 push button #4 */
|
||||
RcSeq_DeclareCommandAndShortAction(RC_CHANNEL, PUSH_BUTTON5, ToggleAction5);pinMode(5,OUTPUT); /* The ToggleAction5 is assigned to the PUSH_BUTTON1 push button #5 */
|
||||
}
|
||||
//==============================================================================================
|
||||
void loop()
|
||||
{
|
||||
RcSeq_Refresh(); /* This function performs all the needed job asynchronously (non blocking) */
|
||||
}
|
||||
//============================ END OF SKETCH =================================================
|
||||
|
@@ -0,0 +1,140 @@
|
||||
/*
|
||||
Ce sketch de demo de la librairie RcSeq montre comment configurer tres facilement la commande d'actions ou de sequences de servo predefinies.
|
||||
La commande peut etre:
|
||||
- un manche de l'emetteur RC avec possibilité de definir jusqu'a 8 positions "actives" (le nombre de position doit etre pair: neutre au milieu)
|
||||
- un clavier: un montage resistances/boutons-poussoirs remplacant le potentiometre du manche d'un emetteur RC
|
||||
(les resistances doivent etre d'egales valeurs avec une 2 resistances identiques "au centre/neutre" pour la zone inactive)
|
||||
- un clavier "maison": un montage resistances/boutons-poussoirs remplacant le potentiometre du manche d'un emetteur RC avec des resistances pas forcement identiques
|
||||
(la largeur d'impulsion pour chaque bouton-poussoir est define dans une table, une tolerance est egalement prevue)
|
||||
Les 3 exemples sont traites dans ce sketch de demo.
|
||||
*/
|
||||
#include <RcSeq.h>
|
||||
#include <TinyPinChange.h> /* Ne pas oublier d'inclure la librairie <TinyPinChange> qui est utilisee par la librairie <RcSeq> */
|
||||
#include <SoftRcPulseIn.h> /* Ne pas oublier d'inclure la librairie <SoftRcPulseIn> qui est utilisee par la librairie <RcSeq> */
|
||||
#include <SoftRcPulseOut.h> /* Ne pas oublier d'inclure la librairie <SoftRcPulseOut> qui est utilisee par la librairie <RcSeq> */
|
||||
|
||||
enum {RC_VOIE1, RC_VOIE2, RC_VOIE3, NBR_VOIES_RC}; /* Declaration des voies */
|
||||
|
||||
enum {BP1, BP2, NBR_BP}; /* Declaration des Boutons-Poussoirs (On peut aller jusqu'à BP8) */
|
||||
|
||||
enum {POS_MINUS1, POS_PLUS1,NBR_POS}; /* Declaration des positions du Manche on peut aller de POS_MOINS2 à POS_PLUS2 (4 Positions actives Max)*/
|
||||
|
||||
|
||||
/* Declaration d'un clavier "Maison": les impulsions des Boutons-Poussoirs n'ont pas besoin d'etre equidistantes */
|
||||
enum {BP_MAISON1, BP_MAISON2, BP_MAISON3, NBR_BP_MAISON};
|
||||
#define TOLERANCE 40 /* Tolerance en + ou en - (en micro-seconde) */
|
||||
KeyMap_t ClavierMaison[] PROGMEM ={ {VALEUR_CENTRALE_US(1100,TOLERANCE)}, /* BP_MAISON1: 1100 +/-40 us */
|
||||
{VALEUR_CENTRALE_US(1300,TOLERANCE)}, /* BP_MAISON2: 1300 +/-40 us */
|
||||
{VALEUR_CENTRALE_US(1700,TOLERANCE)}, /* BP_MAISON3: 1700 +/-40 us */
|
||||
};
|
||||
|
||||
enum {AZIMUT=0, ELEVATION , NBR_SERVO}; /* Delaration de tous les servos, 2 dans cet exemple (On peut déclaer jusqu'à 8 servos) */
|
||||
|
||||
/* Declaration des broches reliees aux sorties du recepteur RC */
|
||||
#define BROCHE_SIGNAL_RECEPTEUR_VOIE1 8
|
||||
#define BROCHE_SIGNAL_RECEPTEUR_VOIE2 2
|
||||
#define BROCHE_SIGNAL_RECEPTEUR_VOIE3 9
|
||||
|
||||
/* Declaration des broches de commande des servos */
|
||||
#define BROCHE_SIGNAL_SERVO_EL 3
|
||||
#define BROCHE_SIGNAL_SERVO_AZ 4
|
||||
|
||||
/* Declaration des differents angles des servos */
|
||||
#define ELEVATION_POS_PONT 120 /* position zodiac sur pont (Pos A) */
|
||||
#define ELEVATION_POS_HAUT 180 /* position zodiac en haut (Pos B) */
|
||||
#define ELEVATION_POS_MER 0 /* position zodiac dans l'eau (pos C) */
|
||||
|
||||
#define AZIMUT_POS_PONT 90 /* position rotation sur pont */
|
||||
#define AZIMUT_POS_MER 0 /* position rotation sur mer */
|
||||
|
||||
/* Declaration des moments de demarrage ainsi que la duree des mouvement de servo */
|
||||
#define DEMARRAGE_MONTEE_PONT_HAUT_MS 0L /* 0 pour demarrage immediat, mais on peut mettre une tempo ici. Ex 2000L, va differer la sequence complete de 2 secondes */
|
||||
#define DUREE_MONTEE_PONT_HAUT_MS 3000L
|
||||
|
||||
#define DEMARRAGE_ROTATION_PONT_MER_MS (DEMARRAGE_MONTEE_PONT_HAUT_MS+DUREE_MONTEE_PONT_HAUT_MS)
|
||||
#define DUREE_ROTATION_PONT_MER_MS 3000L
|
||||
|
||||
#define DEMARRAGE_DESCENTE_HAUT_MER_MS (DEMARRAGE_ROTATION_PONT_MER_MS+DUREE_ROTATION_PONT_MER_MS)
|
||||
#define DUREE_DESCENTE_HAUT_MER_MS 9000L
|
||||
|
||||
#define ATTENTE_AVANT_REMONTEE_MS 6000L /* Exemple d'utilisation d'une temporisation */
|
||||
|
||||
#define DEMARRAGE_MONTEE_MER_HAUT_MS (DEMARRAGE_DESCENTE_HAUT_MER_MS+DUREE_DESCENTE_HAUT_MER_MS+ATTENTE_AVANT_REMONTEE_MS)
|
||||
#define DUREE_MONTEE_MER_HAUT_MS 9000L
|
||||
|
||||
#define DEMARRAGE_ROTATION_MER_PONT_MS (DEMARRAGE_MONTEE_MER_HAUT_MS+DUREE_MONTEE_MER_HAUT_MS)
|
||||
#define DUREE_ROTATION_MER_PONT_MS 3000L
|
||||
|
||||
|
||||
#define DEMARRAGE_DESCENTE_HAUT_PONT_MS (DEMARRAGE_ROTATION_MER_PONT_MS+DUREE_ROTATION_MER_PONT_MS)
|
||||
#define DUREE_DESCENTE_HAUT_PONT_MS 3000L
|
||||
|
||||
#define DEM_ARRET_POUR_CENT 5 /* Pourcentage du mouvement devant etre effectue a mi-vitesse pour demarrage servo et arret servo (Soft start et Soft stop) */
|
||||
|
||||
/* Declaration de la table de sequence des mouvements des servo et des actions courtes */
|
||||
SequenceSt_t SequenceServoEtActionCourte[] PROGMEM = {
|
||||
ACTION_COURTE_A_EFFECTUER(InverseLed,DEMARRAGE_MONTEE_PONT_HAUT_MS)
|
||||
/* Montee du Zodiac du pont vers la position haute */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(ELEVATION,ELEVATION_POS_PONT,ELEVATION_POS_HAUT,DEMARRAGE_MONTEE_PONT_HAUT_MS,DUREE_MONTEE_PONT_HAUT_MS,DEM_ARRET_POUR_CENT)
|
||||
/* Rotation Grue du pont vers la mer */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(AZIMUT,AZIMUT_POS_PONT,AZIMUT_POS_MER,DEMARRAGE_ROTATION_PONT_MER_MS,DUREE_ROTATION_PONT_MER_MS,DEM_ARRET_POUR_CENT)
|
||||
/* Descente du Zodiac depuis la position haute vers la la mer */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(ELEVATION,ELEVATION_POS_HAUT,ELEVATION_POS_MER,DEMARRAGE_DESCENTE_HAUT_MER_MS,DUREE_DESCENTE_HAUT_MER_MS,DEM_ARRET_POUR_CENT)
|
||||
ACTION_COURTE_A_EFFECTUER(InverseLed,DEMARRAGE_DESCENTE_HAUT_MER_MS+DUREE_DESCENTE_HAUT_MER_MS)
|
||||
ACTION_COURTE_A_EFFECTUER(InverseLed,DEMARRAGE_MONTEE_MER_HAUT_MS)
|
||||
/* Montee du Zodiac de la mer vers la position haute */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(ELEVATION,ELEVATION_POS_MER,ELEVATION_POS_HAUT,DEMARRAGE_MONTEE_MER_HAUT_MS,DUREE_MONTEE_MER_HAUT_MS,DEM_ARRET_POUR_CENT)
|
||||
/* Rotation Grue de la mer vers le pont */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(AZIMUT,AZIMUT_POS_MER,AZIMUT_POS_PONT,DEMARRAGE_ROTATION_MER_PONT_MS,DUREE_ROTATION_MER_PONT_MS,DEM_ARRET_POUR_CENT)
|
||||
/* Descente du Zodiac de la position haute vers le pont */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(ELEVATION,ELEVATION_POS_HAUT,ELEVATION_POS_PONT,DEMARRAGE_DESCENTE_HAUT_PONT_MS,DUREE_DESCENTE_HAUT_PONT_MS,DEM_ARRET_POUR_CENT)
|
||||
ACTION_COURTE_A_EFFECTUER(InverseLed,DEMARRAGE_DESCENTE_HAUT_PONT_MS+DUREE_DESCENTE_HAUT_PONT_MS)
|
||||
};
|
||||
|
||||
#define LED 13
|
||||
|
||||
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("RcSeq library V");Serial.print(RcSeq_LibTextVersionRevision());Serial.print(" demo: RcSeqDemo");
|
||||
#endif
|
||||
RcSeq_Init();
|
||||
|
||||
/* Declaration des Servos */
|
||||
RcSeq_DeclareServo(ELEVATION, BROCHE_SIGNAL_SERVO_EL);
|
||||
RcSeq_DeclareServo(AZIMUT, BROCHE_SIGNAL_SERVO_AZ);
|
||||
|
||||
/* Commande d'une action courte et d'une sequence de servos avec 2 BP du clavier de la VOIE1 */
|
||||
RcSeq_DeclareSignal(RC_VOIE1,BROCHE_SIGNAL_RECEPTEUR_VOIE1);
|
||||
RcSeq_DeclareClavier(RC_VOIE1, 1000, 2000, NBR_BP);
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE1, BP1, InverseLed);
|
||||
RcSeq_DeclareCommandeEtSequence(RC_VOIE1, BP2, RC_SEQUENCE(SequenceServoEtActionCourte));
|
||||
|
||||
/* Commande d'une action courte et d'une sequence de servos avec le manche de la VOIE2 */
|
||||
RcSeq_DeclareSignal(RC_VOIE2,BROCHE_SIGNAL_RECEPTEUR_VOIE2);
|
||||
RcSeq_DeclareManche(RC_VOIE2, 1000, 2000, NBR_POS);
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE2, POS_MINUS1, InverseLed);
|
||||
RcSeq_DeclareCommandeEtSequence(RC_VOIE2, POS_PLUS1, RC_SEQUENCE(SequenceServoEtActionCourte));
|
||||
|
||||
/* Commande d'une action courte et d'une sequence de servos avec le clavier "maison" de la VOIE3 */
|
||||
RcSeq_DeclareSignal(RC_VOIE3,BROCHE_SIGNAL_RECEPTEUR_VOIE3);
|
||||
RcSeq_DeclareClavierMaison(RC_VOIE3, RC_CLAVIER_MAISON(ClavierMaison));
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE3, BP_MAISON1, InverseLed);
|
||||
RcSeq_DeclareCommandeEtSequence(RC_VOIE3, BP_MAISON3, RC_SEQUENCE(SequenceServoEtActionCourte));
|
||||
|
||||
pinMode(LED, OUTPUT);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
RcSeq_Rafraichit();
|
||||
}
|
||||
|
||||
/* Action associee au BP1 de la VOIE1 ou au manche position basse de la VOIE2 ou au BP_MAISON1 de la VOIE3 */
|
||||
void InverseLed(void)
|
||||
{
|
||||
static boolean Etat=HIGH; /* static, pour conserver l'etat entre 2 appels de la fonction */
|
||||
digitalWrite(LED, Etat);
|
||||
Etat=!Etat; /* AU prochain appel de InverseLed(), l'etat de la LED sera inverse */
|
||||
}
|
@@ -0,0 +1,218 @@
|
||||
/*
|
||||
IMPORTANT:
|
||||
=========
|
||||
La librairie "RcSeq" utilise la technique de programmation dite "asynchrone", c'est-a-dire qu'aucun appel a des fonctions bloquantes telles que la fonction delay()
|
||||
ou la fonction pulseIn() n'est effectue.
|
||||
Ceci se traduit par un temps de boucle principale inferieur a 70 micro-secondes bien que les servos soient rafraichis toutes les 20ms a l'aide de la methode
|
||||
Rafraichit() qui doit etre appelee dans la fonction loop(). Cela laisse donc enormement de temps au micro-controleur pour faire "en meme temps" d'autres taches.
|
||||
Par exemple dans ce sketch, il est possible d'envoyer la commande 'i' via la serial console pour inverser l'etat de la LED connectee a la pin digitale 13 pendant
|
||||
que les servos sont en mouvement.
|
||||
|
||||
Ce sketch illustre l'utilisation de la librairie "RcSeq" qui permet de sequencer tres facilement des servos et des actions courtes a l'aide de la librairie "SoftwareServo".
|
||||
Les actions courtes doivent durer moins de 20ms pour ne pas perturber la commande des servos.
|
||||
Si ce sketch est charge dans une carte UNO, il est possible de lancer la sequence en tapant 'g' puis Entree dans la serial console de l'EDI Arduino.
|
||||
En tapant 'i' puis Entree, l'action InverseLed() est executee. Comme "RcSeq" est asynchrone, il est possible de le faire pendant que les servos tournent.
|
||||
La possibilite de lancer les sequence et action courte via la serial console evite de sortir et cabler l'ensemble RC pour lancer la sequence et l'action.
|
||||
|
||||
Dans cet exemple, la sequence declaree est la mise a l'eau d'un Zodiac avec une grue depuis un bateau de service type baliseur:
|
||||
1) La grue souleve le Zodiac en position haute puis s'arrete
|
||||
2) La grue fait une rotation de 90° pour positionner le Zodiac au dessus de l'eau
|
||||
3) La grue descend le Zodiac au niveau de l'eau
|
||||
4) La grue reste sans action pendant 6 secondes
|
||||
5) La grue remonte le Zodiac en position haute puis s'arrete
|
||||
6) La grue fait une rotation de 90° pour positionner le Zodiac au dessus du pont
|
||||
7) La grue descend le Zodiac en position basse puis s'arrete. La sequence est terminee.
|
||||
Cette sequence utilise:
|
||||
- 2 commande RC sur le meme manche (Impulsion d'au moins 1/4 de seconde en position mi-course pour l'action courte et extreme pour la sequnce avec le manche de l'emetteur RC)
|
||||
ou la commande 'i' ou 'g' depuis la serial console de l'EDI Arduino
|
||||
- 2 servos (un servo "Azimut" pour les rotations et un servo "Elevation" pour la montee/descente)
|
||||
*/
|
||||
|
||||
/***************************************************/
|
||||
/* ETAPE N°1: Inclure les 4 librairies necessaires */
|
||||
/***************************************************/
|
||||
#include <RcSeq.h>
|
||||
#include <TinyPinChange.h> /* Ne pas oublier d'inclure la librairie <TinyPinChange> qui est utilisee par la librairie <RcSeq> */
|
||||
#include <SoftRcPulseIn.h> /* Ne pas oublier d'inclure la librairie <SoftRcPulseIn> qui est utilisee par la librairie <RcSeq> */
|
||||
#include <SoftRcPulseOut.h> /* Ne pas oublier d'inclure la librairie <SoftRcPulseOut> qui est utilisee par la librairie <RcSeq> */
|
||||
|
||||
/*****************************************************/
|
||||
/* ETAPE N°2: Enumeration des signaux de commande RC */
|
||||
/*****************************************************/
|
||||
enum {SIGNAL_RC=0, NBR_SIGNAL}; /* Delaration de tous les signaux de commande (sortie voie du recepteur), un seul dans cet exemple */
|
||||
|
||||
/****************************************************************/
|
||||
/* ETAPE N°3: Enumeration des differentes position du manche RC */
|
||||
/****************************************************************/
|
||||
enum {RC_IMPULSION_NIVEAU_MOINS_2, RC_IMPULSION_NIVEAU_MOINS_1, RC_IMPULSION_NIVEAU_PLUS_1, RC_IMPULSION_NIVEAU_PLUS_2, NBR_RC_IMPULSIONS};
|
||||
|
||||
/*****************************************************************/
|
||||
/* ETAPE N°4: Enumeration des servos utilisés pour les sequences */
|
||||
/*****************************************************************/
|
||||
enum {AZIMUT=0, ELEVATION , NBR_SERVO}; /* Delaration de tous les servos, 2 dans cet exemple */
|
||||
|
||||
/*********************************************************************************/
|
||||
/* ETAPE N°5: Affectation des broches Digitales (PIN) des signaux de commande RC */
|
||||
/*********************************************************************************/
|
||||
#define BROCHE_SIGNAL_RECEPTEUR 2
|
||||
|
||||
/*****************************************************************************************/
|
||||
/* ETAPE N°6: Affectation des broches Digitales (PIN) des signaux de commande des servos */
|
||||
/*****************************************************************************************/
|
||||
#define BROCHE_SIGNAL_SERVO_EL 3
|
||||
#define BROCHE_SIGNAL_SERVO_AZ 4
|
||||
|
||||
/**************************************************************************************/
|
||||
/* ETAPE N°7: Declaration des angles des servos pour les differents mouvements (en °) */
|
||||
/**************************************************************************************/
|
||||
#define ELEVATION_POS_PONT 120 /* position zodiac sur pont (Pos A) */
|
||||
#define ELEVATION_POS_HAUT 180 /* position zodiac en haut (Pos B) */
|
||||
#define ELEVATION_POS_MER 0 /* position zodiac dans l'eau (pos C) */
|
||||
|
||||
#define AZIMUT_POS_PONT 90 /* position rotation sur pont */
|
||||
#define AZIMUT_POS_MER 0 /* position rotation sur mer */
|
||||
|
||||
|
||||
/***************************************************************************************************************************************/
|
||||
/* ETAPE N°8: Faire un croquis temporel faisant apparaitre les moments de demarrages et les duree des mouvements des differents servos */
|
||||
/***************************************************************************************************************************************/
|
||||
/*
|
||||
Toutes les valeurs de demarrage ont comme reference le moment de l'ordre de demarrage de sequence (t=0).
|
||||
|
||||
MOUVEMENT SERVO ELEVATION MOUVEMENT SERVO AZIMUT MOUVEMENT SERVO ELEVATION AUCUN MOUVEMENT(ATTENTE) MOUVEMENT SERVO ELEVATION MOUVEMENT SERVO AZIMUT MOUVEMENT SERVO ELEVATION
|
||||
Ordre <---DUREE_MONTEE_PONT_HAUT_MS--> <--DUREE_ROTATION_PONT_MER_MS----> <--DUREE_DESCENTE_HAUT_MER_MS--><--ATTENTE_AVANT_REMONTEE_MS--><---DUREE_MONTEE_MER_HAUT_MS---><----DUREE_ROTATION_MER_PONT_MS-----><--DUREE_DESCENTE_HAUT_PONT_MS-->
|
||||
|-------------------|--------------------------------|----------------------------------|--------------------------------|------------------------------|-------------------------------|------------------------------------|--------------------------------|-->Axe du Temps
|
||||
0 DEMARRAGE_MONTEE_PONT_HAUT_MS DEMARRAGE_ROTATION_PONT_MER_MS DEMARRAGE_DESCENTE_HAUT_MER_MS DEMARRAGE_MONTEE_MER_HAUT_MS DEMARRAGE_ROTATION_MER_PONT_MS DEMARRAGE_DESCENTE_HAUT_PONT_MS
|
||||
*/
|
||||
|
||||
/**************************************************************************************************************************************************/
|
||||
/* ETAPE N°9: A l'aide du croquis temporel, declarer les moments de demarrage, les durees des movement de servo et les eventuelles temporisations */
|
||||
/**************************************************************************************************************************************************/
|
||||
/* Regler ci-dessous les temps de mouvement en ms. Ne pas oulier de d'ajouter un 'L' a la fin de la valeur pour forcer les valeurs en type Long */
|
||||
#define DEMARRAGE_MONTEE_PONT_HAUT_MS 0L /* 0 pour demarrage immediat, mais on peut mettre une tempo ici. Ex 2000L, va differer la sequence complete de 2 secondes */
|
||||
#define DUREE_MONTEE_PONT_HAUT_MS 3000L
|
||||
|
||||
#define DEMARRAGE_ROTATION_PONT_MER_MS (DEMARRAGE_MONTEE_PONT_HAUT_MS+DUREE_MONTEE_PONT_HAUT_MS)
|
||||
#define DUREE_ROTATION_PONT_MER_MS 3000L
|
||||
|
||||
#define DEMARRAGE_DESCENTE_HAUT_MER_MS (DEMARRAGE_ROTATION_PONT_MER_MS+DUREE_ROTATION_PONT_MER_MS)
|
||||
#define DUREE_DESCENTE_HAUT_MER_MS 9000L
|
||||
|
||||
#define ATTENTE_AVANT_REMONTEE_MS 6000L /* Exemple d'utilisation d'une temporisation */
|
||||
|
||||
#define DEMARRAGE_MONTEE_MER_HAUT_MS (DEMARRAGE_DESCENTE_HAUT_MER_MS+DUREE_DESCENTE_HAUT_MER_MS+ATTENTE_AVANT_REMONTEE_MS)
|
||||
#define DUREE_MONTEE_MER_HAUT_MS 9000L
|
||||
|
||||
#define DEMARRAGE_ROTATION_MER_PONT_MS (DEMARRAGE_MONTEE_MER_HAUT_MS+DUREE_MONTEE_MER_HAUT_MS)
|
||||
#define DUREE_ROTATION_MER_PONT_MS 3000L
|
||||
|
||||
|
||||
#define DEMARRAGE_DESCENTE_HAUT_PONT_MS (DEMARRAGE_ROTATION_MER_PONT_MS+DUREE_ROTATION_MER_PONT_MS)
|
||||
#define DUREE_DESCENTE_HAUT_PONT_MS 3000L
|
||||
|
||||
/********************************************************************************************************************/
|
||||
/* ETAPE N°10: Declarer le pourcentage de mouvement devant etre a mi-vitesse pour les demarrage et arret des servos */
|
||||
/********************************************************************************************************************/
|
||||
#define DEM_ARRET_POUR_CENT 5 /* Pourcentage du mouvement devant etre effectue a mi-vitesse pour demarrage servo et arret servo (Soft start et Soft stop) */
|
||||
|
||||
/***************************************************************************************************************************************************************/
|
||||
/* ETAPE N°11: Dans une structure de type "SequenceSt_t", a l'aide de la macro MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(), declarer le N° de servo, l'angle initial, */
|
||||
/* l'angle final, le moment de demarrage, la duree du mouvement et le pourcentage de mouvement devant etre a mi-vitesse pour les demarrage et arret des servos */
|
||||
/* Il est possible d'inclure des actions courtes. Il suffit d'utiliser la macro ACTION_COURTE_A_EFFECTUER() en donnant le nom de la fonction a appeler et le */
|
||||
/* moment ou l'action doit avoir lieu. Dans cet exemple, la LED s'allume pendant que les servos tournent et s'eteint pendant la pause de 6 secondes. */
|
||||
/***************************************************************************************************************************************************************/
|
||||
SequenceSt_t SequencePlus2[] PROGMEM = {
|
||||
ACTION_COURTE_A_EFFECTUER(InverseLed,DEMARRAGE_MONTEE_PONT_HAUT_MS)
|
||||
/* Montee du Zodiac du pont vers la position haute */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(ELEVATION,ELEVATION_POS_PONT,ELEVATION_POS_HAUT,DEMARRAGE_MONTEE_PONT_HAUT_MS,DUREE_MONTEE_PONT_HAUT_MS,DEM_ARRET_POUR_CENT)
|
||||
/* Rotation Grue du pont vers la mer */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(AZIMUT,AZIMUT_POS_PONT,AZIMUT_POS_MER,DEMARRAGE_ROTATION_PONT_MER_MS,DUREE_ROTATION_PONT_MER_MS,DEM_ARRET_POUR_CENT)
|
||||
/* Descente du Zodiac depuis la position haute vers la la mer */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(ELEVATION,ELEVATION_POS_HAUT,ELEVATION_POS_MER,DEMARRAGE_DESCENTE_HAUT_MER_MS,DUREE_DESCENTE_HAUT_MER_MS,DEM_ARRET_POUR_CENT)
|
||||
ACTION_COURTE_A_EFFECTUER(InverseLed,DEMARRAGE_DESCENTE_HAUT_MER_MS+DUREE_DESCENTE_HAUT_MER_MS)
|
||||
ACTION_COURTE_A_EFFECTUER(InverseLed,DEMARRAGE_MONTEE_MER_HAUT_MS)
|
||||
/* Montee du Zodiac de la mer vers la position haute */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(ELEVATION,ELEVATION_POS_MER,ELEVATION_POS_HAUT,DEMARRAGE_MONTEE_MER_HAUT_MS,DUREE_MONTEE_MER_HAUT_MS,DEM_ARRET_POUR_CENT)
|
||||
/* Rotation Grue de la mer vers le pont */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(AZIMUT,AZIMUT_POS_MER,AZIMUT_POS_PONT,DEMARRAGE_ROTATION_MER_PONT_MS,DUREE_ROTATION_MER_PONT_MS,DEM_ARRET_POUR_CENT)
|
||||
/* Descente du Zodiac de la position haute vers le pont */
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS(ELEVATION,ELEVATION_POS_HAUT,ELEVATION_POS_PONT,DEMARRAGE_DESCENTE_HAUT_PONT_MS,DUREE_DESCENTE_HAUT_PONT_MS,DEM_ARRET_POUR_CENT)
|
||||
ACTION_COURTE_A_EFFECTUER(InverseLed,DEMARRAGE_DESCENTE_HAUT_PONT_MS+DUREE_DESCENTE_HAUT_PONT_MS)
|
||||
};
|
||||
|
||||
#define LED 13
|
||||
|
||||
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("RcSeq library V");Serial.print(RcSeq_LibTextVersionRevision());Serial.print(" demo: RcSeqZodiac");
|
||||
#endif
|
||||
|
||||
/***************************************************************************/
|
||||
/* ETAPE N°12: Appeler la fonction d'initialisation de la libraire "RcSeq" */
|
||||
/***************************************************************************/
|
||||
RcSeq_Init();
|
||||
|
||||
/**************************************************************************************/
|
||||
/* ETAPE N°13: declarer le(s) signal(aux) de commande RC avec leur N° de pin digitale */
|
||||
/**************************************************************************************/
|
||||
RcSeq_DeclareSignal(SIGNAL_RC,BROCHE_SIGNAL_RECEPTEUR);
|
||||
|
||||
/******************************************************************************************/
|
||||
/* ETAPE N°14: que le signal RC est associe a un manche qui a NBR_RC_IMPULSIONS positions */
|
||||
/*****************************************************************************************/
|
||||
RcSeq_DeclareManche(SIGNAL_RC, 1000, 2000, NBR_RC_IMPULSIONS);
|
||||
|
||||
/********************************************************************************************/
|
||||
/* ETAPE N°15: declarer le(s) signal(aux) ce commande de servo avec leur N° de pin digitale */
|
||||
/********************************************************************************************/
|
||||
RcSeq_DeclareServo(ELEVATION, BROCHE_SIGNAL_SERVO_EL);
|
||||
RcSeq_DeclareServo(AZIMUT, BROCHE_SIGNAL_SERVO_AZ);
|
||||
|
||||
/**************************************************************************************************************************/
|
||||
/* ETAPE N°16: declarer le signal de commande de sequence, le niveau du manche, et la sequence ou action courte a appeler */
|
||||
/**************************************************************************************************************************/
|
||||
RcSeq_DeclareCommandeEtSequence(SIGNAL_RC, RC_IMPULSION_NIVEAU_PLUS_2, RC_SEQUENCE(SequencePlus2)); // Voici comment declarer une sequence actionnee par une impulsion Niveau Plus 2 (manche en position extreme pendant au moins 250 ms)
|
||||
|
||||
pinMode(LED, OUTPUT);
|
||||
RcSeq_DeclareCommandeEtActionCourte(SIGNAL_RC, RC_IMPULSION_NIVEAU_MOINS_1, InverseLed); // Voici comment declarer une action actionnee par une impulsion Niveau Moins 1 (manche en position mi-course pendant au moins 250 ms)
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
|
||||
/***********************************************************************************************************************************/
|
||||
/* ETAPE N°17: appeler la fonction Rafraichit dans la fonction loop() pour capter les commandes RC et gerer la position des servos */
|
||||
/***********************************************************************************************************************************/
|
||||
RcSeq_Rafraichit();
|
||||
|
||||
/******************************************************************************************************/
|
||||
/* ETAPE N°18: optionnellement, autoriser le lancement des Sequences ou Actions via la serial console */
|
||||
/******************************************************************************************************/
|
||||
#if !defined(__AVR_ATtiny24__) && !defined(__AVR_ATtiny44__) && !defined(__AVR_ATtiny84__) && !defined(__AVR_ATtiny25__) && !defined(__AVR_ATtiny45__) && !defined(__AVR_ATtiny85__)
|
||||
int RxChar;
|
||||
/* Lance la sequence en envoyant le caractere 'g' dans la serial console: cela permet de tester la sequence de servo avec une carte UNO sans utiliser d'ensemble RC */
|
||||
if(Serial.available() > 0)
|
||||
{
|
||||
RxChar=Serial.read();
|
||||
if(tolower(RxChar)=='g') /* Go ! */
|
||||
{
|
||||
RcSeq_LanceSequence(SequencePlus2);
|
||||
}
|
||||
if(tolower(RxChar)=='i') /* inverse led ! */
|
||||
{
|
||||
RcSeq_LanceActionCourte(InverseLed);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Action associee au manche a mi-course */
|
||||
void InverseLed(void)
|
||||
{
|
||||
static boolean Etat=HIGH; /* static, pour conserver l'etat entre 2 appels de la fonction */
|
||||
digitalWrite(LED, Etat);
|
||||
Etat=!Etat; /* AU prochain appel de InverseLed(), l'etat de la LED sera inverse */
|
||||
}
|
@@ -0,0 +1,76 @@
|
||||
#include <RcSeq.h>
|
||||
#include <TinyPinChange.h> /* Ne pas oublier d'inclure la librairie <TinyPinChange> qui est utilisee par la librairie <RcSeq> */
|
||||
#include <SoftRcPulseIn.h> /* Ne pas oublier d'inclure la librairie <SoftRcPulseIn> qui est utilisee par la librairie <RcSeq> */
|
||||
#include <SoftRcPulseOut.h> /* Ne pas oublier d'inclure la librairie <SoftRcPulseOut> qui est utilisee par la librairie <RcSeq> */
|
||||
|
||||
/*================= COMMMANDE DE 8 SORTIES ON/OFF PAR 8 INTERS POUSSOIR ========================
|
||||
Les 8 relais ou sont connectés aux prise n°1,2,3,4,5,6,7,8 d'un ATtiny84
|
||||
La voie du récepteur est connecté à la prise n°0 de l'ATtiny84
|
||||
Un appui furtif sur un bouton fait actionne le relais correspondant qui reste collé.
|
||||
Un deuxième appui furtif sur le même bouton fait décoller le relais correspondant.
|
||||
Version avec librairie RcSeq d'apres l'exemple de http://bateaux.trucs.free.fr/huit_sorties.html
|
||||
================================================================================================*/
|
||||
|
||||
/* Declaration des voies */
|
||||
enum {RC_VOIE, NBR_VOIES_RC}; /* Ici, comme il n'y a qu'une voie, on aurait pu faire un simple "#define RC_VOIE 0" a la place de l'enumeration */
|
||||
|
||||
//==============================================================================================
|
||||
/* Declaration du signal du recepteur */
|
||||
#define BROCHE_SIGNAL_RECEPTEUR_VOIE 0
|
||||
|
||||
//==============================================================================================
|
||||
/* Declaration d'un clavier "Maison": les impulsions des Boutons-Poussoirs n'ont pas besoin d'etre equidistantes */
|
||||
enum {BP1, BP2, BP3, BP4, BP5, BP6, BP7, BP8, NBR_BP};
|
||||
#define TOLERANCE 40 /* Tolerance en + ou en - (en micro-seconde): ATTENTION, il ne doit pas y avoir recouvrement entre 2 zones actives adjascentes. Zone active = 2 x TOLERANCE (us) */
|
||||
KeyMap_t ClavierMaison[] PROGMEM ={ {VALEUR_CENTRALE_US(1100,TOLERANCE)}, /* BP1: +/-40 us */
|
||||
{VALEUR_CENTRALE_US(1200,TOLERANCE)}, /* BP2: +/-40 us */
|
||||
{VALEUR_CENTRALE_US(1300,TOLERANCE)}, /* BP3: +/-40 us */
|
||||
{VALEUR_CENTRALE_US(1400,TOLERANCE)}, /* BP4: +/-40 us */
|
||||
{VALEUR_CENTRALE_US(1600,TOLERANCE)}, /* BP5: +/-40 us */
|
||||
{VALEUR_CENTRALE_US(1700,TOLERANCE)}, /* BP6: +/-40 us */
|
||||
{VALEUR_CENTRALE_US(1800,TOLERANCE)}, /* BP7: +/-40 us */
|
||||
{VALEUR_CENTRALE_US(1900,TOLERANCE)}, /* BP8: +/-40 us */
|
||||
};
|
||||
|
||||
//==============================================================================================
|
||||
/* Astuce: une macro pour n'ecrire qu'une seule fois la fonction ActionX() */
|
||||
#define DECLARE_ACTION(Idx) \
|
||||
void Action##Idx(void) \
|
||||
{ \
|
||||
static boolean Etat=HIGH; \
|
||||
digitalWrite(Idx, Etat); \
|
||||
Etat=!Etat; \
|
||||
}
|
||||
|
||||
/* Declaration des actions en utilisant la macro DECLARE_ACTION(Idx) avec Idx = le numero de l'action et de la pin (le ##Idx sera remplace automatiquement par la valeur de Idx */
|
||||
DECLARE_ACTION(1)
|
||||
DECLARE_ACTION(2)
|
||||
DECLARE_ACTION(3)
|
||||
DECLARE_ACTION(4)
|
||||
DECLARE_ACTION(5)
|
||||
DECLARE_ACTION(6)
|
||||
DECLARE_ACTION(7)
|
||||
DECLARE_ACTION(8)
|
||||
|
||||
//==============================================================================================
|
||||
void setup()
|
||||
{
|
||||
RcSeq_Init();
|
||||
RcSeq_DeclareSignal(RC_VOIE, BROCHE_SIGNAL_RECEPTEUR_VOIE);
|
||||
RcSeq_DeclareClavierMaison(RC_VOIE, RC_CLAVIER_MAISON(ClavierMaison));
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE, BP1, Action1);pinMode(1,OUTPUT);
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE, BP2, Action2);pinMode(2,OUTPUT);
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE, BP3, Action3);pinMode(3,OUTPUT);
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE, BP4, Action4);pinMode(4,OUTPUT);
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE, BP5, Action5);pinMode(5,OUTPUT);
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE, BP6, Action6);pinMode(6,OUTPUT);
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE, BP7, Action7);pinMode(7,OUTPUT);
|
||||
RcSeq_DeclareCommandeEtActionCourte(RC_VOIE, BP8, Action8);pinMode(8,OUTPUT);
|
||||
}
|
||||
//==============================================================================================
|
||||
void loop()
|
||||
{
|
||||
RcSeq_Rafraichit();
|
||||
}
|
||||
//============================ FIN DU PROGRAMME =================================================
|
||||
|
566
hardware/digistump/avr/libraries/RcSeq/RcSeq.cpp
Normal file
566
hardware/digistump/avr/libraries/RcSeq/RcSeq.cpp
Normal file
@@ -0,0 +1,566 @@
|
||||
#include "RcSeq.h"
|
||||
/*
|
||||
English: by RC Navy (2012/2013)
|
||||
=======
|
||||
<RcSeq> is an asynchronous library for ATmega328P (UNO), ATtiny84 and ATtiny85 to easily create servo's sequences and/or to execute short actions from RC commands.
|
||||
It can also be used to trig some short "actions" (the duration must be less than 20ms to not disturb the servo commands)
|
||||
The Application Programming Interface (API) makes <RcSeq> library very easy to use.
|
||||
<RcSeq> needs 3 other libraries written by the same author:
|
||||
1) <TinyPinChange>: a library to catch asynchronously the input change using Pin Change Interruption capability of the AVR
|
||||
2) <SoftRcPulseIn>: a library to catch asynchronously the input pulses using <TinyPinChange> library
|
||||
3) <SoftRcPulseOut>: a library mainly based on the <SoftwareServo> library, but with a better pulse generation to limit jitter
|
||||
RC Signals (receiver outputs) can be assigned to a control type:
|
||||
-Stick Positions (up to 8, but in practice, 4 is the maximum to manually discriminate each stick position)
|
||||
-Keyboard (<RcSeq> assumes Push-Buttons associated Pulse duration are equidistant)
|
||||
-Custom Keyboard (The pulse durations can be defined independently for each Push-Button)
|
||||
Some definitions:
|
||||
-Sequence: is used to sequence one or several servos (sequence is defined in a structure in the user's sketch to be performed when the RC command rises)
|
||||
The Sequence table (structure) may contain some servo motions and some short actions to call.
|
||||
-Short Action: is used to perform a quick action (action is a short function defined in the user's sketch to be called when the RC command rises)
|
||||
CAUTION: the end user shall also use asynchronous programmation method in the loop() function (no blocking functions such as delay() or pulseIn()).
|
||||
http://p.loussouarn.free.fr
|
||||
|
||||
Francais: par RC Navy (2012)
|
||||
========
|
||||
<RcSeq> est une librairie asynchrone pour ATmega328P (UNO), ATtiny84 et ATtiny85 pour creer facilement des sequences de servos et/ou executer des actions depuis des commandes RC.
|
||||
Elle peut egalement etre utilisee pour lancer des "actions courtes" (la duree doit etre inferieure a 20ms pour ne pas perturber la commande des servos)
|
||||
L'Interface de Programmation d'Application (API) fait que la librairie <RcSeq> est tres facile a utiliser.
|
||||
<RcSeq> necessite 3 autres librairies ecrites par le meme auteur:
|
||||
1) <TinyPinChange>: une librarie pour capter de maniere asynchrone les changements d'etat des broches utilisant les interruptions sur changement des pins des AVR
|
||||
2) <SoftRcPulseIn>: une librarie pour capter de maniere asynchrone les impulsions entrantes en utilisant la librairie <TinyPinChange>
|
||||
3) <SoftRcPulseOut>: une librairie majoritairement basee sur la librairie <SoftwareServo>, mais avec une meilleur generation des impulsions pour limiter la gigue
|
||||
Les signaux RC (sorties du recepteur) peuvent etre associes a un type de controle:
|
||||
-Positions de Manche (jusqu'a 8, mais en pratique, 4 est le maximum pour discriminer manuellement les positions du manche)
|
||||
-Clavier (<RcSeq> suppose que les durees d'impulsion des Bouton-Poussoirs sont equidistantes)
|
||||
-Clavier "Maison" (Les durees d'impulsion peuvent etre definies de manière independante pour chaque Bouton-Poussoir)
|
||||
Quelques definitions:
|
||||
-Sequence: est utilisee pour sequencer un ou plusieurs servos (sequence est definie dans une structure dans le sketch utilisateur: est lancee quand la commande RC est recue)
|
||||
La table de sequence (structure) peut contenir des mouvements de servo et des actions courtes a appeler.
|
||||
-Action courte: est utilisee pour une action rapide (action est une fonction courte definie dans le sketch utilsateur: est appelee quand la commande RC est recue)
|
||||
ATTENTION: l'utilisateur final doit egalement utiliser la methode de programmation asynchrone dans la fonction loop() (pas de fonctions bloquantes comme delay() ou pulseIn()).
|
||||
http://p.loussouarn.free.fr
|
||||
|
||||
ASTUCE:
|
||||
======
|
||||
|
||||
Il est possible de declarer 8 sequences par manche (4 avec la voie du potentiometre vertical et 4 avec la voie du potentiometre horizontal).
|
||||
Il est possible de lancer 2 sequences en meme temps en utilisant les diagonales (la ou il y a des X dans la figure ci-dessous).
|
||||
|
||||
POSITION MANCHE SUR EMETTEUR
|
||||
,---------------------. \
|
||||
| X O X | --> RC_IMPULSION_NIVEAU_PLUS_2 |
|
||||
| | | |
|
||||
| X O X | --> RC_IMPULSION_NIVEAU_PLUS_1 |
|
||||
| | | /
|
||||
| O---O---O---O---O | --> Neutre (Aucune action) > 4 sequences possibles avec le manche vertical
|
||||
| | | \
|
||||
| X O X | --> RC_IMPULSION_NIVEAU_MOINS_1 |
|
||||
| | | |
|
||||
| X O X | --> RC_IMPULSION_NIVEAU_MOINS_2 |
|
||||
'---------------------' /
|
||||
| | | | |
|
||||
| | | | | \
|
||||
| | | | '------> RC_IMPULSION_NIVEAU_PLUS_2 |
|
||||
| | | | |
|
||||
| | | '----------> RC_IMPULSION_NIVEAU_PLUS_1 |
|
||||
| | | /
|
||||
| | '--------------> Neutre (Aucune action) > 4 sequences possibles avec le manche horizontal
|
||||
| | \
|
||||
| '------------------> RC_IMPULSION_NIVEAU_MOINS_1 |
|
||||
| |
|
||||
'----------------------> RC_IMPULSION_NIVEAU_MOINS_2 |
|
||||
/
|
||||
*/
|
||||
/*************************************************************************
|
||||
MACROS
|
||||
*************************************************************************/
|
||||
/* For an easy Library Version Management */
|
||||
#define LIB_VERSION 1
|
||||
#define LIB_REVISION 0
|
||||
|
||||
#define STR(s) #s
|
||||
#define MAKE_TEXT_VER_REV(Ver,Rev) (char*)(STR(Ver)"."STR(Rev))
|
||||
|
||||
#define LIB_TEXT_VERSION_REVISION MAKE_TEXT_VER_REV(LIB_VERSION,LIB_REVISION) /* Make Full version as a string "Ver.Rev" */
|
||||
|
||||
/* A Set of Macros for bit manipulation */
|
||||
#define SET_BIT(Value,BitIdx) (Value)|= (1<<(BitIdx))
|
||||
#define CLR_BIT(Value,BitIdx) (Value)&=~(1<<(BitIdx))
|
||||
#define TST_BIT(Value,BitIdx) ((Value)&(1<<(BitIdx)))
|
||||
|
||||
/* Servo refresh interval in ms (do not change this value, this one allows "round" values) */
|
||||
#define REFRESH_INTERVAL_MS 20L
|
||||
|
||||
/* A pulse shall be valid during XXXX_PULSE_CHECK_MS before being taken into account */
|
||||
#define STICK_PULSE_CHECK_MS 100L
|
||||
#define KBD_PULSE_CHECK_MS 10L
|
||||
|
||||
/* Duration between 2 consecutive commands */
|
||||
#define INTER_CMD_DURATION_MS 1000L
|
||||
|
||||
/* Free servo Indicator */
|
||||
#define NO_SEQ_LINE 255
|
||||
|
||||
/* Free Position Indicator */
|
||||
#define NO_POS 255
|
||||
|
||||
/* The macro below computes how many refresh to perform while a duration in ms */
|
||||
#define REFRESH_NB(DurationMs) ((DurationMs)/REFRESH_INTERVAL_MS)
|
||||
|
||||
/* The motion goes from StartInDegrees to EndInDegrees and will take MotionDurationMs in ms */
|
||||
#define STEP_IN_DEGREES_PER_REFRESH(StartInDegrees,EndInDegrees,MotionDurationMs) (EndInDegrees-StartInDegrees)/REFRESH_NB(MotionDurationMs)
|
||||
/* A set of Macros to read an (u)int8_t (Byte), an (u)int16_t (Word) in program memory (Flash memory) */
|
||||
#define PGM_READ_8(FlashAddr) pgm_read_byte(&(FlashAddr))
|
||||
#define PGM_READ_16(FlashAddr) pgm_read_word(&(FlashAddr))
|
||||
#define PGM_READ_32(FlashAddr) pgm_read_dword(&(FlashAddr))
|
||||
|
||||
/*
|
||||
STICK TYPE:
|
||||
==========
|
||||
Pos 0 1 2 3
|
||||
|---|-|---|--|---|-|---|
|
||||
1000us 2000us (Typical Pulse Width values)
|
||||
*/
|
||||
#define ACTIVE_AREA_STEP_NBR 3
|
||||
#define INACTIVE_AREA_STEP_NBR 1
|
||||
#define TOTAL_STEP_NBR(KeyNb,Type) ((Type==RC_CMD_STICK)?((KeyNb)*(ACTIVE_AREA_STEP_NBR+INACTIVE_AREA_STEP_NBR)):(((KeyNb)*(ACTIVE_AREA_STEP_NBR+INACTIVE_AREA_STEP_NBR))-1))
|
||||
#define STEP(MinUs, MaxUs,KeyNb,Type) ((MaxUs-MinUs)/TOTAL_STEP_NBR(KeyNb,Type))
|
||||
#define KEY_MIN_VAL(Idx,Step) ((ACTIVE_AREA_STEP_NBR+INACTIVE_AREA_STEP_NBR)*(Step)*(Idx))
|
||||
#define KEY_MAX_VAL(Idx,Step) (KEY_MIN_VAL(Idx,Step)+(ACTIVE_AREA_STEP_NBR*(Step)))
|
||||
|
||||
typedef struct {
|
||||
int8_t InProgress;
|
||||
int8_t CmdIdx;
|
||||
int8_t Pos;
|
||||
uint32_t StartChronoMs;
|
||||
void *TableOrShortAction;
|
||||
uint8_t SequenceLength;
|
||||
uint8_t ShortActionMap;
|
||||
}CmdSequenceSt_t;
|
||||
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
typedef struct {
|
||||
int8_t Idx;
|
||||
uint32_t StartChronoMs;
|
||||
}PosST_t;
|
||||
|
||||
typedef struct {
|
||||
SoftRcPulseIn Pulse;
|
||||
PosST_t Pos;
|
||||
uint8_t Type; /* RC_CMD_STICK or RC_CMD_KEYBOARD or RC_CMD_CUSTOM */
|
||||
uint8_t PosNb;
|
||||
uint16_t PulseMinUs;
|
||||
uint16_t PulseMaxUs;
|
||||
uint16_t StepUs;
|
||||
KeyMap_t *KeyMap;
|
||||
}RcCmdSt_t;
|
||||
#endif
|
||||
|
||||
typedef struct {
|
||||
SoftRcPulseOut Motor;
|
||||
uint16_t RefreshNb; /* Used to store the number of refresh to perform during a servo motion (if not 0 -> Motion in progress) */
|
||||
uint8_t SeqLineInProgress;
|
||||
}ServoSt_t;
|
||||
/*************************************************************************
|
||||
GLOBAL VARIABLES
|
||||
*************************************************************************/
|
||||
static uint8_t SeqNb;
|
||||
static uint8_t ServoNb;
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
static uint8_t CmdSignalNb;
|
||||
static RcCmdSt_t RcChannel[RC_CMD_MAX_NB];
|
||||
#endif
|
||||
#ifdef RC_SEQ_WITH_STATIC_MEM_ALLOC_SUPPORT
|
||||
#define AsMember .
|
||||
static ServoSt_t Servo[SERVO_MAX_NB];
|
||||
static CmdSequenceSt_t CmdSequence[SEQUENCE_MAX_NB];
|
||||
#else
|
||||
#define AsMember ->
|
||||
static ServoSt_t **Servo=NULL;
|
||||
static CmdSequenceSt_t **CmdSequence=NULL;
|
||||
#endif
|
||||
/*************************************************************************
|
||||
PRIVATE FUNCTION PROTOTYPES
|
||||
*************************************************************************/
|
||||
static void ExecuteSequence(uint8_t CmdIdx, uint8_t Pos);
|
||||
#ifndef RC_SEQ_WITH_STATIC_MEM_ALLOC_SUPPORT
|
||||
static void LoadSequenceOrShortAction(uint8_t CmdIdx,uint8_t Pos,void *SequenceOrShortAction, uint8_t SequenceLength);
|
||||
#endif
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
static int8_t GetPos(uint8_t ChIdx,uint16_t PulseWidthUs);
|
||||
#endif
|
||||
|
||||
//========================================================================================================================
|
||||
void RcSeq_Init(void)
|
||||
{
|
||||
SeqNb=0;
|
||||
ServoNb=0;
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
for(uint8_t ChIdx=0;ChIdx<RC_CMD_MAX_NB;ChIdx++)
|
||||
{
|
||||
RcChannel[ChIdx].Pos.Idx=NO_POS;
|
||||
}
|
||||
#endif
|
||||
#ifdef RC_SEQ_WITH_STATIC_MEM_ALLOC_SUPPORT
|
||||
for(uint8_t SeqIdx=0;SeqIdx<SEQUENCE_MAX_NB;SeqIdx++)
|
||||
{
|
||||
CmdSequence[SeqIdx].InProgress=0;
|
||||
CmdSequence[SeqIdx].TableOrShortAction=NULL;
|
||||
CmdSequence[SeqIdx].SequenceLength=0;
|
||||
CmdSequence[SeqIdx].ShortActionMap=0;
|
||||
}
|
||||
#endif
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
TinyPinChange_Init();
|
||||
#endif
|
||||
}
|
||||
//========================================================================================================================
|
||||
uint8_t RcSeq_LibVersion(void)
|
||||
{
|
||||
return(LIB_VERSION);
|
||||
}
|
||||
//========================================================================================================================
|
||||
uint8_t RcSeq_LibRevision(void)
|
||||
{
|
||||
return(LIB_REVISION);
|
||||
}
|
||||
//========================================================================================================================
|
||||
char *RcSeq_LibTextVersionRevision(void)
|
||||
{
|
||||
return(LIB_TEXT_VERSION_REVISION);
|
||||
}
|
||||
//========================================================================================================================
|
||||
void RcSeq_DeclareServo(uint8_t Idx, uint8_t DigitalPin)
|
||||
{
|
||||
#ifdef RC_SEQ_WITH_STATIC_MEM_ALLOC_SUPPORT
|
||||
if(Idx<SERVO_MAX_NB)
|
||||
{
|
||||
Servo[Idx].Motor.attach(DigitalPin);
|
||||
Servo[Idx].SeqLineInProgress=NO_SEQ_LINE;
|
||||
if(ServoNb<(Idx+1)) ServoNb=(Idx+1);
|
||||
}
|
||||
#else
|
||||
if(Idx<SERVO_MAX_NB)
|
||||
{
|
||||
ServoNb++;
|
||||
if(!Servo) Servo=(ServoSt_t**)malloc(sizeof(ServoSt_t));
|
||||
else Servo=(ServoSt_t**)realloc(Servo, sizeof(ServoSt_t)*ServoNb);
|
||||
Servo[Idx] AsMember Motor.attach(DigitalPin);
|
||||
Servo[Idx] AsMember SeqLineInProgress=NO_SEQ_LINE;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
//========================================================================================================================
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
void RcSeq_DeclareSignal(uint8_t Idx, uint8_t DigitalPin)
|
||||
{
|
||||
if(Idx<RC_CMD_MAX_NB)
|
||||
{
|
||||
RcChannel[Idx].Pulse.attach(DigitalPin);
|
||||
CmdSignalNb++;
|
||||
}
|
||||
}
|
||||
//========================================================================================================================
|
||||
void RcSeq_DeclareKeyboardOrStickOrCustom(uint8_t ChIdx, uint8_t Type, uint16_t PulseMinUs, uint16_t PulseMaxUs, KeyMap_t *KeyMap, uint8_t PosNb)
|
||||
{
|
||||
RcChannel[ChIdx].Type = Type;
|
||||
RcChannel[ChIdx].PosNb = PosNb;
|
||||
RcChannel[ChIdx].PulseMinUs = PulseMinUs;
|
||||
RcChannel[ChIdx].PulseMaxUs = PulseMaxUs;
|
||||
RcChannel[ChIdx].StepUs = STEP(PulseMinUs, PulseMaxUs, PosNb, Type);
|
||||
RcChannel[ChIdx].KeyMap = KeyMap;
|
||||
}
|
||||
//========================================================================================================================
|
||||
void RcSeq_DeclareCustomKeyboard(uint8_t ChIdx, KeyMap_t *KeyMapTbl, uint8_t KeyNb)
|
||||
{
|
||||
RcSeq_DeclareKeyboardOrStickOrCustom(ChIdx, RC_CMD_CUSTOM, 0, 0, KeyMapTbl, KeyNb);
|
||||
}
|
||||
#endif
|
||||
//========================================================================================================================
|
||||
void RcSeq_DeclareCommandAndSequence(uint8_t CmdIdx,uint8_t Pos,SequenceSt_t *Table, uint8_t SequenceLength)
|
||||
{
|
||||
uint8_t Idx, ServoIdx;
|
||||
uint16_t StartInDegrees;
|
||||
uint32_t StartMinMs[SERVO_MAX_NB];
|
||||
#ifdef RC_SEQ_WITH_STATIC_MEM_ALLOC_SUPPORT
|
||||
for(Idx=0;Idx<SEQUENCE_MAX_NB;Idx++)
|
||||
{
|
||||
if(!CmdSequence[Idx].TableOrShortAction)
|
||||
{
|
||||
CmdSequence[Idx].CmdIdx=CmdIdx;
|
||||
CmdSequence[Idx].Pos=Pos;
|
||||
CmdSequence[Idx].TableOrShortAction=(void*)Table;
|
||||
CmdSequence[Idx].SequenceLength=SequenceLength;
|
||||
SeqNb++;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#else
|
||||
LoadSequenceOrShortAction(CmdIdx,Pos,(void*)Table, SequenceLength);
|
||||
#endif
|
||||
|
||||
/* Get initial pulse width for each Servo */
|
||||
for(Idx=0;Idx<SERVO_MAX_NB;Idx++)
|
||||
{
|
||||
StartMinMs[Idx]=0xFFFFFFFF;
|
||||
}
|
||||
for(Idx=0;Idx<SequenceLength;Idx++)
|
||||
{
|
||||
ServoIdx=(int8_t)PGM_READ_8(Table[Idx].ServoIndex);
|
||||
if(ServoIdx!=255)
|
||||
{
|
||||
if((uint32_t)PGM_READ_32(Table[Idx].StartMotionOffsetMs)<=StartMinMs[ServoIdx])
|
||||
{
|
||||
StartMinMs[ServoIdx]=(uint32_t)PGM_READ_32(Table[Idx].StartMotionOffsetMs);
|
||||
StartInDegrees=(uint16_t)PGM_READ_8(Table[Idx].StartInDegrees);
|
||||
Servo[ServoIdx] AsMember Motor.write(StartInDegrees);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
//========================================================================================================================
|
||||
void RcSeq_DeclareCommandAndShortAction(uint8_t CmdIdx,uint8_t Pos,void(*ShortAction)(void))
|
||||
{
|
||||
#ifdef RC_SEQ_WITH_STATIC_MEM_ALLOC_SUPPORT
|
||||
uint8_t Idx;
|
||||
for(Idx=0;Idx<SEQUENCE_MAX_NB;Idx++)
|
||||
{
|
||||
if(!CmdSequence[Idx].TableOrShortAction)
|
||||
{
|
||||
CmdSequence[Idx].CmdIdx=CmdIdx;
|
||||
CmdSequence[Idx].Pos=Pos;
|
||||
CmdSequence[Idx].TableOrShortAction=(void*)ShortAction;
|
||||
SeqNb++;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#else
|
||||
LoadSequenceOrShortAction(CmdIdx,Pos,(void*)ShortAction, 0);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef RC_SEQ_WITH_STATIC_MEM_ALLOC_SUPPORT
|
||||
static void LoadSequenceOrShortAction(uint8_t CmdIdx,uint8_t Pos,void *SequenceOrShortAction, uint8_t SequenceLength)
|
||||
{
|
||||
if(!CmdSequence) CmdSequence=(CmdSequenceSt_t**)malloc(sizeof(CmdSequenceSt_t));
|
||||
else CmdSequence=(CmdSequenceSt_t**)realloc(CmdSequence,sizeof(CmdSequence)+sizeof(CmdSequenceSt_t));
|
||||
CmdSequence[SeqNb] AsMember CmdIdx=CmdIdx;
|
||||
CmdSequence[SeqNb] AsMember Pos=Pos;
|
||||
CmdSequence[SeqNb] AsMember TableOrShortAction=(void*)SequenceOrShortAction;
|
||||
CmdSequence[SeqNb] AsMember SequenceLength=SequenceLength;
|
||||
SeqNb++;
|
||||
}
|
||||
#endif
|
||||
//========================================================================================================================
|
||||
uint8_t RcSeq_LaunchSequence(SequenceSt_t *Table)
|
||||
{
|
||||
uint8_t Idx, Ret=0;
|
||||
for(Idx=0;Idx<SEQUENCE_MAX_NB;Idx++)
|
||||
{
|
||||
if(CmdSequence[Idx] AsMember TableOrShortAction==(void*)Table)
|
||||
{
|
||||
ExecuteSequence(CmdSequence[Idx] AsMember CmdIdx,CmdSequence[Idx] AsMember Pos);
|
||||
Ret=1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return(Ret);
|
||||
}
|
||||
//========================================================================================================================
|
||||
void RcSeq_Refresh(void)
|
||||
{
|
||||
static uint32_t NowMs=millis();
|
||||
static uint32_t StartChronoInterPulseMs=millis();
|
||||
SequenceSt_t *SequenceTable;
|
||||
void (*ShortAction)(void);
|
||||
int8_t ShortActionCnt;
|
||||
uint8_t ServoIdx;
|
||||
uint32_t MotionDurationMs, StartOfSeqMs, EndOfSeqMs, Pos;
|
||||
uint16_t StartInDegrees, EndInDegrees;
|
||||
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
uint8_t ChIdx, CmdPos;
|
||||
uint32_t RcPulseWidthUs;
|
||||
|
||||
/* Asynchronous RC Command acquisition */
|
||||
for(ChIdx=0;ChIdx<CmdSignalNb;ChIdx++)
|
||||
{
|
||||
if(!RcChannel[ChIdx].Pulse.available()) continue; /* Channel not used or no pulse received */
|
||||
RcPulseWidthUs=RcChannel[ChIdx].Pulse.width_us();
|
||||
CmdPos=GetPos(ChIdx,RcPulseWidthUs);
|
||||
if(CmdPos>=0)
|
||||
{
|
||||
if(RcChannel[ChIdx].Pos.Idx!=CmdPos)
|
||||
{
|
||||
if((millis()-RcChannel[ChIdx].Pos.StartChronoMs)>=INTER_CMD_DURATION_MS) /* Check the last command was received for at least 1 second */
|
||||
{
|
||||
RcChannel[ChIdx].Pos.Idx=CmdPos;
|
||||
RcChannel[ChIdx].Pos.StartChronoMs=millis();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if((millis()-RcChannel[ChIdx].Pos.StartChronoMs)>=((RcChannel[ChIdx].Type==RC_CMD_STICK)?STICK_PULSE_CHECK_MS:KBD_PULSE_CHECK_MS)) /* Check the Pulse is valid at least for 100 ms or 50 ms */
|
||||
{
|
||||
ExecuteSequence(ChIdx,CmdPos);
|
||||
RcChannel[ChIdx].Pos.Idx=NO_POS;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
RcChannel[ChIdx].Pos.Idx=NO_POS;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
NowMs=millis();
|
||||
if((NowMs - StartChronoInterPulseMs) >= 20L)
|
||||
{
|
||||
/* We arrive here every 20 ms */
|
||||
/* Asynchronous Servo Sequence management */
|
||||
for(int8_t Idx=0;Idx<SeqNb;Idx++)
|
||||
{
|
||||
if(!CmdSequence[Idx] AsMember InProgress || !CmdSequence[Idx] AsMember SequenceLength) continue;
|
||||
ShortActionCnt=-1;
|
||||
for(int8_t SeqLine=0;SeqLine<CmdSequence[Idx] AsMember SequenceLength;SeqLine++) /* Read all lines of the sequence table: this allows to run several servos simultaneously (not forcibly one after the other) */
|
||||
{
|
||||
SequenceTable=(SequenceSt_t *)CmdSequence[Idx] AsMember TableOrShortAction;
|
||||
ServoIdx=(int8_t)PGM_READ_8(SequenceTable[SeqLine].ServoIndex);
|
||||
#ifdef RC_SEQ_WITH_SHORT_ACTION_SUPPORT
|
||||
if(ServoIdx==255) /* Not a Servo: it's a short Action to perform only if not already done */
|
||||
{
|
||||
ShortActionCnt++;
|
||||
StartOfSeqMs = CmdSequence[Idx] AsMember StartChronoMs + (int32_t)PGM_READ_32(SequenceTable[SeqLine].StartMotionOffsetMs);
|
||||
if( (NowMs>=StartOfSeqMs) && !TST_BIT(CmdSequence[Idx] AsMember ShortActionMap,ShortActionCnt) )
|
||||
{
|
||||
ShortAction=(void(*)(void))PGM_READ_16(SequenceTable[SeqLine].ShortAction);
|
||||
ShortAction();
|
||||
SET_BIT(CmdSequence[Idx] AsMember ShortActionMap,ShortActionCnt); /* Mark short Action as performed */
|
||||
/* If the last line contains an Action AsMember End of Sequence */
|
||||
if(SeqLine==(CmdSequence[Idx] AsMember SequenceLength-1))
|
||||
{
|
||||
CmdSequence[Idx] AsMember InProgress=0;
|
||||
CmdSequence[Idx] AsMember ShortActionMap=0; /* Mark all Short Action as not performed */
|
||||
}
|
||||
}
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
if(Servo[ServoIdx] AsMember RefreshNb && SeqLine!=Servo[ServoIdx] AsMember SeqLineInProgress)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
StartOfSeqMs = CmdSequence[Idx] AsMember StartChronoMs + (int32_t)PGM_READ_32(SequenceTable[SeqLine].StartMotionOffsetMs);
|
||||
MotionDurationMs = (int32_t)PGM_READ_32(SequenceTable[SeqLine].MotionDurationMs);
|
||||
EndOfSeqMs = StartOfSeqMs + MotionDurationMs;
|
||||
if(!Servo[ServoIdx] AsMember RefreshNb && Servo[ServoIdx] AsMember SeqLineInProgress==NO_SEQ_LINE)
|
||||
{
|
||||
if( (NowMs>=StartOfSeqMs) && (NowMs<=EndOfSeqMs) )
|
||||
{
|
||||
Servo[ServoIdx] AsMember SeqLineInProgress=SeqLine;
|
||||
StartInDegrees=(uint16_t)PGM_READ_8(SequenceTable[SeqLine].StartInDegrees);
|
||||
Servo[ServoIdx] AsMember RefreshNb=REFRESH_NB(MotionDurationMs);
|
||||
Servo[ServoIdx] AsMember Motor.write(StartInDegrees);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* A sequence line is in progress: update the next position */
|
||||
if(Servo[ServoIdx] AsMember RefreshNb) Servo[ServoIdx] AsMember RefreshNb--;
|
||||
StartInDegrees=(uint16_t)PGM_READ_8(SequenceTable[SeqLine].StartInDegrees);
|
||||
EndInDegrees=(uint16_t)PGM_READ_8(SequenceTable[SeqLine].EndInDegrees);
|
||||
Pos=(int32_t)EndInDegrees-((int32_t)Servo[ServoIdx] AsMember RefreshNb*STEP_IN_DEGREES_PER_REFRESH((int32_t)StartInDegrees,(int32_t)EndInDegrees,(int32_t)MotionDurationMs)); //For refresh max nb, Pos = StartInDegrees
|
||||
Servo[ServoIdx] AsMember Motor.write(Pos);
|
||||
if( !Servo[ServoIdx] AsMember RefreshNb )
|
||||
{
|
||||
Servo[ServoIdx] AsMember SeqLineInProgress=NO_SEQ_LINE;
|
||||
/* Last servo motion and refresh = 0 -> End of Sequence */
|
||||
if(SeqLine==(CmdSequence[Idx] AsMember SequenceLength-1))
|
||||
{
|
||||
CmdSequence[Idx] AsMember InProgress=0;
|
||||
CmdSequence[Idx] AsMember ShortActionMap=0; /* Mark all Short Action as not performed */
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
SoftRcPulseOut::refresh(1); /* Force Refresh */
|
||||
StartChronoInterPulseMs=millis();
|
||||
}
|
||||
}
|
||||
|
||||
//========================================================================================================================
|
||||
// PRIVATE FUNCTIONS
|
||||
//========================================================================================================================
|
||||
static void ExecuteSequence(uint8_t CmdIdx, uint8_t Pos)
|
||||
{
|
||||
void(*ShortAction)(void);
|
||||
uint8_t Idx;
|
||||
|
||||
for(Idx=0;Idx<SeqNb;Idx++)
|
||||
{
|
||||
if((CmdSequence[Idx] AsMember CmdIdx==CmdIdx) && (CmdSequence[Idx] AsMember Pos==Pos))
|
||||
{
|
||||
#ifdef RC_SEQ_WITH_SHORT_ACTION_SUPPORT
|
||||
if(CmdSequence[Idx] AsMember TableOrShortAction && !CmdSequence[Idx] AsMember SequenceLength)
|
||||
{
|
||||
/* It's a short action */
|
||||
ShortAction=(void(*)(void))CmdSequence[Idx] AsMember TableOrShortAction;
|
||||
ShortAction();
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
/* It's a Table of Sequence */
|
||||
if(!CmdSequence[Idx] AsMember InProgress)
|
||||
{
|
||||
CmdSequence[Idx] AsMember InProgress=1;
|
||||
CmdSequence[Idx] AsMember StartChronoMs=millis();
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
//========================================================================================================================
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
static int8_t GetPos(uint8_t ChIdx,uint16_t PulseWidthUs)
|
||||
{
|
||||
int8_t Idx, Ret=-1;
|
||||
uint16_t PulseMinUs,PulseMaxUs;
|
||||
|
||||
for(Idx=0;Idx<RcChannel[ChIdx].PosNb;Idx++)
|
||||
{
|
||||
switch(RcChannel[ChIdx].Type)
|
||||
{
|
||||
case RC_CMD_STICK: /* No break: normal */
|
||||
case RC_CMD_KEYBOARD:
|
||||
if(Idx<(RcChannel[ChIdx].PosNb/2))
|
||||
{
|
||||
PulseMinUs=RcChannel[ChIdx].PulseMinUs+KEY_MIN_VAL(Idx,RcChannel[ChIdx].StepUs);
|
||||
PulseMaxUs=RcChannel[ChIdx].PulseMinUs+KEY_MAX_VAL(Idx,RcChannel[ChIdx].StepUs);
|
||||
}
|
||||
else
|
||||
{
|
||||
PulseMinUs=RcChannel[ChIdx].PulseMaxUs-KEY_MAX_VAL(RcChannel[ChIdx].PosNb-1-Idx,RcChannel[ChIdx].StepUs);
|
||||
PulseMaxUs=RcChannel[ChIdx].PulseMaxUs-KEY_MIN_VAL(RcChannel[ChIdx].PosNb-1-Idx,RcChannel[ChIdx].StepUs);
|
||||
}
|
||||
break;
|
||||
|
||||
case RC_CMD_CUSTOM:
|
||||
PulseMinUs=(uint16_t)PGM_READ_16(RcChannel[ChIdx].KeyMap[Idx].Min);
|
||||
PulseMaxUs=(uint16_t)PGM_READ_16(RcChannel[ChIdx].KeyMap[Idx].Max);
|
||||
break;
|
||||
}
|
||||
if((PulseWidthUs>=PulseMinUs) && (PulseWidthUs<=PulseMaxUs))
|
||||
{
|
||||
Ret=Idx;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return(Ret);
|
||||
}
|
||||
#endif
|
||||
//========================================================================================================================
|
171
hardware/digistump/avr/libraries/RcSeq/RcSeq.h
Normal file
171
hardware/digistump/avr/libraries/RcSeq/RcSeq.h
Normal file
@@ -0,0 +1,171 @@
|
||||
#ifndef RC_SEQ_H
|
||||
#define RC_SEQ_H
|
||||
|
||||
/*
|
||||
English: by RC Navy (2012)
|
||||
=======
|
||||
<RcSeq> is an asynchronous library for ATmega328P (UNO), ATtiny84 and ATtiny85 to easily create servo's sequences and/or to execute short actions from RC commands.
|
||||
It can also be used to trig some short "actions" (the duration must be less than 20ms to not disturb the servo commands)
|
||||
The Application Programming Interface (API) makes <RcSeq> library very easy to use.
|
||||
<RcSeq> needs 3 other libraries written by the same author:
|
||||
1) <TinyPinChange>: a library to catch asynchronously the input change using Pin Change Interruption capability of the AVR
|
||||
2) <SoftRcPulseIn>: a library to catch asynchronously the input pulses using <TinyPinChange> library
|
||||
3) <SoftRcPulseOut>: a library mainly based on the <SoftwareServo> library, but with a better pulse generation to limit jitter
|
||||
RC Signals (receiver outputs) can be assigned to a control type:
|
||||
-Stick Positions (up to 8, but in practice, 4 is the maximum to manually discriminate each stick position)
|
||||
-Keyboard (<RcSeq> assumes Push-Buttons associated Pulse duration are equidistant)
|
||||
-Custom Keyboard (The pulse durations can be defined independently for each Push-Button)
|
||||
Some definitions:
|
||||
-Sequence: is used to sequence one or several servos (sequence is defined in a structure in the user's sketch to be performed when the RC command rises)
|
||||
The Sequence table (structure) may contain some servo motions and some short actions to call.
|
||||
-Short Action: is used to perform a quick action (action is a short function defined in the user's sketch to be called when the RC command rises)
|
||||
CAUTION: the end user shall also use asynchronous programmation method in the loop() function (no blocking functions such as delay() or pulseIn()).
|
||||
http://p.loussouarn.free.fr
|
||||
|
||||
Francais: par RC Navy (2012)
|
||||
========
|
||||
<RcSeq> est une librairie asynchrone pour ATmega328P (UNO), ATtiny84 et ATtiny85 pour creer facilement des sequences de servos et/ou executer des actions depuis des commandes RC.
|
||||
Elle peut egalement etre utilisee pour lancer des "actions courtes" (la duree doit etre inferieure a 20ms pour ne pas perturber la commande des servos)
|
||||
L'Interface de Programmation d'Application (API) fait que la librairie <RcSeq> est tres facile a utiliser.
|
||||
<RcSeq> necessite 3 autres librairies ecrites par le meme auteur:
|
||||
1) <TinyPinChange>: une librarie pour capter de maniere asynchrone les changements d'etat des broches utilisant les interruptions sur changement des pins des AVR
|
||||
2) <SoftRcPulseIn>: une librarie pour capter de maniere asynchrone les impulsions entrantes en utilisant la librairie <TinyPinChange>
|
||||
3) <SoftRcPulseOut>: une librairie majoritairement basee sur la librairie <SoftwareServo>, mais avec une meilleur generation des impulsions pour limiter la gigue
|
||||
Les signaux RC (sorties du recepteur) peuvent etre associes a un type de controle:
|
||||
-Positions de Manche (jusqu'a 8, mais en pratique, 4 est le maximum pour discriminer manuellement les positions du manche)
|
||||
-Clavier (<RcSeq> suppose que les durees d'impulsion des Bouton-Poussoirs sont equidistantes)
|
||||
-Clavier "Maison" (Les durees d'impulsion peuvent etre definies de manière independante pour chaque Bouton-Poussoir)
|
||||
Quelques definitions:
|
||||
-Sequence: est utilisee pour sequencer un ou plusieurs servos (sequence est definie dans une structure dans le sketch utilisateur: est lancee quand la commande RC est recue)
|
||||
La table de sequence (structure) peut contenir des mouvements de servo et des actions courtes a appeler.
|
||||
-Action courte: est utilisee pour une action rapide (action est une fonction courte definie dans le sketch utilsateur: est appelee quand la commande RC est recue)
|
||||
ATTENTION: l'utilisateur final doit egalement utiliser la methode de programmation asynchrone dans la fonction loop() (pas de fonctions bloquantes comme delay() ou pulseIn()).
|
||||
http://p.loussouarn.free.fr
|
||||
*/
|
||||
/**********************************************/
|
||||
/* RCSEQ LIBRARY CONFIGURATION */
|
||||
/**********************************************/
|
||||
//#define RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT /* Comment this line if you use <DigiUSB> library in your sketch */
|
||||
#define RC_SEQ_WITH_SHORT_ACTION_SUPPORT /* This allows to put call to short action in sequence table */
|
||||
|
||||
|
||||
|
||||
/**********************************************/
|
||||
/* /!\ Do not touch below /!\ */
|
||||
/**********************************************/
|
||||
#define RC_SEQ_WITH_STATIC_MEM_ALLOC_SUPPORT /* Do NOT comment this line for DigiSpark */
|
||||
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
#include <TinyPinChange.h>
|
||||
#include <SoftRcPulseIn.h>
|
||||
#else
|
||||
#warning RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT disabled: no RC command possible!!!
|
||||
#endif
|
||||
#ifndef RC_SEQ_WITH_SHORT_ACTION_SUPPORT
|
||||
#warning RC_SEQ_WITH_SHORT_ACTION_SUPPORT disabled: no short action possible!!!
|
||||
#endif
|
||||
#include <SoftRcPulseOut.h>
|
||||
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
#else
|
||||
#include "WProgram.h"
|
||||
#endif
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
#define SERVO_MAX_NB 10
|
||||
#define SEQUENCE_MAX_NB 8
|
||||
#define RC_CMD_MAX_NB 4
|
||||
#else
|
||||
#define SERVO_MAX_NB 3 /* 3 is the maximum for DigiSpark if DigiUSB is used in the skecth */
|
||||
#define SEQUENCE_MAX_NB 1 /* 1 is the maximum for DigiSpark if DigiUSB is used in the skecth */
|
||||
#define RC_CMD_MAX_NB 0
|
||||
#endif
|
||||
|
||||
typedef struct {
|
||||
uint8_t ServoIndex;
|
||||
uint8_t StartInDegrees;
|
||||
uint8_t EndInDegrees;
|
||||
uint32_t StartMotionOffsetMs;
|
||||
uint32_t MotionDurationMs;
|
||||
void (*ShortAction)(void);
|
||||
}SequenceSt_t;
|
||||
|
||||
typedef struct {
|
||||
uint16_t Min;
|
||||
uint16_t Max;
|
||||
} KeyMap_t;
|
||||
|
||||
#define TABLE_ITEM_NBR(Tbl) (sizeof(Tbl)/sizeof(Tbl[0]))
|
||||
|
||||
/* Macro to declare a motion WITH soft start and soft stop (to use in "Sequence[]" structure table) */
|
||||
#define MOTION_WITH_SOFT_START_AND_STOP(ServoIndex,StartInDegrees,EndInDegrees,StartMvtOffsetMs,MvtDurationMs,PourCent) \
|
||||
{(ServoIndex), (StartInDegrees), (StartInDegrees+((EndInDegrees-StartInDegrees)*PourCent)/100L), (StartMvtOffsetMs), ((MvtDurationMs*2L*PourCent)/100L), NULL }, \
|
||||
{(ServoIndex), (StartInDegrees+((EndInDegrees-StartInDegrees)*PourCent)/100L), (EndInDegrees-((EndInDegrees-StartInDegrees)*PourCent)/100L), (StartMvtOffsetMs+(MvtDurationMs*2L*PourCent)/100L), ((MvtDurationMs*(100L-4L*PourCent))/100L), NULL }, \
|
||||
{(ServoIndex), (EndInDegrees-((EndInDegrees-StartInDegrees)*PourCent)/100L), (EndInDegrees), ((StartMvtOffsetMs+(MvtDurationMs*2L*PourCent)/100L)+(MvtDurationMs*(100L-4L*PourCent))/100L), ((MvtDurationMs*2L*PourCent)/100L), NULL },
|
||||
|
||||
/* Macro to declare a motion WITHOUT soft start and soft stop (to use in "Sequence[]" structure table) */
|
||||
#define MOTION_WITHOUT_SOFT_START_AND_STOP(ServoIndex,StartInDegrees,EndInDegrees,StartMvtOffsetMs,MvtDurationMs) \
|
||||
{ServoIndex, StartInDegrees, EndInDegrees, StartMvtOffsetMs, MvtDurationMs, NULL},
|
||||
|
||||
/* Macro to declare a short action (to use in "Sequence[]" structure table) */
|
||||
#define SHORT_ACTION_TO_PERFORM(ShortAction, StartActionOffsetMs) {255, 0, 0, (StartActionOffsetMs), 0L, (ShortAction)},
|
||||
|
||||
enum {RC_CMD_STICK=0, RC_CMD_KEYBOARD, RC_CMD_CUSTOM};
|
||||
|
||||
#define RC_SEQUENCE(Sequence) Sequence, TABLE_ITEM_NBR(Sequence)
|
||||
#define RC_CUSTOM_KEYBOARD(KeyMap) KeyMap, TABLE_ITEM_NBR(KeyMap)
|
||||
|
||||
#define CENTER_VALUE_US(CenterVal,Tol) ((CenterVal)-(Tol)),((CenterVal)+(Tol))
|
||||
|
||||
void RcSeq_Init(void);
|
||||
uint8_t RcSeq_LibVersion(void);
|
||||
uint8_t RcSeq_LibRevision(void);
|
||||
char *RcSeq_LibTextVersionRevision(void);
|
||||
void RcSeq_DeclareServo(uint8_t Idx, uint8_t DigitalPin);
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
void RcSeq_DeclareSignal(uint8_t Idx, uint8_t DigitalPin);
|
||||
void RcSeq_DeclareKeyboardOrStickOrCustom(uint8_t ChIdx, uint8_t Type, uint16_t PulseMinUs, uint16_t PulseMaxUs, KeyMap_t *KeyMapTbl, uint8_t PosNb);
|
||||
void RcSeq_DeclareCustomKeyboard(uint8_t ChIdx, KeyMap_t *KeyMapTbl, uint8_t PosNb);
|
||||
#define RcSeq_DeclareStick(ChIdx, PulseMinUs, PulseMaxUs, PosNb) RcSeq_DeclareKeyboardOrStickOrCustom(ChIdx, RC_CMD_STICK, PulseMinUs, PulseMaxUs, NULL, PosNb)
|
||||
#define RcSeq_DeclareKeyboard(ChIdx, PulseMinUs, PulseMaxUs, KeyNb) RcSeq_DeclareKeyboardOrStickOrCustom(ChIdx, RC_CMD_KEYBOARD, PulseMinUs, PulseMaxUs, NULL, KeyNb)
|
||||
#ifdef RC_SEQ_WITH_SHORT_ACTION_SUPPORT
|
||||
void RcSeq_DeclareCommandAndShortAction(uint8_t CmdIdx,uint8_t TypeCmd,void(*ShortAction)(void));
|
||||
#endif
|
||||
#endif
|
||||
void RcSeq_DeclareCommandAndSequence(uint8_t CmdIdx,uint8_t TypeCmd,SequenceSt_t *Table, uint8_t SequenceLength);
|
||||
uint8_t RcSeq_LaunchSequence(SequenceSt_t *Table);
|
||||
#ifdef RC_SEQ_WITH_SHORT_ACTION_SUPPORT
|
||||
#define RcSeq_LaunchShortAction(ShortAction) if(ShortAction) ShortAction()
|
||||
#endif
|
||||
void RcSeq_Refresh(void);
|
||||
|
||||
/*******************************************************/
|
||||
/* Application Programming Interface (API) en Francais */
|
||||
/*******************************************************/
|
||||
|
||||
/* Macro en Francais de declaration mouvement English native Macro to declare a motion */
|
||||
#define MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS MOTION_WITH_SOFT_START_AND_STOP
|
||||
#define MVT_SANS_DEBUT_ET_FIN_MVT_LENTS MOTION_WITHOUT_SOFT_START_AND_STOP
|
||||
#define ACTION_COURTE_A_EFFECTUER SHORT_ACTION_TO_PERFORM
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
#define RC_CLAVIER_MAISON RC_CUSTOM_KEYBOARD
|
||||
#define VALEUR_CENTRALE_US CENTER_VALUE_US
|
||||
#endif
|
||||
|
||||
/* Methodes en Francais English native methods */
|
||||
#ifdef RC_SEQ_WITH_SOFT_RC_PULSE_IN_SUPPORT
|
||||
#define RcSeq_DeclareManche RcSeq_DeclareStick
|
||||
#define RcSeq_DeclareClavier RcSeq_DeclareKeyboard
|
||||
#define RcSeq_DeclareClavierMaison RcSeq_DeclareCustomKeyboard
|
||||
#define RcSeq_DeclareCommandeEtActionCourte RcSeq_DeclareCommandAndShortAction
|
||||
#endif
|
||||
#define RcSeq_DeclareCommandeEtSequence RcSeq_DeclareCommandAndSequence
|
||||
#define RcSeq_LanceSequence RcSeq_LaunchSequence
|
||||
#define RcSeq_LanceActionCourte RcSeq_LaunchShortAction
|
||||
#define RcSeq_Rafraichit RcSeq_Refresh
|
||||
|
||||
#endif
|
51
hardware/digistump/avr/libraries/RcSeq/keywords.txt
Normal file
51
hardware/digistump/avr/libraries/RcSeq/keywords.txt
Normal file
@@ -0,0 +1,51 @@
|
||||
############################################
|
||||
# Syntax Coloring Map RcSeq
|
||||
############################################
|
||||
|
||||
############################################
|
||||
# Datatypes (KEYWORD1)
|
||||
############################################
|
||||
RcSeq KEYWORD1
|
||||
|
||||
############################################
|
||||
# Methods and Functions (KEYWORD2)
|
||||
############################################
|
||||
RcSeq_LibVersion KEYWORD2
|
||||
RcSeq_LibRevision KEYWORD2
|
||||
RcSeq_LibTextVersionRevision KEYWORD2
|
||||
RcSeq_Init KEYWORD2
|
||||
RcSeq_DeclareSignal KEYWORD2
|
||||
RcSeq_DeclareKeyboard KEYWORD2
|
||||
RcSeq_DeclareClavier KEYWORD2
|
||||
RcSeq_DeclareStick KEYWORD2
|
||||
RcSeq_DeclareManche KEYWORD2
|
||||
RcSeq_DeclareServo KEYWORD2
|
||||
RcSeq_DeclareCustomKeyboard KEYWORD2
|
||||
RcSeq_DeclareClavierMaison KEYWORD2
|
||||
RcSeq_DeclareCommandAndSequence KEYWORD2
|
||||
RcSeq_DeclareCommandeEtSequence KEYWORD2
|
||||
RcSeq_DeclareCommandAndShortAction KEYWORD2
|
||||
RcSeq_DeclareCommandeEtActionCourte KEYWORD2
|
||||
RcSeq_LaunchSequence KEYWORD2
|
||||
RcSeq_LanceSequence KEYWORD2
|
||||
RcSeq_LaunchShortAction KEYWORD2
|
||||
RcSeq_LanceActionCourte KEYWORD2
|
||||
RcSeq_Refresh KEYWORD2
|
||||
RcSeq_Rafraichit KEYWORD2
|
||||
|
||||
############################################
|
||||
# Constants (LITERAL1)
|
||||
############################################
|
||||
SequenceSt_t LITERAL1
|
||||
KeyMap_t LITERAL1
|
||||
SHORT_ACTION_TO_PERFORM LITERAL1
|
||||
ACTION_COURTE_A_EFFECTUER LITERAL1
|
||||
MOTION_WITH_SOFT_START_AND_STOP LITERAL1
|
||||
MOTION_WITHOUT_SOFT_START_AND_STOP LITERAL1
|
||||
MVT_AVEC_DEBUT_ET_FIN_MVT_LENTS LITERAL1
|
||||
MVT_SANS_DEBUT_ET_FIN_MVT_LENTS LITERAL1
|
||||
RC_CUSTOM_KEYBOARD LITERAL1
|
||||
RC_CLAVIER_MAISON LITERAL1
|
||||
RC_SEQUENCE LITERAL1
|
||||
CENTER_VALUE_US LITERAL1
|
||||
VALEUR_CENTRALE_US LITERAL1
|
Reference in New Issue
Block a user