mirror of
https://forge.apps.education.fr/blender-edutech/jumeaux-numeriques.git
synced 2024-01-27 06:56:18 +01:00
Portail coulissant : test du shield moteur
This commit is contained in:
parent
4ddb18652f
commit
c13cb9af85
@ -124,11 +124,11 @@ def get_public_vars():
|
||||
|
||||
# Pour la commande du moteur de la variante 1 version Grove , le brochage du shield moteur CC 4 x 1,2 A DRI0039 (DFROBOT) est fixe,
|
||||
# il doit respecter le tableau suivant :
|
||||
# Motor # Direction pin (Forward/Backward) # Speed pin # Speed range (PWM)
|
||||
# M1 # 4 LOW HIGH # 3 # 0-255
|
||||
# M2 # 12 HIGH LOW # 11 # 0-255
|
||||
# M3 # 8 LOW HIGH # 5 # 0-255
|
||||
# M4 # 7 HIGH LOW # 6 # 0-255
|
||||
# Motor Direction(Forward/Backward) Speed Speed range
|
||||
# M1 4 LOW HIGH 3 0-255
|
||||
# M2 12 HIGH LOW 11 0-255
|
||||
# M3 8 LOW HIGH 5 0-255
|
||||
# M4 7 HIGH LOW 6 0-255
|
||||
|
||||
##
|
||||
# Moteur et portail
|
||||
|
@ -52,7 +52,7 @@ from porcou_lib import * # Bibliothèque utilisateur du portail coulissant
|
||||
brochage={
|
||||
'bp_ext' : ['d',6,'i'],'bp_int' : ['d',5,'i'],
|
||||
'fdc_o' : ['a',1,'i'],'fdc_f' : ['a',0,'i'],
|
||||
'mot_s' : ['d',4,'o'],'mot_v' : ['d',3,'o'],
|
||||
'mot_v' : ['d',3,'o'], 'mot_s' : ['d',4,'o'],
|
||||
'gyr' : ['d',2,'o'],
|
||||
'ir_emet' : ['d',7,'o'],'ir_recep' : ['d',8,'i']}
|
||||
|
||||
@ -102,12 +102,6 @@ def ouvrir():
|
||||
|
||||
def commandes():
|
||||
|
||||
# jumeau(brochage)
|
||||
|
||||
# while True :
|
||||
# gyr(True)
|
||||
# tempo(0.1) # Donne du temps à communication avec le jumeau réel
|
||||
|
||||
# Mise en place : Fermeture
|
||||
print ("Version avec sécurité : avec réouverture si bouton ou capteur barrage")
|
||||
print ("Mise en place : Fermeture")
|
||||
@ -116,7 +110,7 @@ def commandes():
|
||||
|
||||
# Jumelage
|
||||
print ("Attente")
|
||||
# jumeau(brochage)
|
||||
jumeau(brochage)
|
||||
|
||||
# Fonctionnement normal
|
||||
while True :
|
||||
|
Binary file not shown.
@ -27,20 +27,20 @@
|
||||
#include <Wire.h>
|
||||
#include <Firmata.h>
|
||||
|
||||
#define I2C_WRITE B00000000
|
||||
#define I2C_READ B00001000
|
||||
#define I2C_READ_CONTINUOUSLY B00010000
|
||||
#define I2C_STOP_READING B00011000
|
||||
#define I2C_READ_WRITE_MODE_MASK B00011000
|
||||
#define I2C_WRITE B00000000
|
||||
#define I2C_READ B00001000
|
||||
#define I2C_READ_CONTINUOUSLY B00010000
|
||||
#define I2C_STOP_READING B00011000
|
||||
#define I2C_READ_WRITE_MODE_MASK B00011000
|
||||
#define I2C_10BIT_ADDRESS_MODE_MASK B00100000
|
||||
#define I2C_END_TX_MASK B01000000
|
||||
#define I2C_STOP_TX 1
|
||||
#define I2C_RESTART_TX 0
|
||||
#define I2C_MAX_QUERIES 8
|
||||
#define I2C_REGISTER_NOT_SPECIFIED -1
|
||||
#define I2C_END_TX_MASK B01000000
|
||||
#define I2C_STOP_TX 1
|
||||
#define I2C_RESTART_TX 0
|
||||
#define I2C_MAX_QUERIES 8
|
||||
#define I2C_REGISTER_NOT_SPECIFIED -1
|
||||
|
||||
// the minimum interval for sampling analog input
|
||||
#define MINIMUM_SAMPLING_INTERVAL 1
|
||||
#define MINIMUM_SAMPLING_INTERVAL 1
|
||||
|
||||
|
||||
/*==============================================================================
|
||||
@ -52,19 +52,19 @@ SerialFirmata serialFeature;
|
||||
#endif
|
||||
|
||||
/* analog inputs */
|
||||
int analogInputsToReport = 0; // bitwise array to store pin reporting
|
||||
int analogInputsToReport = 0; // bitwise array to store pin reporting
|
||||
|
||||
/* digital input ports */
|
||||
byte reportPINs[TOTAL_PORTS]; // 1 = report this port, 0 = silence
|
||||
byte previousPINs[TOTAL_PORTS]; // previous 8 bits sent
|
||||
byte reportPINs[TOTAL_PORTS]; // 1 = report this port, 0 = silence
|
||||
byte previousPINs[TOTAL_PORTS]; // previous 8 bits sent
|
||||
|
||||
/* pins configuration */
|
||||
byte portConfigInputs[TOTAL_PORTS]; // each bit: 1 = pin in INPUT, 0 = anything else
|
||||
byte portConfigInputs[TOTAL_PORTS]; // each bit: 1 = pin in INPUT, 0 = anything else
|
||||
|
||||
/* timer variables */
|
||||
unsigned long currentMillis; // store the current value from millis()
|
||||
unsigned long previousMillis; // for comparison with currentMillis
|
||||
unsigned int samplingInterval = 19; // how often to run the main loop (in ms)
|
||||
unsigned long currentMillis; // store the current value from millis()
|
||||
unsigned long previousMillis; // for comparison with currentMillis
|
||||
unsigned int samplingInterval = 19; // how often to run the main loop (in ms)
|
||||
|
||||
/* i2c data */
|
||||
struct i2c_device_info {
|
||||
@ -95,11 +95,10 @@ boolean isResetting = false;
|
||||
// of the Arduino IDE.
|
||||
void setPinModeCallback(byte, int);
|
||||
void reportAnalogCallback(byte analogPin, int value);
|
||||
void sysexCallback(byte, byte, byte*);
|
||||
void sysexCallback(byte, byte, byte *);
|
||||
|
||||
/* utility functions */
|
||||
void wireWrite(byte data)
|
||||
{
|
||||
void wireWrite(byte data) {
|
||||
#if ARDUINO >= 100
|
||||
Wire.write((byte)data);
|
||||
#else
|
||||
@ -107,8 +106,7 @@ void wireWrite(byte data)
|
||||
#endif
|
||||
}
|
||||
|
||||
byte wireRead(void)
|
||||
{
|
||||
byte wireRead(void) {
|
||||
#if ARDUINO >= 100
|
||||
return Wire.read();
|
||||
#else
|
||||
@ -120,8 +118,7 @@ byte wireRead(void)
|
||||
* FUNCTIONS
|
||||
*============================================================================*/
|
||||
|
||||
void attachServo(byte pin, int minPulse, int maxPulse)
|
||||
{
|
||||
void attachServo(byte pin, int minPulse, int maxPulse) {
|
||||
if (servoCount < MAX_SERVOS) {
|
||||
// reuse indexes of detached servos until all have been reallocated
|
||||
if (detachedServoCount > 0) {
|
||||
@ -141,8 +138,7 @@ void attachServo(byte pin, int minPulse, int maxPulse)
|
||||
}
|
||||
}
|
||||
|
||||
void detachServo(byte pin)
|
||||
{
|
||||
void detachServo(byte pin) {
|
||||
servos[servoPinMap[pin]].detach();
|
||||
// if we're detaching the last servo, decrement the count
|
||||
// otherwise store the index of the detached servo
|
||||
@ -158,8 +154,7 @@ void detachServo(byte pin)
|
||||
servoPinMap[pin] = 255;
|
||||
}
|
||||
|
||||
void enableI2CPins()
|
||||
{
|
||||
void enableI2CPins() {
|
||||
byte i;
|
||||
// is there a faster way to do this? would probaby require importing
|
||||
// Arduino.h to get SCL and SDA pins
|
||||
@ -189,7 +184,7 @@ void readAndReportData(byte address, int theRegister, byte numBytes, byte stopTX
|
||||
if (theRegister != I2C_REGISTER_NOT_SPECIFIED) {
|
||||
Wire.beginTransmission(address);
|
||||
wireWrite((byte)theRegister);
|
||||
Wire.endTransmission(stopTX); // default = true
|
||||
Wire.endTransmission(stopTX); // default = true
|
||||
// do not set a value of 0
|
||||
if (i2cReadDelayTime > 0) {
|
||||
// delay is necessary for some devices such as WiiNunchuck
|
||||
@ -220,8 +215,7 @@ void readAndReportData(byte address, int theRegister, byte numBytes, byte stopTX
|
||||
Firmata.sendSysex(SYSEX_I2C_REPLY, numBytes + 2, i2cRxData);
|
||||
}
|
||||
|
||||
void outputPort(byte portNumber, byte portValue, byte forceSend)
|
||||
{
|
||||
void outputPort(byte portNumber, byte portValue, byte forceSend) {
|
||||
// pins not configured as INPUT are cleared to zeros
|
||||
portValue = portValue & portConfigInputs[portNumber];
|
||||
// only send if the value is different than previously sent
|
||||
@ -234,8 +228,7 @@ void outputPort(byte portNumber, byte portValue, byte forceSend)
|
||||
/* -----------------------------------------------------------------------------
|
||||
* check all the active digital inputs for change of state, then add any events
|
||||
* to the Serial output queue using Serial.print() */
|
||||
void checkDigitalInputs(void)
|
||||
{
|
||||
void checkDigitalInputs(void) {
|
||||
/* Using non-looping code allows constants to be given to readPort().
|
||||
* The compiler will apply substantial optimizations if the inputs
|
||||
* to readPort() are compile-time constants. */
|
||||
@ -261,8 +254,7 @@ void checkDigitalInputs(void)
|
||||
/* sets the pin mode to the correct state and sets the relevant bits in the
|
||||
* two bit-arrays that track Digital I/O and PWM status
|
||||
*/
|
||||
void setPinModeCallback(byte pin, int mode)
|
||||
{
|
||||
void setPinModeCallback(byte pin, int mode) {
|
||||
if (Firmata.getPinMode(pin) == PIN_MODE_IGNORE)
|
||||
return;
|
||||
|
||||
@ -277,7 +269,7 @@ void setPinModeCallback(byte pin, int mode)
|
||||
}
|
||||
}
|
||||
if (IS_PIN_ANALOG(pin)) {
|
||||
reportAnalogCallback(PIN_TO_ANALOG(pin), mode == PIN_MODE_ANALOG ? 1 : 0); // turn on/off reporting
|
||||
reportAnalogCallback(PIN_TO_ANALOG(pin), mode == PIN_MODE_ANALOG ? 1 : 0); // turn on/off reporting
|
||||
}
|
||||
if (IS_PIN_DIGITAL(pin)) {
|
||||
if (mode == INPUT || mode == PIN_MODE_PULLUP) {
|
||||
@ -291,10 +283,10 @@ void setPinModeCallback(byte pin, int mode)
|
||||
case PIN_MODE_ANALOG:
|
||||
if (IS_PIN_ANALOG(pin)) {
|
||||
if (IS_PIN_DIGITAL(pin)) {
|
||||
pinMode(PIN_TO_DIGITAL(pin), INPUT); // disable output driver
|
||||
pinMode(PIN_TO_DIGITAL(pin), INPUT); // disable output driver
|
||||
#if ARDUINO <= 100
|
||||
// deprecated since Arduino 1.0.1 - TODO: drop support in Firmata 2.6
|
||||
digitalWrite(PIN_TO_DIGITAL(pin), LOW); // disable internal pull-ups
|
||||
digitalWrite(PIN_TO_DIGITAL(pin), LOW); // disable internal pull-ups
|
||||
#endif
|
||||
}
|
||||
Firmata.setPinMode(pin, PIN_MODE_ANALOG);
|
||||
@ -302,10 +294,10 @@ void setPinModeCallback(byte pin, int mode)
|
||||
break;
|
||||
case INPUT:
|
||||
if (IS_PIN_DIGITAL(pin)) {
|
||||
pinMode(PIN_TO_DIGITAL(pin), INPUT); // disable output driver
|
||||
pinMode(PIN_TO_DIGITAL(pin), INPUT); // disable output driver
|
||||
#if ARDUINO <= 100
|
||||
// deprecated since Arduino 1.0.1 - TODO: drop support in Firmata 2.6
|
||||
digitalWrite(PIN_TO_DIGITAL(pin), LOW); // disable internal pull-ups
|
||||
digitalWrite(PIN_TO_DIGITAL(pin), LOW); // disable internal pull-ups
|
||||
#endif
|
||||
Firmata.setPinMode(pin, INPUT);
|
||||
}
|
||||
@ -357,7 +349,7 @@ void setPinModeCallback(byte pin, int mode)
|
||||
#endif
|
||||
break;
|
||||
default:
|
||||
Firmata.sendString("Unknown pin mode"); // TODO: put error msgs in EEPROM
|
||||
Firmata.sendString("Unknown pin mode"); // TODO: put error msgs in EEPROM
|
||||
}
|
||||
// TODO: save status to EEPROM here, if changed
|
||||
}
|
||||
@ -368,8 +360,7 @@ void setPinModeCallback(byte pin, int mode)
|
||||
* Can only be used on pins configured as OUTPUT.
|
||||
* Cannot be used to enable pull-ups on Digital INPUT pins.
|
||||
*/
|
||||
void setPinValueCallback(byte pin, int value)
|
||||
{
|
||||
void setPinValueCallback(byte pin, int value) {
|
||||
if (pin < TOTAL_PINS && IS_PIN_DIGITAL(pin)) {
|
||||
if (Firmata.getPinMode(pin) == OUTPUT) {
|
||||
Firmata.setPinState(pin, value);
|
||||
@ -378,8 +369,7 @@ void setPinValueCallback(byte pin, int value)
|
||||
}
|
||||
}
|
||||
|
||||
void analogWriteCallback(byte pin, int value)
|
||||
{
|
||||
void analogWriteCallback(byte pin, int value) {
|
||||
if (pin < TOTAL_PINS) {
|
||||
switch (Firmata.getPinMode(pin)) {
|
||||
case PIN_MODE_SERVO:
|
||||
@ -396,8 +386,7 @@ void analogWriteCallback(byte pin, int value)
|
||||
}
|
||||
}
|
||||
|
||||
void digitalWriteCallback(byte port, int value)
|
||||
{
|
||||
void digitalWriteCallback(byte port, int value) {
|
||||
byte pin, lastPin, pinValue, mask = 1, pinWriteMask = 0;
|
||||
|
||||
if (port < TOTAL_PORTS) {
|
||||
@ -436,11 +425,10 @@ void digitalWriteCallback(byte port, int value)
|
||||
*/
|
||||
//void FirmataClass::setAnalogPinReporting(byte pin, byte state) {
|
||||
//}
|
||||
void reportAnalogCallback(byte analogPin, int value)
|
||||
{
|
||||
void reportAnalogCallback(byte analogPin, int value) {
|
||||
if (analogPin < TOTAL_ANALOG_PINS) {
|
||||
if (value == 0) {
|
||||
analogInputsToReport = analogInputsToReport & ~ (1 << analogPin);
|
||||
analogInputsToReport = analogInputsToReport & ~(1 << analogPin);
|
||||
} else {
|
||||
analogInputsToReport = analogInputsToReport | (1 << analogPin);
|
||||
// prevent during system reset or all analog pin values will be reported
|
||||
@ -456,8 +444,7 @@ void reportAnalogCallback(byte analogPin, int value)
|
||||
// TODO: save status to EEPROM here, if changed
|
||||
}
|
||||
|
||||
void reportDigitalCallback(byte port, int value)
|
||||
{
|
||||
void reportDigitalCallback(byte port, int value) {
|
||||
if (port < TOTAL_PORTS) {
|
||||
reportPINs[port] = (byte)value;
|
||||
// Send port value immediately. This is helpful when connected via
|
||||
@ -477,8 +464,7 @@ void reportDigitalCallback(byte port, int value)
|
||||
* SYSEX-BASED commands
|
||||
*============================================================================*/
|
||||
|
||||
void sysexCallback(byte command, byte argc, byte *argv)
|
||||
{
|
||||
void sysexCallback(byte command, byte argc, byte *argv) {
|
||||
byte mode;
|
||||
byte stopTX;
|
||||
byte slaveAddress;
|
||||
@ -492,8 +478,7 @@ void sysexCallback(byte command, byte argc, byte *argv)
|
||||
if (argv[1] & I2C_10BIT_ADDRESS_MODE_MASK) {
|
||||
Firmata.sendString("10-bit addressing not supported");
|
||||
return;
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
slaveAddress = argv[0];
|
||||
}
|
||||
|
||||
@ -501,9 +486,8 @@ void sysexCallback(byte command, byte argc, byte *argv)
|
||||
// libraries that have not updated to add support for restart tx
|
||||
if (argv[1] & I2C_END_TX_MASK) {
|
||||
stopTX = I2C_RESTART_TX;
|
||||
}
|
||||
else {
|
||||
stopTX = I2C_STOP_TX; // default
|
||||
} else {
|
||||
stopTX = I2C_STOP_TX; // default
|
||||
}
|
||||
|
||||
switch (mode) {
|
||||
@ -521,8 +505,7 @@ void sysexCallback(byte command, byte argc, byte *argv)
|
||||
// a slave register is specified
|
||||
slaveRegister = argv[2] + (argv[3] << 7);
|
||||
data = argv[4] + (argv[5] << 7); // bytes to read
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
// a slave register is NOT specified
|
||||
slaveRegister = I2C_REGISTER_NOT_SPECIFIED;
|
||||
data = argv[2] + (argv[3] << 7); // bytes to read
|
||||
@ -539,8 +522,7 @@ void sysexCallback(byte command, byte argc, byte *argv)
|
||||
// a slave register is specified
|
||||
slaveRegister = argv[2] + (argv[3] << 7);
|
||||
data = argv[4] + (argv[5] << 7); // bytes to read
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
// a slave register is NOT specified
|
||||
slaveRegister = (int)I2C_REGISTER_NOT_SPECIFIED;
|
||||
data = argv[2] + (argv[3] << 7); // bytes to read
|
||||
@ -644,7 +626,7 @@ void sysexCallback(byte command, byte argc, byte *argv)
|
||||
}
|
||||
if (IS_PIN_ANALOG(pin)) {
|
||||
Firmata.write(PIN_MODE_ANALOG);
|
||||
Firmata.write(10); // 10 = 10-bit resolution
|
||||
Firmata.write(10); // 10 = 10-bit resolution
|
||||
}
|
||||
if (IS_PIN_PWM(pin)) {
|
||||
Firmata.write(PIN_MODE_PWM);
|
||||
@ -701,8 +683,7 @@ void sysexCallback(byte command, byte argc, byte *argv)
|
||||
* SETUP()
|
||||
*============================================================================*/
|
||||
|
||||
void systemResetCallback()
|
||||
{
|
||||
void systemResetCallback() {
|
||||
isResetting = true;
|
||||
|
||||
// initialize a defalt state
|
||||
@ -753,8 +734,7 @@ void systemResetCallback()
|
||||
isResetting = false;
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
void setup() {
|
||||
Firmata.setFirmwareVersion(FIRMATA_FIRMWARE_MAJOR_VERSION, FIRMATA_FIRMWARE_MINOR_VERSION);
|
||||
|
||||
Firmata.attach(ANALOG_MESSAGE, analogWriteCallback);
|
||||
@ -774,7 +754,7 @@ void setup()
|
||||
|
||||
Firmata.begin(57600);
|
||||
while (!Serial) {
|
||||
; // wait for serial port to connect. Needed for ATmega32u4-based boards and Arduino 101
|
||||
; // wait for serial port to connect. Needed for ATmega32u4-based boards and Arduino 101
|
||||
}
|
||||
|
||||
systemResetCallback(); // reset to default config
|
||||
@ -783,8 +763,7 @@ void setup()
|
||||
/*==============================================================================
|
||||
* LOOP()
|
||||
*============================================================================*/
|
||||
void loop()
|
||||
{
|
||||
void loop() {
|
||||
byte pin, analogPin;
|
||||
|
||||
/* DIGITALREAD - as fast as possible, check for changes and output them to the
|
47
portail_coulissant/test/shield_motor-test.py
Normal file
47
portail_coulissant/test/shield_motor-test.py
Normal file
@ -0,0 +1,47 @@
|
||||
import pyfirmata
|
||||
import time
|
||||
|
||||
###############################################################################
|
||||
# shield_motor-test :
|
||||
# @title: Test de pilotage du moteur en pyFirmata par le shield moteur Arduino CC 4 x 1,2 A DRI0039 (DFROBOT)
|
||||
# @project: Blender-EduTech
|
||||
# @lang: fr
|
||||
# @authors: Philippe Roy <philippe.roy@ac-grenoble.fr>
|
||||
# @copyright: Copyright (C) 2024 Philippe Roy
|
||||
# @license: GNU GPL
|
||||
###############################################################################
|
||||
|
||||
# Communication avec la carte Arduino
|
||||
# carte = pyfirmata.Arduino('COM3') # Windows
|
||||
carte = pyfirmata.Arduino('/dev/ttyACM0') # GNU/Linux
|
||||
print("Communication Carte Arduino établie")
|
||||
|
||||
# Motor Direction(Forward/Backward) Speed Speed range
|
||||
# M1 4 LOW HIGH 3 0-255
|
||||
# M2 12 HIGH LOW 11 0-255
|
||||
# M3 8 LOW HIGH 5 0-255
|
||||
# M4 7 HIGH LOW 6 0-255
|
||||
|
||||
mot_v = carte.get_pin('d:3:p') # Vitesse du M1 sur la broche D3 en PWM
|
||||
mot_s = carte.get_pin('d:4:o') # Sens du M1 sur la broche D4
|
||||
|
||||
try :
|
||||
while True: # Boucle infinie
|
||||
print ("Moteur M1 sens LOW vitesse 255")
|
||||
mot_s.write(0)
|
||||
mot_v.write(1)
|
||||
time.sleep(1)
|
||||
print ("Moteur M1 sens LOW vitesse 0")
|
||||
mot_s.write(0)
|
||||
mot_v.write(0)
|
||||
time.sleep(1)
|
||||
print ("Moteur M1 sens HIGH vitesse 255/2")
|
||||
mot_s.write(1)
|
||||
mot_v.write(0.5)
|
||||
time.sleep(1)
|
||||
print ("Moteur M1 sens HIGH vitesse 0")
|
||||
mot_s.write(0)
|
||||
mot_v.write(0)
|
||||
time.sleep(1)
|
||||
except :
|
||||
carte.exit()
|
Loading…
Reference in New Issue
Block a user