mirror of
https://forge.apps.education.fr/blender-edutech/jumeaux-numeriques.git
synced 2024-01-27 06:56:18 +01:00
Programme Arduino spécifique
This commit is contained in:
parent
7ac5d4ec70
commit
d1578805fb
@ -0,0 +1,127 @@
|
|||||||
|
#include "Grove_Motor_Driver_TB6612FNG.h"
|
||||||
|
|
||||||
|
MotorDriver::MotorDriver() {
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorDriver::init(uint8_t addr) {
|
||||||
|
_addr = addr;
|
||||||
|
standby();
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorDriver::standby() {
|
||||||
|
I2Cdev::writeByte(_addr, GROVE_MOTOR_DRIVER_I2C_CMD_STANDBY, 0);
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorDriver::notStandby() {
|
||||||
|
I2Cdev::writeByte(_addr, GROVE_MOTOR_DRIVER_I2C_CMD_NOT_STANDBY, 0);
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorDriver::setI2cAddr(uint8_t addr) {
|
||||||
|
if (addr == 0x00) {
|
||||||
|
return;
|
||||||
|
} else if (addr >= 0x80) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
I2Cdev::writeByte(_addr, GROVE_MOTOR_DRIVER_I2C_CMD_SET_ADDR, addr);
|
||||||
|
_addr = addr;
|
||||||
|
delay(100);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorDriver::dcMotorRun(motor_channel_type_t chl, int16_t speed) {
|
||||||
|
if (speed > 255) {
|
||||||
|
speed = 255;
|
||||||
|
} else if (speed < -255) {
|
||||||
|
speed = -255;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (speed >= 0) {
|
||||||
|
_buffer[0] = GROVE_MOTOR_DRIVER_I2C_CMD_CW;
|
||||||
|
} else {
|
||||||
|
_buffer[0] = GROVE_MOTOR_DRIVER_I2C_CMD_CCW;
|
||||||
|
}
|
||||||
|
|
||||||
|
_buffer[1] = chl;
|
||||||
|
if (speed >= 0) {
|
||||||
|
_buffer[2] = speed;
|
||||||
|
} else {
|
||||||
|
_buffer[2] = (uint8_t)(-speed);
|
||||||
|
}
|
||||||
|
|
||||||
|
I2Cdev::writeBytes(_addr, _buffer[0], 2, _buffer + 1);
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorDriver::dcMotorBrake(motor_channel_type_t chl) {
|
||||||
|
I2Cdev::writeByte(_addr, GROVE_MOTOR_DRIVER_I2C_CMD_BRAKE, chl);
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorDriver::dcMotorStop(motor_channel_type_t chl) {
|
||||||
|
I2Cdev::writeByte(_addr, GROVE_MOTOR_DRIVER_I2C_CMD_STOP, chl);
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorDriver::stepperRun(stepper_mode_type_t mode, int16_t steps, uint16_t rpm) {
|
||||||
|
uint8_t cw = 0;
|
||||||
|
// 0.1ms_per_step
|
||||||
|
uint16_t ms_per_step = 0;
|
||||||
|
|
||||||
|
if (steps > 0) {
|
||||||
|
cw = 1;
|
||||||
|
}
|
||||||
|
// stop
|
||||||
|
else if (steps == 0) {
|
||||||
|
stepperStop();
|
||||||
|
return;
|
||||||
|
} else if (steps == -32768) {
|
||||||
|
steps = 32767;
|
||||||
|
} else {
|
||||||
|
steps = -steps;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (rpm < 1) {
|
||||||
|
rpm = 1;
|
||||||
|
} else if (rpm > 300) {
|
||||||
|
rpm = 300;
|
||||||
|
}
|
||||||
|
|
||||||
|
ms_per_step = (uint16_t)(3000.0 / (float)rpm);
|
||||||
|
_buffer[0] = mode;
|
||||||
|
_buffer[1] = cw; //(cw=1) => cw; (cw=0) => ccw
|
||||||
|
_buffer[2] = steps;
|
||||||
|
_buffer[3] = (steps >> 8);
|
||||||
|
_buffer[4] = ms_per_step;
|
||||||
|
_buffer[5] = (ms_per_step >> 8);
|
||||||
|
|
||||||
|
I2Cdev::writeBytes(_addr, GROVE_MOTOR_DRIVER_I2C_CMD_STEPPER_RUN, 6, _buffer);
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorDriver::stepperStop() {
|
||||||
|
I2Cdev::writeByte(_addr, GROVE_MOTOR_DRIVER_I2C_CMD_STEPPER_STOP, 0);
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorDriver::stepperKeepRun(stepper_mode_type_t mode, uint16_t rpm, bool is_cw) {
|
||||||
|
// 4=>infinite ccw 5=>infinite cw
|
||||||
|
uint8_t cw = (is_cw) ? 5 : 4;
|
||||||
|
// 0.1ms_per_step
|
||||||
|
uint16_t ms_per_step = 0;
|
||||||
|
|
||||||
|
if (rpm < 1) {
|
||||||
|
rpm = 1;
|
||||||
|
} else if (rpm > 300) {
|
||||||
|
rpm = 300;
|
||||||
|
}
|
||||||
|
ms_per_step = (uint16_t)(3000.0 / (float)rpm);
|
||||||
|
|
||||||
|
_buffer[0] = mode;
|
||||||
|
_buffer[1] = cw; //(cw=1) => cw; (cw=0) => ccw
|
||||||
|
_buffer[2] = ms_per_step;
|
||||||
|
_buffer[3] = (ms_per_step >> 8);
|
||||||
|
|
||||||
|
I2Cdev::writeBytes(_addr, GROVE_MOTOR_DRIVER_I2C_CMD_STEPPER_KEEP_RUN, 4, _buffer);
|
||||||
|
delay(1);
|
||||||
|
}
|
183
portail_coulissant/porcou-arduino/Grove_Motor_Driver_TB6612FNG.h
Normal file
183
portail_coulissant/porcou-arduino/Grove_Motor_Driver_TB6612FNG.h
Normal file
@ -0,0 +1,183 @@
|
|||||||
|
/*
|
||||||
|
Grove_Motor_Driver_TB6612FNG.h
|
||||||
|
A library for the Grove - Motor Driver(TB6612FNG)
|
||||||
|
|
||||||
|
Copyright (c) 2018 seeed technology co., ltd.
|
||||||
|
Website : www.seeed.cc
|
||||||
|
Author : Jerry Yip
|
||||||
|
Create Time: 2018-06
|
||||||
|
Version : 0.1
|
||||||
|
Change Log :
|
||||||
|
|
||||||
|
The MIT License (MIT)
|
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
of this software and associated documentation files (the "Software"), to deal
|
||||||
|
in the Software without restriction, including without limitation the rights
|
||||||
|
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
copies of the Software, and to permit persons to whom the Software is
|
||||||
|
furnished to do so, subject to the following conditions:
|
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in
|
||||||
|
all copies or substantial portions of the Software.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
THE SOFTWARE.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef __GROVE_MOTOR_DRIVER_TB6612FNG_H__
|
||||||
|
#define __GROVE_MOTOR_DRIVER_TB6612FNG_H__
|
||||||
|
|
||||||
|
#include "I2Cdev.h"
|
||||||
|
|
||||||
|
#define GROVE_MOTOR_DRIVER_DEFAULT_I2C_ADDR 0x14
|
||||||
|
|
||||||
|
#define GROVE_MOTOR_DRIVER_DEFAULT_I2C_ADDR 0x14
|
||||||
|
#define GROVE_MOTOR_DRIVER_I2C_CMD_BRAKE 0x00
|
||||||
|
#define GROVE_MOTOR_DRIVER_I2C_CMD_STOP 0x01
|
||||||
|
#define GROVE_MOTOR_DRIVER_I2C_CMD_CW 0x02
|
||||||
|
#define GROVE_MOTOR_DRIVER_I2C_CMD_CCW 0x03
|
||||||
|
#define GROVE_MOTOR_DRIVER_I2C_CMD_STANDBY 0x04
|
||||||
|
#define GROVE_MOTOR_DRIVER_I2C_CMD_NOT_STANDBY 0x05
|
||||||
|
#define GROVE_MOTOR_DRIVER_I2C_CMD_STEPPER_RUN 0x06
|
||||||
|
#define GROVE_MOTOR_DRIVER_I2C_CMD_STEPPER_STOP 0x07
|
||||||
|
#define GROVE_MOTOR_DRIVER_I2C_CMD_STEPPER_KEEP_RUN 0x08
|
||||||
|
#define GROVE_MOTOR_DRIVER_I2C_CMD_SET_ADDR 0x11
|
||||||
|
|
||||||
|
|
||||||
|
enum motor_channel_type_t {
|
||||||
|
MOTOR_CHA = 0,
|
||||||
|
MOTOR_CHB = 1,
|
||||||
|
};
|
||||||
|
|
||||||
|
enum stepper_mode_type_t {
|
||||||
|
FULL_STEP = 0,
|
||||||
|
WAVE_DRIVE = 1,
|
||||||
|
HALF_STEP = 2,
|
||||||
|
MICRO_STEPPING = 3,
|
||||||
|
};
|
||||||
|
|
||||||
|
class MotorDriver {
|
||||||
|
public:
|
||||||
|
MotorDriver();
|
||||||
|
|
||||||
|
void init(uint8_t addr = GROVE_MOTOR_DRIVER_DEFAULT_I2C_ADDR);
|
||||||
|
|
||||||
|
/*************************************************************
|
||||||
|
Description
|
||||||
|
Enter standby mode. Normally you don't need to call this, except that
|
||||||
|
you have called notStandby() before.
|
||||||
|
Parameter
|
||||||
|
Null.
|
||||||
|
Return
|
||||||
|
Null.
|
||||||
|
*************************************************************/
|
||||||
|
void standby();
|
||||||
|
|
||||||
|
/*************************************************************
|
||||||
|
Description
|
||||||
|
Exit standby mode. Motor driver does't do any action at this mode.
|
||||||
|
Parameter
|
||||||
|
Null.
|
||||||
|
Return
|
||||||
|
Null.
|
||||||
|
*************************************************************/
|
||||||
|
void notStandby();
|
||||||
|
|
||||||
|
/*************************************************************
|
||||||
|
Description
|
||||||
|
Set an new I2C address.
|
||||||
|
Parameter
|
||||||
|
addr: 0x01~0x7f
|
||||||
|
Return
|
||||||
|
Null.
|
||||||
|
*************************************************************/
|
||||||
|
void setI2cAddr(uint8_t addr);
|
||||||
|
|
||||||
|
/*************************************************************
|
||||||
|
Description
|
||||||
|
Drive a motor.
|
||||||
|
Parameter
|
||||||
|
chl: MOTOR_CHA or MOTOR_CHB
|
||||||
|
speed: -255~255, if speed > 0, motor moves clockwise.
|
||||||
|
Note that there is always a starting speed(a starting voltage) for motor.
|
||||||
|
If the input voltage is 5V, the starting speed should larger than 100 or
|
||||||
|
smaller than -100.
|
||||||
|
Return
|
||||||
|
Null.
|
||||||
|
*************************************************************/
|
||||||
|
void dcMotorRun(motor_channel_type_t chl, int16_t speed);
|
||||||
|
|
||||||
|
/*************************************************************
|
||||||
|
Description
|
||||||
|
Brake, stop the motor immediately
|
||||||
|
Parameter
|
||||||
|
chl: MOTOR_CHA or MOTOR_CHB
|
||||||
|
Return
|
||||||
|
Null.
|
||||||
|
*************************************************************/
|
||||||
|
void dcMotorBrake(motor_channel_type_t chl);
|
||||||
|
|
||||||
|
/*************************************************************
|
||||||
|
Description
|
||||||
|
Stop the motor slowly.
|
||||||
|
Parameter
|
||||||
|
chl: MOTOR_CHA or MOTOR_CHB
|
||||||
|
Return
|
||||||
|
Null.
|
||||||
|
*************************************************************/
|
||||||
|
void dcMotorStop(motor_channel_type_t chl);
|
||||||
|
|
||||||
|
/*************************************************************
|
||||||
|
Description
|
||||||
|
Drive a stepper.
|
||||||
|
Parameter
|
||||||
|
mode: 4 driver mode: FULL_STEP,WAVE_DRIVE, HALF_STEP, MICRO_STEPPING,
|
||||||
|
for more information: https://en.wikipedia.org/wiki/Stepper_motor#/media/File:Drive.png
|
||||||
|
steps: The number of steps to run, range from -32768 to 32767.
|
||||||
|
When steps = 0, the stepper stops.
|
||||||
|
When steps > 0, the stepper runs clockwise. When steps < 0, the stepper runs anticlockwise.
|
||||||
|
rpm: Revolutions per minute, the speed of a stepper, range from 1 to 300.
|
||||||
|
Note that high rpm will lead to step lose, so rpm should not be larger than 150.
|
||||||
|
Return
|
||||||
|
Null.
|
||||||
|
*************************************************************/
|
||||||
|
void stepperRun(stepper_mode_type_t mode, int16_t steps, uint16_t rpm);
|
||||||
|
|
||||||
|
/*************************************************************
|
||||||
|
Description
|
||||||
|
Stop a stepper.
|
||||||
|
Parameter
|
||||||
|
Null.
|
||||||
|
Return
|
||||||
|
Null.
|
||||||
|
*************************************************************/
|
||||||
|
void stepperStop();
|
||||||
|
|
||||||
|
// keeps moving(direction same as the last move, default to clockwise)
|
||||||
|
/*************************************************************
|
||||||
|
Description
|
||||||
|
Keep a stepper running.
|
||||||
|
Parameter
|
||||||
|
mode: 4 driver mode: FULL_STEP,WAVE_DRIVE, HALF_STEP, MICRO_STEPPING,
|
||||||
|
for more information: https://en.wikipedia.org/wiki/Stepper_motor#/media/File:Drive.png
|
||||||
|
rpm: Revolutions per minute, the speed of a stepper, range from 1 to 300.
|
||||||
|
Note that high rpm will lead to step lose, so rpm should not be larger than 150.
|
||||||
|
is_cw: Set the running direction, true for clockwise and false for anti-clockwise.
|
||||||
|
|
||||||
|
Return
|
||||||
|
Null.
|
||||||
|
*************************************************************/
|
||||||
|
void stepperKeepRun(stepper_mode_type_t mode, uint16_t rpm, bool is_cw);
|
||||||
|
|
||||||
|
private:
|
||||||
|
uint8_t _addr;
|
||||||
|
uint8_t _buffer[16];
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif //__GROVE_MOTOR_DRIVER_TB6612FNG_H__
|
83
portail_coulissant/porcou-arduino/I2CScanner/I2CScanner.ino
Normal file
83
portail_coulissant/porcou-arduino/I2CScanner/I2CScanner.ino
Normal file
@ -0,0 +1,83 @@
|
|||||||
|
// --------------------------------------
|
||||||
|
// i2c_scanner
|
||||||
|
//
|
||||||
|
// Version 1
|
||||||
|
// This program (or code that looks like it)
|
||||||
|
// can be found in many places.
|
||||||
|
// For example on the Arduino.cc forum.
|
||||||
|
// The original author is not know.
|
||||||
|
// Version 2, Juni 2012, Using Arduino 1.0.1
|
||||||
|
// Adapted to be as simple as possible by Arduino.cc user Krodal
|
||||||
|
// Version 3, Feb 26 2013
|
||||||
|
// V3 by louarnold
|
||||||
|
// Version 4, March 3, 2013, Using Arduino 1.0.3
|
||||||
|
// by Arduino.cc user Krodal.
|
||||||
|
// Changes by louarnold removed.
|
||||||
|
// Scanning addresses changed from 0...127 to 1...119,
|
||||||
|
// according to the i2c scanner by Nick Gammon
|
||||||
|
// https://www.gammon.com.au/forum/?id=10896
|
||||||
|
// Version 5, March 28, 2013
|
||||||
|
// As version 4, but address scans now to 127.
|
||||||
|
// A sensor seems to use address 120.
|
||||||
|
// Version 6, November 27, 2015.
|
||||||
|
// Added waiting for the Leonardo serial communication.
|
||||||
|
//
|
||||||
|
//
|
||||||
|
// This sketch tests the standard 7-bit addresses
|
||||||
|
// Devices with higher bit address might not be seen properly.
|
||||||
|
//
|
||||||
|
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
Wire.begin();
|
||||||
|
|
||||||
|
Serial.begin(9600);
|
||||||
|
while (!Serial); // Leonardo: wait for serial monitor
|
||||||
|
Serial.println("\nI2C Scanner");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
byte error, address;
|
||||||
|
int nDevices;
|
||||||
|
|
||||||
|
Serial.println("Scanning...");
|
||||||
|
|
||||||
|
nDevices = 0;
|
||||||
|
for(address = 1; address < 127; address++ )
|
||||||
|
{
|
||||||
|
// The i2c_scanner uses the return value of
|
||||||
|
// the Write.endTransmisstion to see if
|
||||||
|
// a device did acknowledge to the address.
|
||||||
|
Wire.beginTransmission(address);
|
||||||
|
error = Wire.endTransmission();
|
||||||
|
|
||||||
|
if (error == 0)
|
||||||
|
{
|
||||||
|
Serial.print("I2C device found at address 0x");
|
||||||
|
if (address<16)
|
||||||
|
Serial.print("0");
|
||||||
|
Serial.print(address,HEX);
|
||||||
|
Serial.println(" !");
|
||||||
|
|
||||||
|
nDevices++;
|
||||||
|
}
|
||||||
|
else if (error==4)
|
||||||
|
{
|
||||||
|
Serial.print("Unknown error at address 0x");
|
||||||
|
if (address<16)
|
||||||
|
Serial.print("0");
|
||||||
|
Serial.println(address,HEX);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (nDevices == 0)
|
||||||
|
Serial.println("No I2C devices found\n");
|
||||||
|
else
|
||||||
|
Serial.println("done\n");
|
||||||
|
|
||||||
|
delay(5000); // wait 5 seconds for next scan
|
||||||
|
}
|
1466
portail_coulissant/porcou-arduino/I2Cdev.cpp
Executable file
1466
portail_coulissant/porcou-arduino/I2Cdev.cpp
Executable file
File diff suppressed because it is too large
Load Diff
274
portail_coulissant/porcou-arduino/I2Cdev.h
Executable file
274
portail_coulissant/porcou-arduino/I2Cdev.h
Executable file
@ -0,0 +1,274 @@
|
|||||||
|
// I2Cdev library collection - Main I2C device class header file
|
||||||
|
// Abstracts bit and byte I2C R/W functions into a convenient class
|
||||||
|
// 6/9/2012 by Jeff Rowberg <jeff@rowberg.net>
|
||||||
|
//
|
||||||
|
// Changelog:
|
||||||
|
// 2012-06-09 - fix major issue with reading > 32 bytes at a time with Arduino Wire
|
||||||
|
// - add compiler warnings when using outdated or IDE or limited I2Cdev implementation
|
||||||
|
// 2011-11-01 - fix write*Bits mask calculation (thanks sasquatch @ Arduino forums)
|
||||||
|
// 2011-10-03 - added automatic Arduino version detection for ease of use
|
||||||
|
// 2011-10-02 - added Gene Knight's NBWire TwoWire class implementation with small modifications
|
||||||
|
// 2011-08-31 - added support for Arduino 1.0 Wire library (methods are different from 0.x)
|
||||||
|
// 2011-08-03 - added optional timeout parameter to read* methods to easily change from default
|
||||||
|
// 2011-08-02 - added support for 16-bit registers
|
||||||
|
// - fixed incorrect Doxygen comments on some methods
|
||||||
|
// - added timeout value for read operations (thanks mem @ Arduino forums)
|
||||||
|
// 2011-07-30 - changed read/write function structures to return success or byte counts
|
||||||
|
// - made all methods static for multi-device memory savings
|
||||||
|
// 2011-07-28 - initial release
|
||||||
|
|
||||||
|
/* ============================================
|
||||||
|
I2Cdev device library code is placed under the MIT license
|
||||||
|
Copyright (c) 2012 Jeff Rowberg
|
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
of this software and associated documentation files (the "Software"), to deal
|
||||||
|
in the Software without restriction, including without limitation the rights
|
||||||
|
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
copies of the Software, and to permit persons to whom the Software is
|
||||||
|
furnished to do so, subject to the following conditions:
|
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in
|
||||||
|
all copies or substantial portions of the Software.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
THE SOFTWARE.
|
||||||
|
===============================================
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _I2CDEV_H_
|
||||||
|
#define _I2CDEV_H_
|
||||||
|
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
// I2C interface implementation setting
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
#define I2CDEV_IMPLEMENTATION I2CDEV_ARDUINO_WIRE
|
||||||
|
|
||||||
|
// comment this out if you are using a non-optimal IDE/implementation setting
|
||||||
|
// but want the compiler to shut up about it
|
||||||
|
#define I2CDEV_IMPLEMENTATION_WARNINGS
|
||||||
|
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
// I2C interface implementation options
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
#define I2CDEV_ARDUINO_WIRE 1 // Wire object from Arduino
|
||||||
|
#define I2CDEV_BUILTIN_NBWIRE 2 // Tweaked Wire object from Gene Knight's NBWire project
|
||||||
|
// ^^^ NBWire implementation is still buggy w/some interrupts!
|
||||||
|
#define I2CDEV_BUILTIN_FASTWIRE 3 // FastWire object from Francesco Ferrara's project
|
||||||
|
// ^^^ FastWire implementation in I2Cdev is INCOMPLETE!
|
||||||
|
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
// Arduino-style "Serial.print" debug constant (uncomment to enable)
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
//#define I2CDEV_SERIAL_DEBUG
|
||||||
|
|
||||||
|
#ifdef ARDUINO
|
||||||
|
#if ARDUINO < 100
|
||||||
|
#include "WProgram.h"
|
||||||
|
#else
|
||||||
|
#include "Arduino.h"
|
||||||
|
#endif
|
||||||
|
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
|
||||||
|
#include <Wire.h>
|
||||||
|
#ifndef BUFFER_LENGTH
|
||||||
|
#define BUFFER_LENGTH 32
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#include "ArduinoWrapper.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(ESP8266) || defined(ESP32)
|
||||||
|
#define min(x,y) _min(x,y)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// 1000ms default read timeout (modify with "I2Cdev::readTimeout = [ms];")
|
||||||
|
#define I2CDEV_DEFAULT_READ_TIMEOUT 1000
|
||||||
|
|
||||||
|
class I2Cdev {
|
||||||
|
public:
|
||||||
|
I2Cdev();
|
||||||
|
|
||||||
|
static int8_t readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t* data,
|
||||||
|
uint16_t timeout = I2Cdev::readTimeout);
|
||||||
|
static int8_t readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t* data,
|
||||||
|
uint16_t timeout = I2Cdev::readTimeout);
|
||||||
|
static int8_t readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t* data,
|
||||||
|
uint16_t timeout = I2Cdev::readTimeout);
|
||||||
|
static int8_t readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t* data,
|
||||||
|
uint16_t timeout = I2Cdev::readTimeout);
|
||||||
|
static int8_t readByte(uint8_t devAddr, uint8_t regAddr, uint8_t* data, uint16_t timeout = I2Cdev::readTimeout);
|
||||||
|
static int8_t readWord(uint8_t devAddr, uint8_t regAddr, uint16_t* data, uint16_t timeout = I2Cdev::readTimeout);
|
||||||
|
static int8_t readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t* data,
|
||||||
|
uint16_t timeout = I2Cdev::readTimeout);
|
||||||
|
static int8_t readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t* data,
|
||||||
|
uint16_t timeout = I2Cdev::readTimeout);
|
||||||
|
|
||||||
|
static bool writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data);
|
||||||
|
static bool writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data);
|
||||||
|
static bool writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data);
|
||||||
|
static bool writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data);
|
||||||
|
static bool writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data);
|
||||||
|
static bool writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data);
|
||||||
|
static bool writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t* data);
|
||||||
|
static bool writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t* data);
|
||||||
|
|
||||||
|
static uint16_t readTimeout;
|
||||||
|
};
|
||||||
|
|
||||||
|
#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
|
||||||
|
//////////////////////
|
||||||
|
// FastWire 0.2
|
||||||
|
// This is a library to help faster programs to read I2C devices.
|
||||||
|
// Copyright(C) 2011
|
||||||
|
// Francesco Ferrara
|
||||||
|
//////////////////////
|
||||||
|
|
||||||
|
/* Master */
|
||||||
|
#define TW_START 0x08
|
||||||
|
#define TW_REP_START 0x10
|
||||||
|
|
||||||
|
/* Master Transmitter */
|
||||||
|
#define TW_MT_SLA_ACK 0x18
|
||||||
|
#define TW_MT_SLA_NACK 0x20
|
||||||
|
#define TW_MT_DATA_ACK 0x28
|
||||||
|
#define TW_MT_DATA_NACK 0x30
|
||||||
|
#define TW_MT_ARB_LOST 0x38
|
||||||
|
|
||||||
|
/* Master Receiver */
|
||||||
|
#define TW_MR_ARB_LOST 0x38
|
||||||
|
#define TW_MR_SLA_ACK 0x40
|
||||||
|
#define TW_MR_SLA_NACK 0x48
|
||||||
|
#define TW_MR_DATA_ACK 0x50
|
||||||
|
#define TW_MR_DATA_NACK 0x58
|
||||||
|
|
||||||
|
#define TW_OK 0
|
||||||
|
#define TW_ERROR 1
|
||||||
|
|
||||||
|
class Fastwire {
|
||||||
|
private:
|
||||||
|
static boolean waitInt();
|
||||||
|
|
||||||
|
public:
|
||||||
|
static void setup(int khz, boolean pullup);
|
||||||
|
static byte write(byte device, byte address, byte value);
|
||||||
|
static byte readBuf(byte device, byte address, byte* data, byte num);
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE
|
||||||
|
// NBWire implementation based heavily on code by Gene Knight <Gene@Telobot.com>
|
||||||
|
// Originally posted on the Arduino forum at http://arduino.cc/forum/index.php/topic,70705.0.html
|
||||||
|
// Originally offered to the i2cdevlib project at http://arduino.cc/forum/index.php/topic,68210.30.html
|
||||||
|
|
||||||
|
#define NBWIRE_BUFFER_LENGTH 32
|
||||||
|
|
||||||
|
class TwoWire {
|
||||||
|
private:
|
||||||
|
static uint8_t rxBuffer[];
|
||||||
|
static uint8_t rxBufferIndex;
|
||||||
|
static uint8_t rxBufferLength;
|
||||||
|
|
||||||
|
static uint8_t txAddress;
|
||||||
|
static uint8_t txBuffer[];
|
||||||
|
static uint8_t txBufferIndex;
|
||||||
|
static uint8_t txBufferLength;
|
||||||
|
|
||||||
|
// static uint8_t transmitting;
|
||||||
|
static void (*user_onRequest)(void);
|
||||||
|
static void (*user_onReceive)(int);
|
||||||
|
static void onRequestService(void);
|
||||||
|
static void onReceiveService(uint8_t*, int);
|
||||||
|
|
||||||
|
public:
|
||||||
|
TwoWire();
|
||||||
|
void begin();
|
||||||
|
void begin(uint8_t);
|
||||||
|
void begin(int);
|
||||||
|
void beginTransmission(uint8_t);
|
||||||
|
//void beginTransmission(int);
|
||||||
|
uint8_t endTransmission(uint16_t timeout = 0);
|
||||||
|
void nbendTransmission(void (*function)(int)) ;
|
||||||
|
uint8_t requestFrom(uint8_t, int, uint16_t timeout = 0);
|
||||||
|
//uint8_t requestFrom(int, int);
|
||||||
|
void nbrequestFrom(uint8_t, int, void (*function)(int));
|
||||||
|
void send(uint8_t);
|
||||||
|
void send(uint8_t*, uint8_t);
|
||||||
|
//void send(int);
|
||||||
|
void send(char*);
|
||||||
|
uint8_t available(void);
|
||||||
|
uint8_t receive(void);
|
||||||
|
void onReceive(void (*)(int));
|
||||||
|
void onRequest(void (*)(void));
|
||||||
|
};
|
||||||
|
|
||||||
|
#define TWI_READY 0
|
||||||
|
#define TWI_MRX 1
|
||||||
|
#define TWI_MTX 2
|
||||||
|
#define TWI_SRX 3
|
||||||
|
#define TWI_STX 4
|
||||||
|
|
||||||
|
#define TW_WRITE 0
|
||||||
|
#define TW_READ 1
|
||||||
|
|
||||||
|
#define TW_MT_SLA_NACK 0x20
|
||||||
|
#define TW_MT_DATA_NACK 0x30
|
||||||
|
|
||||||
|
#define CPU_FREQ 16000000L
|
||||||
|
#define TWI_FREQ 100000L
|
||||||
|
#define TWI_BUFFER_LENGTH 32
|
||||||
|
|
||||||
|
/* TWI Status is in TWSR, in the top 5 bits: TWS7 - TWS3 */
|
||||||
|
|
||||||
|
#define TW_STATUS_MASK (_BV(TWS7)|_BV(TWS6)|_BV(TWS5)|_BV(TWS4)|_BV(TWS3))
|
||||||
|
#define TW_STATUS (TWSR & TW_STATUS_MASK)
|
||||||
|
#define TW_START 0x08
|
||||||
|
#define TW_REP_START 0x10
|
||||||
|
#define TW_MT_SLA_ACK 0x18
|
||||||
|
#define TW_MT_SLA_NACK 0x20
|
||||||
|
#define TW_MT_DATA_ACK 0x28
|
||||||
|
#define TW_MT_DATA_NACK 0x30
|
||||||
|
#define TW_MT_ARB_LOST 0x38
|
||||||
|
#define TW_MR_ARB_LOST 0x38
|
||||||
|
#define TW_MR_SLA_ACK 0x40
|
||||||
|
#define TW_MR_SLA_NACK 0x48
|
||||||
|
#define TW_MR_DATA_ACK 0x50
|
||||||
|
#define TW_MR_DATA_NACK 0x58
|
||||||
|
#define TW_ST_SLA_ACK 0xA8
|
||||||
|
#define TW_ST_ARB_LOST_SLA_ACK 0xB0
|
||||||
|
#define TW_ST_DATA_ACK 0xB8
|
||||||
|
#define TW_ST_DATA_NACK 0xC0
|
||||||
|
#define TW_ST_LAST_DATA 0xC8
|
||||||
|
#define TW_SR_SLA_ACK 0x60
|
||||||
|
#define TW_SR_ARB_LOST_SLA_ACK 0x68
|
||||||
|
#define TW_SR_GCALL_ACK 0x70
|
||||||
|
#define TW_SR_ARB_LOST_GCALL_ACK 0x78
|
||||||
|
#define TW_SR_DATA_ACK 0x80
|
||||||
|
#define TW_SR_DATA_NACK 0x88
|
||||||
|
#define TW_SR_GCALL_DATA_ACK 0x90
|
||||||
|
#define TW_SR_GCALL_DATA_NACK 0x98
|
||||||
|
#define TW_SR_STOP 0xA0
|
||||||
|
#define TW_NO_INFO 0xF8
|
||||||
|
#define TW_BUS_ERROR 0x00
|
||||||
|
|
||||||
|
//#define _MMIO_BYTE(mem_addr) (*(volatile uint8_t *)(mem_addr))
|
||||||
|
//#define _SFR_BYTE(sfr) _MMIO_BYTE(_SFR_ADDR(sfr))
|
||||||
|
|
||||||
|
#ifndef sbi // set bit
|
||||||
|
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
||||||
|
#endif // sbi
|
||||||
|
|
||||||
|
#ifndef cbi // clear bit
|
||||||
|
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
|
||||||
|
#endif // cbi
|
||||||
|
|
||||||
|
extern TwoWire Wire;
|
||||||
|
|
||||||
|
#endif // I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE
|
||||||
|
|
||||||
|
#endif /* _I2CDEV_H_ */
|
458
portail_coulissant/porcou-arduino/StandardFirmata/LICENSE.txt
Normal file
458
portail_coulissant/porcou-arduino/StandardFirmata/LICENSE.txt
Normal file
@ -0,0 +1,458 @@
|
|||||||
|
|
||||||
|
GNU LESSER GENERAL PUBLIC LICENSE
|
||||||
|
Version 2.1, February 1999
|
||||||
|
|
||||||
|
Copyright (C) 1991, 1999 Free Software Foundation, Inc.
|
||||||
|
51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||||
|
Everyone is permitted to copy and distribute verbatim copies
|
||||||
|
of this license document, but changing it is not allowed.
|
||||||
|
|
||||||
|
[This is the first released version of the Lesser GPL. It also counts
|
||||||
|
as the successor of the GNU Library Public License, version 2, hence
|
||||||
|
the version number 2.1.]
|
||||||
|
|
||||||
|
Preamble
|
||||||
|
|
||||||
|
The licenses for most software are designed to take away your
|
||||||
|
freedom to share and change it. By contrast, the GNU General Public
|
||||||
|
Licenses are intended to guarantee your freedom to share and change
|
||||||
|
free software--to make sure the software is free for all its users.
|
||||||
|
|
||||||
|
This license, the Lesser General Public License, applies to some
|
||||||
|
specially designated software packages--typically libraries--of the
|
||||||
|
Free Software Foundation and other authors who decide to use it. You
|
||||||
|
can use it too, but we suggest you first think carefully about whether
|
||||||
|
this license or the ordinary General Public License is the better
|
||||||
|
strategy to use in any particular case, based on the explanations below.
|
||||||
|
|
||||||
|
When we speak of free software, we are referring to freedom of use,
|
||||||
|
not price. Our General Public Licenses are designed to make sure that
|
||||||
|
you have the freedom to distribute copies of free software (and charge
|
||||||
|
for this service if you wish); that you receive source code or can get
|
||||||
|
it if you want it; that you can change the software and use pieces of
|
||||||
|
it in new free programs; and that you are informed that you can do
|
||||||
|
these things.
|
||||||
|
|
||||||
|
To protect your rights, we need to make restrictions that forbid
|
||||||
|
distributors to deny you these rights or to ask you to surrender these
|
||||||
|
rights. These restrictions translate to certain responsibilities for
|
||||||
|
you if you distribute copies of the library or if you modify it.
|
||||||
|
|
||||||
|
For example, if you distribute copies of the library, whether gratis
|
||||||
|
or for a fee, you must give the recipients all the rights that we gave
|
||||||
|
you. You must make sure that they, too, receive or can get the source
|
||||||
|
code. If you link other code with the library, you must provide
|
||||||
|
complete object files to the recipients, so that they can relink them
|
||||||
|
with the library after making changes to the library and recompiling
|
||||||
|
it. And you must show them these terms so they know their rights.
|
||||||
|
|
||||||
|
We protect your rights with a two-step method: (1) we copyright the
|
||||||
|
library, and (2) we offer you this license, which gives you legal
|
||||||
|
permission to copy, distribute and/or modify the library.
|
||||||
|
|
||||||
|
To protect each distributor, we want to make it very clear that
|
||||||
|
there is no warranty for the free library. Also, if the library is
|
||||||
|
modified by someone else and passed on, the recipients should know
|
||||||
|
that what they have is not the original version, so that the original
|
||||||
|
author's reputation will not be affected by problems that might be
|
||||||
|
introduced by others.
|
||||||
|
|
||||||
|
Finally, software patents pose a constant threat to the existence of
|
||||||
|
any free program. We wish to make sure that a company cannot
|
||||||
|
effectively restrict the users of a free program by obtaining a
|
||||||
|
restrictive license from a patent holder. Therefore, we insist that
|
||||||
|
any patent license obtained for a version of the library must be
|
||||||
|
consistent with the full freedom of use specified in this license.
|
||||||
|
|
||||||
|
Most GNU software, including some libraries, is covered by the
|
||||||
|
ordinary GNU General Public License. This license, the GNU Lesser
|
||||||
|
General Public License, applies to certain designated libraries, and
|
||||||
|
is quite different from the ordinary General Public License. We use
|
||||||
|
this license for certain libraries in order to permit linking those
|
||||||
|
libraries into non-free programs.
|
||||||
|
|
||||||
|
When a program is linked with a library, whether statically or using
|
||||||
|
a shared library, the combination of the two is legally speaking a
|
||||||
|
combined work, a derivative of the original library. The ordinary
|
||||||
|
General Public License therefore permits such linking only if the
|
||||||
|
entire combination fits its criteria of freedom. The Lesser General
|
||||||
|
Public License permits more lax criteria for linking other code with
|
||||||
|
the library.
|
||||||
|
|
||||||
|
We call this license the "Lesser" General Public License because it
|
||||||
|
does Less to protect the user's freedom than the ordinary General
|
||||||
|
Public License. It also provides other free software developers Less
|
||||||
|
of an advantage over competing non-free programs. These disadvantages
|
||||||
|
are the reason we use the ordinary General Public License for many
|
||||||
|
libraries. However, the Lesser license provides advantages in certain
|
||||||
|
special circumstances.
|
||||||
|
|
||||||
|
For example, on rare occasions, there may be a special need to
|
||||||
|
encourage the widest possible use of a certain library, so that it becomes
|
||||||
|
a de-facto standard. To achieve this, non-free programs must be
|
||||||
|
allowed to use the library. A more frequent case is that a free
|
||||||
|
library does the same job as widely used non-free libraries. In this
|
||||||
|
case, there is little to gain by limiting the free library to free
|
||||||
|
software only, so we use the Lesser General Public License.
|
||||||
|
|
||||||
|
In other cases, permission to use a particular library in non-free
|
||||||
|
programs enables a greater number of people to use a large body of
|
||||||
|
free software. For example, permission to use the GNU C Library in
|
||||||
|
non-free programs enables many more people to use the whole GNU
|
||||||
|
operating system, as well as its variant, the GNU/Linux operating
|
||||||
|
system.
|
||||||
|
|
||||||
|
Although the Lesser General Public License is Less protective of the
|
||||||
|
users' freedom, it does ensure that the user of a program that is
|
||||||
|
linked with the Library has the freedom and the wherewithal to run
|
||||||
|
that program using a modified version of the Library.
|
||||||
|
|
||||||
|
The precise terms and conditions for copying, distribution and
|
||||||
|
modification follow. Pay close attention to the difference between a
|
||||||
|
"work based on the library" and a "work that uses the library". The
|
||||||
|
former contains code derived from the library, whereas the latter must
|
||||||
|
be combined with the library in order to run.
|
||||||
|
|
||||||
|
GNU LESSER GENERAL PUBLIC LICENSE
|
||||||
|
TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION
|
||||||
|
|
||||||
|
0. This License Agreement applies to any software library or other
|
||||||
|
program which contains a notice placed by the copyright holder or
|
||||||
|
other authorized party saying it may be distributed under the terms of
|
||||||
|
this Lesser General Public License (also called "this License").
|
||||||
|
Each licensee is addressed as "you".
|
||||||
|
|
||||||
|
A "library" means a collection of software functions and/or data
|
||||||
|
prepared so as to be conveniently linked with application programs
|
||||||
|
(which use some of those functions and data) to form executables.
|
||||||
|
|
||||||
|
The "Library", below, refers to any such software library or work
|
||||||
|
which has been distributed under these terms. A "work based on the
|
||||||
|
Library" means either the Library or any derivative work under
|
||||||
|
copyright law: that is to say, a work containing the Library or a
|
||||||
|
portion of it, either verbatim or with modifications and/or translated
|
||||||
|
straightforwardly into another language. (Hereinafter, translation is
|
||||||
|
included without limitation in the term "modification".)
|
||||||
|
|
||||||
|
"Source code" for a work means the preferred form of the work for
|
||||||
|
making modifications to it. For a library, complete source code means
|
||||||
|
all the source code for all modules it contains, plus any associated
|
||||||
|
interface definition files, plus the scripts used to control compilation
|
||||||
|
and installation of the library.
|
||||||
|
|
||||||
|
Activities other than copying, distribution and modification are not
|
||||||
|
covered by this License; they are outside its scope. The act of
|
||||||
|
running a program using the Library is not restricted, and output from
|
||||||
|
such a program is covered only if its contents constitute a work based
|
||||||
|
on the Library (independent of the use of the Library in a tool for
|
||||||
|
writing it). Whether that is true depends on what the Library does
|
||||||
|
and what the program that uses the Library does.
|
||||||
|
|
||||||
|
1. You may copy and distribute verbatim copies of the Library's
|
||||||
|
complete source code as you receive it, in any medium, provided that
|
||||||
|
you conspicuously and appropriately publish on each copy an
|
||||||
|
appropriate copyright notice and disclaimer of warranty; keep intact
|
||||||
|
all the notices that refer to this License and to the absence of any
|
||||||
|
warranty; and distribute a copy of this License along with the
|
||||||
|
Library.
|
||||||
|
|
||||||
|
You may charge a fee for the physical act of transferring a copy,
|
||||||
|
and you may at your option offer warranty protection in exchange for a
|
||||||
|
fee.
|
||||||
|
|
||||||
|
2. You may modify your copy or copies of the Library or any portion
|
||||||
|
of it, thus forming a work based on the Library, and copy and
|
||||||
|
distribute such modifications or work under the terms of Section 1
|
||||||
|
above, provided that you also meet all of these conditions:
|
||||||
|
|
||||||
|
a) The modified work must itself be a software library.
|
||||||
|
|
||||||
|
b) You must cause the files modified to carry prominent notices
|
||||||
|
stating that you changed the files and the date of any change.
|
||||||
|
|
||||||
|
c) You must cause the whole of the work to be licensed at no
|
||||||
|
charge to all third parties under the terms of this License.
|
||||||
|
|
||||||
|
d) If a facility in the modified Library refers to a function or a
|
||||||
|
table of data to be supplied by an application program that uses
|
||||||
|
the facility, other than as an argument passed when the facility
|
||||||
|
is invoked, then you must make a good faith effort to ensure that,
|
||||||
|
in the event an application does not supply such function or
|
||||||
|
table, the facility still operates, and performs whatever part of
|
||||||
|
its purpose remains meaningful.
|
||||||
|
|
||||||
|
(For example, a function in a library to compute square roots has
|
||||||
|
a purpose that is entirely well-defined independent of the
|
||||||
|
application. Therefore, Subsection 2d requires that any
|
||||||
|
application-supplied function or table used by this function must
|
||||||
|
be optional: if the application does not supply it, the square
|
||||||
|
root function must still compute square roots.)
|
||||||
|
|
||||||
|
These requirements apply to the modified work as a whole. If
|
||||||
|
identifiable sections of that work are not derived from the Library,
|
||||||
|
and can be reasonably considered independent and separate works in
|
||||||
|
themselves, then this License, and its terms, do not apply to those
|
||||||
|
sections when you distribute them as separate works. But when you
|
||||||
|
distribute the same sections as part of a whole which is a work based
|
||||||
|
on the Library, the distribution of the whole must be on the terms of
|
||||||
|
this License, whose permissions for other licensees extend to the
|
||||||
|
entire whole, and thus to each and every part regardless of who wrote
|
||||||
|
it.
|
||||||
|
|
||||||
|
Thus, it is not the intent of this section to claim rights or contest
|
||||||
|
your rights to work written entirely by you; rather, the intent is to
|
||||||
|
exercise the right to control the distribution of derivative or
|
||||||
|
collective works based on the Library.
|
||||||
|
|
||||||
|
In addition, mere aggregation of another work not based on the Library
|
||||||
|
with the Library (or with a work based on the Library) on a volume of
|
||||||
|
a storage or distribution medium does not bring the other work under
|
||||||
|
the scope of this License.
|
||||||
|
|
||||||
|
3. You may opt to apply the terms of the ordinary GNU General Public
|
||||||
|
License instead of this License to a given copy of the Library. To do
|
||||||
|
this, you must alter all the notices that refer to this License, so
|
||||||
|
that they refer to the ordinary GNU General Public License, version 2,
|
||||||
|
instead of to this License. (If a newer version than version 2 of the
|
||||||
|
ordinary GNU General Public License has appeared, then you can specify
|
||||||
|
that version instead if you wish.) Do not make any other change in
|
||||||
|
these notices.
|
||||||
|
|
||||||
|
Once this change is made in a given copy, it is irreversible for
|
||||||
|
that copy, so the ordinary GNU General Public License applies to all
|
||||||
|
subsequent copies and derivative works made from that copy.
|
||||||
|
|
||||||
|
This option is useful when you wish to copy part of the code of
|
||||||
|
the Library into a program that is not a library.
|
||||||
|
|
||||||
|
4. You may copy and distribute the Library (or a portion or
|
||||||
|
derivative of it, under Section 2) in object code or executable form
|
||||||
|
under the terms of Sections 1 and 2 above provided that you accompany
|
||||||
|
it with the complete corresponding machine-readable source code, which
|
||||||
|
must be distributed under the terms of Sections 1 and 2 above on a
|
||||||
|
medium customarily used for software interchange.
|
||||||
|
|
||||||
|
If distribution of object code is made by offering access to copy
|
||||||
|
from a designated place, then offering equivalent access to copy the
|
||||||
|
source code from the same place satisfies the requirement to
|
||||||
|
distribute the source code, even though third parties are not
|
||||||
|
compelled to copy the source along with the object code.
|
||||||
|
|
||||||
|
5. A program that contains no derivative of any portion of the
|
||||||
|
Library, but is designed to work with the Library by being compiled or
|
||||||
|
linked with it, is called a "work that uses the Library". Such a
|
||||||
|
work, in isolation, is not a derivative work of the Library, and
|
||||||
|
therefore falls outside the scope of this License.
|
||||||
|
|
||||||
|
However, linking a "work that uses the Library" with the Library
|
||||||
|
creates an executable that is a derivative of the Library (because it
|
||||||
|
contains portions of the Library), rather than a "work that uses the
|
||||||
|
library". The executable is therefore covered by this License.
|
||||||
|
Section 6 states terms for distribution of such executables.
|
||||||
|
|
||||||
|
When a "work that uses the Library" uses material from a header file
|
||||||
|
that is part of the Library, the object code for the work may be a
|
||||||
|
derivative work of the Library even though the source code is not.
|
||||||
|
Whether this is true is especially significant if the work can be
|
||||||
|
linked without the Library, or if the work is itself a library. The
|
||||||
|
threshold for this to be true is not precisely defined by law.
|
||||||
|
|
||||||
|
If such an object file uses only numerical parameters, data
|
||||||
|
structure layouts and accessors, and small macros and small inline
|
||||||
|
functions (ten lines or less in length), then the use of the object
|
||||||
|
file is unrestricted, regardless of whether it is legally a derivative
|
||||||
|
work. (Executables containing this object code plus portions of the
|
||||||
|
Library will still fall under Section 6.)
|
||||||
|
|
||||||
|
Otherwise, if the work is a derivative of the Library, you may
|
||||||
|
distribute the object code for the work under the terms of Section 6.
|
||||||
|
Any executables containing that work also fall under Section 6,
|
||||||
|
whether or not they are linked directly with the Library itself.
|
||||||
|
|
||||||
|
6. As an exception to the Sections above, you may also combine or
|
||||||
|
link a "work that uses the Library" with the Library to produce a
|
||||||
|
work containing portions of the Library, and distribute that work
|
||||||
|
under terms of your choice, provided that the terms permit
|
||||||
|
modification of the work for the customer's own use and reverse
|
||||||
|
engineering for debugging such modifications.
|
||||||
|
|
||||||
|
You must give prominent notice with each copy of the work that the
|
||||||
|
Library is used in it and that the Library and its use are covered by
|
||||||
|
this License. You must supply a copy of this License. If the work
|
||||||
|
during execution displays copyright notices, you must include the
|
||||||
|
copyright notice for the Library among them, as well as a reference
|
||||||
|
directing the user to the copy of this License. Also, you must do one
|
||||||
|
of these things:
|
||||||
|
|
||||||
|
a) Accompany the work with the complete corresponding
|
||||||
|
machine-readable source code for the Library including whatever
|
||||||
|
changes were used in the work (which must be distributed under
|
||||||
|
Sections 1 and 2 above); and, if the work is an executable linked
|
||||||
|
with the Library, with the complete machine-readable "work that
|
||||||
|
uses the Library", as object code and/or source code, so that the
|
||||||
|
user can modify the Library and then relink to produce a modified
|
||||||
|
executable containing the modified Library. (It is understood
|
||||||
|
that the user who changes the contents of definitions files in the
|
||||||
|
Library will not necessarily be able to recompile the application
|
||||||
|
to use the modified definitions.)
|
||||||
|
|
||||||
|
b) Use a suitable shared library mechanism for linking with the
|
||||||
|
Library. A suitable mechanism is one that (1) uses at run time a
|
||||||
|
copy of the library already present on the user's computer system,
|
||||||
|
rather than copying library functions into the executable, and (2)
|
||||||
|
will operate properly with a modified version of the library, if
|
||||||
|
the user installs one, as long as the modified version is
|
||||||
|
interface-compatible with the version that the work was made with.
|
||||||
|
|
||||||
|
c) Accompany the work with a written offer, valid for at
|
||||||
|
least three years, to give the same user the materials
|
||||||
|
specified in Subsection 6a, above, for a charge no more
|
||||||
|
than the cost of performing this distribution.
|
||||||
|
|
||||||
|
d) If distribution of the work is made by offering access to copy
|
||||||
|
from a designated place, offer equivalent access to copy the above
|
||||||
|
specified materials from the same place.
|
||||||
|
|
||||||
|
e) Verify that the user has already received a copy of these
|
||||||
|
materials or that you have already sent this user a copy.
|
||||||
|
|
||||||
|
For an executable, the required form of the "work that uses the
|
||||||
|
Library" must include any data and utility programs needed for
|
||||||
|
reproducing the executable from it. However, as a special exception,
|
||||||
|
the materials to be distributed need not include anything that is
|
||||||
|
normally distributed (in either source or binary form) with the major
|
||||||
|
components (compiler, kernel, and so on) of the operating system on
|
||||||
|
which the executable runs, unless that component itself accompanies
|
||||||
|
the executable.
|
||||||
|
|
||||||
|
It may happen that this requirement contradicts the license
|
||||||
|
restrictions of other proprietary libraries that do not normally
|
||||||
|
accompany the operating system. Such a contradiction means you cannot
|
||||||
|
use both them and the Library together in an executable that you
|
||||||
|
distribute.
|
||||||
|
|
||||||
|
7. You may place library facilities that are a work based on the
|
||||||
|
Library side-by-side in a single library together with other library
|
||||||
|
facilities not covered by this License, and distribute such a combined
|
||||||
|
library, provided that the separate distribution of the work based on
|
||||||
|
the Library and of the other library facilities is otherwise
|
||||||
|
permitted, and provided that you do these two things:
|
||||||
|
|
||||||
|
a) Accompany the combined library with a copy of the same work
|
||||||
|
based on the Library, uncombined with any other library
|
||||||
|
facilities. This must be distributed under the terms of the
|
||||||
|
Sections above.
|
||||||
|
|
||||||
|
b) Give prominent notice with the combined library of the fact
|
||||||
|
that part of it is a work based on the Library, and explaining
|
||||||
|
where to find the accompanying uncombined form of the same work.
|
||||||
|
|
||||||
|
8. You may not copy, modify, sublicense, link with, or distribute
|
||||||
|
the Library except as expressly provided under this License. Any
|
||||||
|
attempt otherwise to copy, modify, sublicense, link with, or
|
||||||
|
distribute the Library is void, and will automatically terminate your
|
||||||
|
rights under this License. However, parties who have received copies,
|
||||||
|
or rights, from you under this License will not have their licenses
|
||||||
|
terminated so long as such parties remain in full compliance.
|
||||||
|
|
||||||
|
9. You are not required to accept this License, since you have not
|
||||||
|
signed it. However, nothing else grants you permission to modify or
|
||||||
|
distribute the Library or its derivative works. These actions are
|
||||||
|
prohibited by law if you do not accept this License. Therefore, by
|
||||||
|
modifying or distributing the Library (or any work based on the
|
||||||
|
Library), you indicate your acceptance of this License to do so, and
|
||||||
|
all its terms and conditions for copying, distributing or modifying
|
||||||
|
the Library or works based on it.
|
||||||
|
|
||||||
|
10. Each time you redistribute the Library (or any work based on the
|
||||||
|
Library), the recipient automatically receives a license from the
|
||||||
|
original licensor to copy, distribute, link with or modify the Library
|
||||||
|
subject to these terms and conditions. You may not impose any further
|
||||||
|
restrictions on the recipients' exercise of the rights granted herein.
|
||||||
|
You are not responsible for enforcing compliance by third parties with
|
||||||
|
this License.
|
||||||
|
|
||||||
|
11. If, as a consequence of a court judgment or allegation of patent
|
||||||
|
infringement or for any other reason (not limited to patent issues),
|
||||||
|
conditions are imposed on you (whether by court order, agreement or
|
||||||
|
otherwise) that contradict the conditions of this License, they do not
|
||||||
|
excuse you from the conditions of this License. If you cannot
|
||||||
|
distribute so as to satisfy simultaneously your obligations under this
|
||||||
|
License and any other pertinent obligations, then as a consequence you
|
||||||
|
may not distribute the Library at all. For example, if a patent
|
||||||
|
license would not permit royalty-free redistribution of the Library by
|
||||||
|
all those who receive copies directly or indirectly through you, then
|
||||||
|
the only way you could satisfy both it and this License would be to
|
||||||
|
refrain entirely from distribution of the Library.
|
||||||
|
|
||||||
|
If any portion of this section is held invalid or unenforceable under any
|
||||||
|
particular circumstance, the balance of the section is intended to apply,
|
||||||
|
and the section as a whole is intended to apply in other circumstances.
|
||||||
|
|
||||||
|
It is not the purpose of this section to induce you to infringe any
|
||||||
|
patents or other property right claims or to contest validity of any
|
||||||
|
such claims; this section has the sole purpose of protecting the
|
||||||
|
integrity of the free software distribution system which is
|
||||||
|
implemented by public license practices. Many people have made
|
||||||
|
generous contributions to the wide range of software distributed
|
||||||
|
through that system in reliance on consistent application of that
|
||||||
|
system; it is up to the author/donor to decide if he or she is willing
|
||||||
|
to distribute software through any other system and a licensee cannot
|
||||||
|
impose that choice.
|
||||||
|
|
||||||
|
This section is intended to make thoroughly clear what is believed to
|
||||||
|
be a consequence of the rest of this License.
|
||||||
|
|
||||||
|
12. If the distribution and/or use of the Library is restricted in
|
||||||
|
certain countries either by patents or by copyrighted interfaces, the
|
||||||
|
original copyright holder who places the Library under this License may add
|
||||||
|
an explicit geographical distribution limitation excluding those countries,
|
||||||
|
so that distribution is permitted only in or among countries not thus
|
||||||
|
excluded. In such case, this License incorporates the limitation as if
|
||||||
|
written in the body of this License.
|
||||||
|
|
||||||
|
13. The Free Software Foundation may publish revised and/or new
|
||||||
|
versions of the Lesser General Public License from time to time.
|
||||||
|
Such new versions will be similar in spirit to the present version,
|
||||||
|
but may differ in detail to address new problems or concerns.
|
||||||
|
|
||||||
|
Each version is given a distinguishing version number. If the Library
|
||||||
|
specifies a version number of this License which applies to it and
|
||||||
|
"any later version", you have the option of following the terms and
|
||||||
|
conditions either of that version or of any later version published by
|
||||||
|
the Free Software Foundation. If the Library does not specify a
|
||||||
|
license version number, you may choose any version ever published by
|
||||||
|
the Free Software Foundation.
|
||||||
|
|
||||||
|
14. If you wish to incorporate parts of the Library into other free
|
||||||
|
programs whose distribution conditions are incompatible with these,
|
||||||
|
write to the author to ask for permission. For software which is
|
||||||
|
copyrighted by the Free Software Foundation, write to the Free
|
||||||
|
Software Foundation; we sometimes make exceptions for this. Our
|
||||||
|
decision will be guided by the two goals of preserving the free status
|
||||||
|
of all derivatives of our free software and of promoting the sharing
|
||||||
|
and reuse of software generally.
|
||||||
|
|
||||||
|
NO WARRANTY
|
||||||
|
|
||||||
|
15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO
|
||||||
|
WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW.
|
||||||
|
EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR
|
||||||
|
OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY
|
||||||
|
KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE
|
||||||
|
LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME
|
||||||
|
THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
|
||||||
|
|
||||||
|
16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN
|
||||||
|
WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY
|
||||||
|
AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU
|
||||||
|
FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR
|
||||||
|
CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE
|
||||||
|
LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING
|
||||||
|
RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A
|
||||||
|
FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF
|
||||||
|
SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
|
||||||
|
DAMAGES.
|
||||||
|
|
@ -0,0 +1,824 @@
|
|||||||
|
/*
|
||||||
|
Firmata is a generic protocol for communicating with microcontrollers
|
||||||
|
from software on a host computer. It is intended to work with
|
||||||
|
any host computer software package.
|
||||||
|
|
||||||
|
To download a host software package, please click on the following link
|
||||||
|
to open the list of Firmata client libraries in your default browser.
|
||||||
|
|
||||||
|
https://github.com/firmata/arduino#firmata-client-libraries
|
||||||
|
|
||||||
|
Copyright (C) 2006-2008 Hans-Christoph Steiner. All rights reserved.
|
||||||
|
Copyright (C) 2010-2011 Paul Stoffregen. All rights reserved.
|
||||||
|
Copyright (C) 2009 Shigeru Kobayashi. All rights reserved.
|
||||||
|
Copyright (C) 2009-2016 Jeff Hoefs. All rights reserved.
|
||||||
|
|
||||||
|
This library is free software; you can redistribute it and/or
|
||||||
|
modify it under the terms of the GNU Lesser General Public
|
||||||
|
License as published by the Free Software Foundation; either
|
||||||
|
version 2.1 of the License, or (at your option) any later version.
|
||||||
|
|
||||||
|
See file LICENSE.txt for further informations on licensing terms.
|
||||||
|
|
||||||
|
Last updated August 17th, 2017
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <Servo.h>
|
||||||
|
#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_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
|
||||||
|
|
||||||
|
// the minimum interval for sampling analog input
|
||||||
|
#define MINIMUM_SAMPLING_INTERVAL 1
|
||||||
|
|
||||||
|
|
||||||
|
/*==============================================================================
|
||||||
|
* GLOBAL VARIABLES
|
||||||
|
*============================================================================*/
|
||||||
|
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
SerialFirmata serialFeature;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* analog inputs */
|
||||||
|
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
|
||||||
|
|
||||||
|
/* pins configuration */
|
||||||
|
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)
|
||||||
|
|
||||||
|
/* i2c data */
|
||||||
|
struct i2c_device_info {
|
||||||
|
byte addr;
|
||||||
|
int reg;
|
||||||
|
byte bytes;
|
||||||
|
byte stopTX;
|
||||||
|
};
|
||||||
|
|
||||||
|
/* for i2c read continuous more */
|
||||||
|
i2c_device_info query[I2C_MAX_QUERIES];
|
||||||
|
|
||||||
|
byte i2cRxData[64];
|
||||||
|
boolean isI2CEnabled = false;
|
||||||
|
signed char queryIndex = -1;
|
||||||
|
// default delay time between i2c read request and Wire.requestFrom()
|
||||||
|
unsigned int i2cReadDelayTime = 0;
|
||||||
|
|
||||||
|
Servo servos[MAX_SERVOS];
|
||||||
|
byte servoPinMap[TOTAL_PINS];
|
||||||
|
byte detachedServos[MAX_SERVOS];
|
||||||
|
byte detachedServoCount = 0;
|
||||||
|
byte servoCount = 0;
|
||||||
|
|
||||||
|
boolean isResetting = false;
|
||||||
|
|
||||||
|
// Forward declare a few functions to avoid compiler errors with older versions
|
||||||
|
// of the Arduino IDE.
|
||||||
|
void setPinModeCallback(byte, int);
|
||||||
|
void reportAnalogCallback(byte analogPin, int value);
|
||||||
|
void sysexCallback(byte, byte, byte*);
|
||||||
|
|
||||||
|
/* utility functions */
|
||||||
|
void wireWrite(byte data)
|
||||||
|
{
|
||||||
|
#if ARDUINO >= 100
|
||||||
|
Wire.write((byte)data);
|
||||||
|
#else
|
||||||
|
Wire.send(data);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
byte wireRead(void)
|
||||||
|
{
|
||||||
|
#if ARDUINO >= 100
|
||||||
|
return Wire.read();
|
||||||
|
#else
|
||||||
|
return Wire.receive();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/*==============================================================================
|
||||||
|
* FUNCTIONS
|
||||||
|
*============================================================================*/
|
||||||
|
|
||||||
|
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) {
|
||||||
|
servoPinMap[pin] = detachedServos[detachedServoCount - 1];
|
||||||
|
if (detachedServoCount > 0) detachedServoCount--;
|
||||||
|
} else {
|
||||||
|
servoPinMap[pin] = servoCount;
|
||||||
|
servoCount++;
|
||||||
|
}
|
||||||
|
if (minPulse > 0 && maxPulse > 0) {
|
||||||
|
servos[servoPinMap[pin]].attach(PIN_TO_DIGITAL(pin), minPulse, maxPulse);
|
||||||
|
} else {
|
||||||
|
servos[servoPinMap[pin]].attach(PIN_TO_DIGITAL(pin));
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
Firmata.sendString("Max servos attached");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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
|
||||||
|
if (servoPinMap[pin] == servoCount && servoCount > 0) {
|
||||||
|
servoCount--;
|
||||||
|
} else if (servoCount > 0) {
|
||||||
|
// keep track of detached servos because we want to reuse their indexes
|
||||||
|
// before incrementing the count of attached servos
|
||||||
|
detachedServoCount++;
|
||||||
|
detachedServos[detachedServoCount - 1] = servoPinMap[pin];
|
||||||
|
}
|
||||||
|
|
||||||
|
servoPinMap[pin] = 255;
|
||||||
|
}
|
||||||
|
|
||||||
|
void enableI2CPins()
|
||||||
|
{
|
||||||
|
byte i;
|
||||||
|
// is there a faster way to do this? would probaby require importing
|
||||||
|
// Arduino.h to get SCL and SDA pins
|
||||||
|
for (i = 0; i < TOTAL_PINS; i++) {
|
||||||
|
if (IS_PIN_I2C(i)) {
|
||||||
|
// mark pins as i2c so they are ignore in non i2c data requests
|
||||||
|
setPinModeCallback(i, PIN_MODE_I2C);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
isI2CEnabled = true;
|
||||||
|
|
||||||
|
Wire.begin();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* disable the i2c pins so they can be used for other functions */
|
||||||
|
void disableI2CPins() {
|
||||||
|
isI2CEnabled = false;
|
||||||
|
// disable read continuous mode for all devices
|
||||||
|
queryIndex = -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void readAndReportData(byte address, int theRegister, byte numBytes, byte stopTX) {
|
||||||
|
// allow I2C requests that don't require a register read
|
||||||
|
// for example, some devices using an interrupt pin to signify new data available
|
||||||
|
// do not always require the register read so upon interrupt you call Wire.requestFrom()
|
||||||
|
if (theRegister != I2C_REGISTER_NOT_SPECIFIED) {
|
||||||
|
Wire.beginTransmission(address);
|
||||||
|
wireWrite((byte)theRegister);
|
||||||
|
Wire.endTransmission(stopTX); // default = true
|
||||||
|
// do not set a value of 0
|
||||||
|
if (i2cReadDelayTime > 0) {
|
||||||
|
// delay is necessary for some devices such as WiiNunchuck
|
||||||
|
delayMicroseconds(i2cReadDelayTime);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
theRegister = 0; // fill the register with a dummy value
|
||||||
|
}
|
||||||
|
|
||||||
|
Wire.requestFrom(address, numBytes); // all bytes are returned in requestFrom
|
||||||
|
|
||||||
|
// check to be sure correct number of bytes were returned by slave
|
||||||
|
if (numBytes < Wire.available()) {
|
||||||
|
Firmata.sendString("I2C: Too many bytes received");
|
||||||
|
} else if (numBytes > Wire.available()) {
|
||||||
|
Firmata.sendString("I2C: Too few bytes received");
|
||||||
|
numBytes = Wire.available();
|
||||||
|
}
|
||||||
|
|
||||||
|
i2cRxData[0] = address;
|
||||||
|
i2cRxData[1] = theRegister;
|
||||||
|
|
||||||
|
for (int i = 0; i < numBytes && Wire.available(); i++) {
|
||||||
|
i2cRxData[2 + i] = wireRead();
|
||||||
|
}
|
||||||
|
|
||||||
|
// send slave address, register and received bytes
|
||||||
|
Firmata.sendSysex(SYSEX_I2C_REPLY, numBytes + 2, i2cRxData);
|
||||||
|
}
|
||||||
|
|
||||||
|
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
|
||||||
|
if (forceSend || previousPINs[portNumber] != portValue) {
|
||||||
|
Firmata.sendDigitalPort(portNumber, portValue);
|
||||||
|
previousPINs[portNumber] = portValue;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* -----------------------------------------------------------------------------
|
||||||
|
* 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)
|
||||||
|
{
|
||||||
|
/* 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. */
|
||||||
|
if (TOTAL_PORTS > 0 && reportPINs[0]) outputPort(0, readPort(0, portConfigInputs[0]), false);
|
||||||
|
if (TOTAL_PORTS > 1 && reportPINs[1]) outputPort(1, readPort(1, portConfigInputs[1]), false);
|
||||||
|
if (TOTAL_PORTS > 2 && reportPINs[2]) outputPort(2, readPort(2, portConfigInputs[2]), false);
|
||||||
|
if (TOTAL_PORTS > 3 && reportPINs[3]) outputPort(3, readPort(3, portConfigInputs[3]), false);
|
||||||
|
if (TOTAL_PORTS > 4 && reportPINs[4]) outputPort(4, readPort(4, portConfigInputs[4]), false);
|
||||||
|
if (TOTAL_PORTS > 5 && reportPINs[5]) outputPort(5, readPort(5, portConfigInputs[5]), false);
|
||||||
|
if (TOTAL_PORTS > 6 && reportPINs[6]) outputPort(6, readPort(6, portConfigInputs[6]), false);
|
||||||
|
if (TOTAL_PORTS > 7 && reportPINs[7]) outputPort(7, readPort(7, portConfigInputs[7]), false);
|
||||||
|
if (TOTAL_PORTS > 8 && reportPINs[8]) outputPort(8, readPort(8, portConfigInputs[8]), false);
|
||||||
|
if (TOTAL_PORTS > 9 && reportPINs[9]) outputPort(9, readPort(9, portConfigInputs[9]), false);
|
||||||
|
if (TOTAL_PORTS > 10 && reportPINs[10]) outputPort(10, readPort(10, portConfigInputs[10]), false);
|
||||||
|
if (TOTAL_PORTS > 11 && reportPINs[11]) outputPort(11, readPort(11, portConfigInputs[11]), false);
|
||||||
|
if (TOTAL_PORTS > 12 && reportPINs[12]) outputPort(12, readPort(12, portConfigInputs[12]), false);
|
||||||
|
if (TOTAL_PORTS > 13 && reportPINs[13]) outputPort(13, readPort(13, portConfigInputs[13]), false);
|
||||||
|
if (TOTAL_PORTS > 14 && reportPINs[14]) outputPort(14, readPort(14, portConfigInputs[14]), false);
|
||||||
|
if (TOTAL_PORTS > 15 && reportPINs[15]) outputPort(15, readPort(15, portConfigInputs[15]), false);
|
||||||
|
}
|
||||||
|
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
/* 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)
|
||||||
|
{
|
||||||
|
if (Firmata.getPinMode(pin) == PIN_MODE_IGNORE)
|
||||||
|
return;
|
||||||
|
|
||||||
|
if (Firmata.getPinMode(pin) == PIN_MODE_I2C && isI2CEnabled && mode != PIN_MODE_I2C) {
|
||||||
|
// disable i2c so pins can be used for other functions
|
||||||
|
// the following if statements should reconfigure the pins properly
|
||||||
|
disableI2CPins();
|
||||||
|
}
|
||||||
|
if (IS_PIN_DIGITAL(pin) && mode != PIN_MODE_SERVO) {
|
||||||
|
if (servoPinMap[pin] < MAX_SERVOS && servos[servoPinMap[pin]].attached()) {
|
||||||
|
detachServo(pin);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (IS_PIN_ANALOG(pin)) {
|
||||||
|
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) {
|
||||||
|
portConfigInputs[pin / 8] |= (1 << (pin & 7));
|
||||||
|
} else {
|
||||||
|
portConfigInputs[pin / 8] &= ~(1 << (pin & 7));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
Firmata.setPinState(pin, 0);
|
||||||
|
switch (mode) {
|
||||||
|
case PIN_MODE_ANALOG:
|
||||||
|
if (IS_PIN_ANALOG(pin)) {
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
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
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
Firmata.setPinMode(pin, PIN_MODE_ANALOG);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case INPUT:
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
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
|
||||||
|
#endif
|
||||||
|
Firmata.setPinMode(pin, INPUT);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case PIN_MODE_PULLUP:
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
pinMode(PIN_TO_DIGITAL(pin), INPUT_PULLUP);
|
||||||
|
Firmata.setPinMode(pin, PIN_MODE_PULLUP);
|
||||||
|
Firmata.setPinState(pin, 1);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OUTPUT:
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
if (Firmata.getPinMode(pin) == PIN_MODE_PWM) {
|
||||||
|
// Disable PWM if pin mode was previously set to PWM.
|
||||||
|
digitalWrite(PIN_TO_DIGITAL(pin), LOW);
|
||||||
|
}
|
||||||
|
pinMode(PIN_TO_DIGITAL(pin), OUTPUT);
|
||||||
|
Firmata.setPinMode(pin, OUTPUT);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case PIN_MODE_PWM:
|
||||||
|
if (IS_PIN_PWM(pin)) {
|
||||||
|
pinMode(PIN_TO_PWM(pin), OUTPUT);
|
||||||
|
analogWrite(PIN_TO_PWM(pin), 0);
|
||||||
|
Firmata.setPinMode(pin, PIN_MODE_PWM);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case PIN_MODE_SERVO:
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
Firmata.setPinMode(pin, PIN_MODE_SERVO);
|
||||||
|
if (servoPinMap[pin] == 255 || !servos[servoPinMap[pin]].attached()) {
|
||||||
|
// pass -1 for min and max pulse values to use default values set
|
||||||
|
// by Servo library
|
||||||
|
attachServo(pin, -1, -1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case PIN_MODE_I2C:
|
||||||
|
if (IS_PIN_I2C(pin)) {
|
||||||
|
// mark the pin as i2c
|
||||||
|
// the user must call I2C_CONFIG to enable I2C for a device
|
||||||
|
Firmata.setPinMode(pin, PIN_MODE_I2C);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case PIN_MODE_SERIAL:
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
serialFeature.handlePinMode(pin, PIN_MODE_SERIAL);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
Firmata.sendString("Unknown pin mode"); // TODO: put error msgs in EEPROM
|
||||||
|
}
|
||||||
|
// TODO: save status to EEPROM here, if changed
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Sets the value of an individual pin. Useful if you want to set a pin value but
|
||||||
|
* are not tracking the digital port state.
|
||||||
|
* 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)
|
||||||
|
{
|
||||||
|
if (pin < TOTAL_PINS && IS_PIN_DIGITAL(pin)) {
|
||||||
|
if (Firmata.getPinMode(pin) == OUTPUT) {
|
||||||
|
Firmata.setPinState(pin, value);
|
||||||
|
digitalWrite(PIN_TO_DIGITAL(pin), value);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void analogWriteCallback(byte pin, int value)
|
||||||
|
{
|
||||||
|
if (pin < TOTAL_PINS) {
|
||||||
|
switch (Firmata.getPinMode(pin)) {
|
||||||
|
case PIN_MODE_SERVO:
|
||||||
|
if (IS_PIN_DIGITAL(pin))
|
||||||
|
servos[servoPinMap[pin]].write(value);
|
||||||
|
Firmata.setPinState(pin, value);
|
||||||
|
break;
|
||||||
|
case PIN_MODE_PWM:
|
||||||
|
if (IS_PIN_PWM(pin))
|
||||||
|
analogWrite(PIN_TO_PWM(pin), value);
|
||||||
|
Firmata.setPinState(pin, value);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void digitalWriteCallback(byte port, int value)
|
||||||
|
{
|
||||||
|
byte pin, lastPin, pinValue, mask = 1, pinWriteMask = 0;
|
||||||
|
|
||||||
|
if (port < TOTAL_PORTS) {
|
||||||
|
// create a mask of the pins on this port that are writable.
|
||||||
|
lastPin = port * 8 + 8;
|
||||||
|
if (lastPin > TOTAL_PINS) lastPin = TOTAL_PINS;
|
||||||
|
for (pin = port * 8; pin < lastPin; pin++) {
|
||||||
|
// do not disturb non-digital pins (eg, Rx & Tx)
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
// do not touch pins in PWM, ANALOG, SERVO or other modes
|
||||||
|
if (Firmata.getPinMode(pin) == OUTPUT || Firmata.getPinMode(pin) == INPUT) {
|
||||||
|
pinValue = ((byte)value & mask) ? 1 : 0;
|
||||||
|
if (Firmata.getPinMode(pin) == OUTPUT) {
|
||||||
|
pinWriteMask |= mask;
|
||||||
|
} else if (Firmata.getPinMode(pin) == INPUT && pinValue == 1 && Firmata.getPinState(pin) != 1) {
|
||||||
|
// only handle INPUT here for backwards compatibility
|
||||||
|
#if ARDUINO > 100
|
||||||
|
pinMode(pin, INPUT_PULLUP);
|
||||||
|
#else
|
||||||
|
// only write to the INPUT pin to enable pullups if Arduino v1.0.0 or earlier
|
||||||
|
pinWriteMask |= mask;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
Firmata.setPinState(pin, pinValue);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
mask = mask << 1;
|
||||||
|
}
|
||||||
|
writePort(port, (byte)value, pinWriteMask);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
/* sets bits in a bit array (int) to toggle the reporting of the analogIns
|
||||||
|
*/
|
||||||
|
//void FirmataClass::setAnalogPinReporting(byte pin, byte state) {
|
||||||
|
//}
|
||||||
|
void reportAnalogCallback(byte analogPin, int value)
|
||||||
|
{
|
||||||
|
if (analogPin < TOTAL_ANALOG_PINS) {
|
||||||
|
if (value == 0) {
|
||||||
|
analogInputsToReport = analogInputsToReport & ~ (1 << analogPin);
|
||||||
|
} else {
|
||||||
|
analogInputsToReport = analogInputsToReport | (1 << analogPin);
|
||||||
|
// prevent during system reset or all analog pin values will be reported
|
||||||
|
// which may report noise for unconnected analog pins
|
||||||
|
if (!isResetting) {
|
||||||
|
// Send pin value immediately. This is helpful when connected via
|
||||||
|
// ethernet, wi-fi or bluetooth so pin states can be known upon
|
||||||
|
// reconnecting.
|
||||||
|
Firmata.sendAnalog(analogPin, analogRead(analogPin));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// TODO: save status to EEPROM here, if changed
|
||||||
|
}
|
||||||
|
|
||||||
|
void reportDigitalCallback(byte port, int value)
|
||||||
|
{
|
||||||
|
if (port < TOTAL_PORTS) {
|
||||||
|
reportPINs[port] = (byte)value;
|
||||||
|
// Send port value immediately. This is helpful when connected via
|
||||||
|
// ethernet, wi-fi or bluetooth so pin states can be known upon
|
||||||
|
// reconnecting.
|
||||||
|
if (value) outputPort(port, readPort(port, portConfigInputs[port]), true);
|
||||||
|
}
|
||||||
|
// do not disable analog reporting on these 8 pins, to allow some
|
||||||
|
// pins used for digital, others analog. Instead, allow both types
|
||||||
|
// of reporting to be enabled, but check if the pin is configured
|
||||||
|
// as analog when sampling the analog inputs. Likewise, while
|
||||||
|
// scanning digital pins, portConfigInputs will mask off values from any
|
||||||
|
// pins configured as analog
|
||||||
|
}
|
||||||
|
|
||||||
|
/*==============================================================================
|
||||||
|
* SYSEX-BASED commands
|
||||||
|
*============================================================================*/
|
||||||
|
|
||||||
|
void sysexCallback(byte command, byte argc, byte *argv)
|
||||||
|
{
|
||||||
|
byte mode;
|
||||||
|
byte stopTX;
|
||||||
|
byte slaveAddress;
|
||||||
|
byte data;
|
||||||
|
int slaveRegister;
|
||||||
|
unsigned int delayTime;
|
||||||
|
|
||||||
|
switch (command) {
|
||||||
|
case I2C_REQUEST:
|
||||||
|
mode = argv[1] & I2C_READ_WRITE_MODE_MASK;
|
||||||
|
if (argv[1] & I2C_10BIT_ADDRESS_MODE_MASK) {
|
||||||
|
Firmata.sendString("10-bit addressing not supported");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
slaveAddress = argv[0];
|
||||||
|
}
|
||||||
|
|
||||||
|
// need to invert the logic here since 0 will be default for client
|
||||||
|
// 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
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (mode) {
|
||||||
|
case I2C_WRITE:
|
||||||
|
Wire.beginTransmission(slaveAddress);
|
||||||
|
for (byte i = 2; i < argc; i += 2) {
|
||||||
|
data = argv[i] + (argv[i + 1] << 7);
|
||||||
|
wireWrite(data);
|
||||||
|
}
|
||||||
|
Wire.endTransmission();
|
||||||
|
delayMicroseconds(70);
|
||||||
|
break;
|
||||||
|
case I2C_READ:
|
||||||
|
if (argc == 6) {
|
||||||
|
// a slave register is specified
|
||||||
|
slaveRegister = argv[2] + (argv[3] << 7);
|
||||||
|
data = argv[4] + (argv[5] << 7); // bytes to read
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// a slave register is NOT specified
|
||||||
|
slaveRegister = I2C_REGISTER_NOT_SPECIFIED;
|
||||||
|
data = argv[2] + (argv[3] << 7); // bytes to read
|
||||||
|
}
|
||||||
|
readAndReportData(slaveAddress, (int)slaveRegister, data, stopTX);
|
||||||
|
break;
|
||||||
|
case I2C_READ_CONTINUOUSLY:
|
||||||
|
if ((queryIndex + 1) >= I2C_MAX_QUERIES) {
|
||||||
|
// too many queries, just ignore
|
||||||
|
Firmata.sendString("too many queries");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (argc == 6) {
|
||||||
|
// a slave register is specified
|
||||||
|
slaveRegister = argv[2] + (argv[3] << 7);
|
||||||
|
data = argv[4] + (argv[5] << 7); // bytes to read
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// a slave register is NOT specified
|
||||||
|
slaveRegister = (int)I2C_REGISTER_NOT_SPECIFIED;
|
||||||
|
data = argv[2] + (argv[3] << 7); // bytes to read
|
||||||
|
}
|
||||||
|
queryIndex++;
|
||||||
|
query[queryIndex].addr = slaveAddress;
|
||||||
|
query[queryIndex].reg = slaveRegister;
|
||||||
|
query[queryIndex].bytes = data;
|
||||||
|
query[queryIndex].stopTX = stopTX;
|
||||||
|
break;
|
||||||
|
case I2C_STOP_READING:
|
||||||
|
byte queryIndexToSkip;
|
||||||
|
// if read continuous mode is enabled for only 1 i2c device, disable
|
||||||
|
// read continuous reporting for that device
|
||||||
|
if (queryIndex <= 0) {
|
||||||
|
queryIndex = -1;
|
||||||
|
} else {
|
||||||
|
queryIndexToSkip = 0;
|
||||||
|
// if read continuous mode is enabled for multiple devices,
|
||||||
|
// determine which device to stop reading and remove it's data from
|
||||||
|
// the array, shifiting other array data to fill the space
|
||||||
|
for (byte i = 0; i < queryIndex + 1; i++) {
|
||||||
|
if (query[i].addr == slaveAddress) {
|
||||||
|
queryIndexToSkip = i;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
for (byte i = queryIndexToSkip; i < queryIndex + 1; i++) {
|
||||||
|
if (i < I2C_MAX_QUERIES) {
|
||||||
|
query[i].addr = query[i + 1].addr;
|
||||||
|
query[i].reg = query[i + 1].reg;
|
||||||
|
query[i].bytes = query[i + 1].bytes;
|
||||||
|
query[i].stopTX = query[i + 1].stopTX;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
queryIndex--;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case I2C_CONFIG:
|
||||||
|
delayTime = (argv[0] + (argv[1] << 7));
|
||||||
|
|
||||||
|
if (argc > 1 && delayTime > 0) {
|
||||||
|
i2cReadDelayTime = delayTime;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!isI2CEnabled) {
|
||||||
|
enableI2CPins();
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
case SERVO_CONFIG:
|
||||||
|
if (argc > 4) {
|
||||||
|
// these vars are here for clarity, they'll optimized away by the compiler
|
||||||
|
byte pin = argv[0];
|
||||||
|
int minPulse = argv[1] + (argv[2] << 7);
|
||||||
|
int maxPulse = argv[3] + (argv[4] << 7);
|
||||||
|
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
if (servoPinMap[pin] < MAX_SERVOS && servos[servoPinMap[pin]].attached()) {
|
||||||
|
detachServo(pin);
|
||||||
|
}
|
||||||
|
attachServo(pin, minPulse, maxPulse);
|
||||||
|
setPinModeCallback(pin, PIN_MODE_SERVO);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case SAMPLING_INTERVAL:
|
||||||
|
if (argc > 1) {
|
||||||
|
samplingInterval = argv[0] + (argv[1] << 7);
|
||||||
|
if (samplingInterval < MINIMUM_SAMPLING_INTERVAL) {
|
||||||
|
samplingInterval = MINIMUM_SAMPLING_INTERVAL;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
//Firmata.sendString("Not enough data");
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case EXTENDED_ANALOG:
|
||||||
|
if (argc > 1) {
|
||||||
|
int val = argv[1];
|
||||||
|
if (argc > 2) val |= (argv[2] << 7);
|
||||||
|
if (argc > 3) val |= (argv[3] << 14);
|
||||||
|
analogWriteCallback(argv[0], val);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case CAPABILITY_QUERY:
|
||||||
|
Firmata.write(START_SYSEX);
|
||||||
|
Firmata.write(CAPABILITY_RESPONSE);
|
||||||
|
for (byte pin = 0; pin < TOTAL_PINS; pin++) {
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
Firmata.write((byte)INPUT);
|
||||||
|
Firmata.write(1);
|
||||||
|
Firmata.write((byte)PIN_MODE_PULLUP);
|
||||||
|
Firmata.write(1);
|
||||||
|
Firmata.write((byte)OUTPUT);
|
||||||
|
Firmata.write(1);
|
||||||
|
}
|
||||||
|
if (IS_PIN_ANALOG(pin)) {
|
||||||
|
Firmata.write(PIN_MODE_ANALOG);
|
||||||
|
Firmata.write(10); // 10 = 10-bit resolution
|
||||||
|
}
|
||||||
|
if (IS_PIN_PWM(pin)) {
|
||||||
|
Firmata.write(PIN_MODE_PWM);
|
||||||
|
Firmata.write(DEFAULT_PWM_RESOLUTION);
|
||||||
|
}
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
Firmata.write(PIN_MODE_SERVO);
|
||||||
|
Firmata.write(14);
|
||||||
|
}
|
||||||
|
if (IS_PIN_I2C(pin)) {
|
||||||
|
Firmata.write(PIN_MODE_I2C);
|
||||||
|
Firmata.write(1); // TODO: could assign a number to map to SCL or SDA
|
||||||
|
}
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
serialFeature.handleCapability(pin);
|
||||||
|
#endif
|
||||||
|
Firmata.write(127);
|
||||||
|
}
|
||||||
|
Firmata.write(END_SYSEX);
|
||||||
|
break;
|
||||||
|
case PIN_STATE_QUERY:
|
||||||
|
if (argc > 0) {
|
||||||
|
byte pin = argv[0];
|
||||||
|
Firmata.write(START_SYSEX);
|
||||||
|
Firmata.write(PIN_STATE_RESPONSE);
|
||||||
|
Firmata.write(pin);
|
||||||
|
if (pin < TOTAL_PINS) {
|
||||||
|
Firmata.write(Firmata.getPinMode(pin));
|
||||||
|
Firmata.write((byte)Firmata.getPinState(pin) & 0x7F);
|
||||||
|
if (Firmata.getPinState(pin) & 0xFF80) Firmata.write((byte)(Firmata.getPinState(pin) >> 7) & 0x7F);
|
||||||
|
if (Firmata.getPinState(pin) & 0xC000) Firmata.write((byte)(Firmata.getPinState(pin) >> 14) & 0x7F);
|
||||||
|
}
|
||||||
|
Firmata.write(END_SYSEX);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case ANALOG_MAPPING_QUERY:
|
||||||
|
Firmata.write(START_SYSEX);
|
||||||
|
Firmata.write(ANALOG_MAPPING_RESPONSE);
|
||||||
|
for (byte pin = 0; pin < TOTAL_PINS; pin++) {
|
||||||
|
Firmata.write(IS_PIN_ANALOG(pin) ? PIN_TO_ANALOG(pin) : 127);
|
||||||
|
}
|
||||||
|
Firmata.write(END_SYSEX);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SERIAL_MESSAGE:
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
serialFeature.handleSysex(command, argc, argv);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*==============================================================================
|
||||||
|
* SETUP()
|
||||||
|
*============================================================================*/
|
||||||
|
|
||||||
|
void systemResetCallback()
|
||||||
|
{
|
||||||
|
isResetting = true;
|
||||||
|
|
||||||
|
// initialize a defalt state
|
||||||
|
// TODO: option to load config from EEPROM instead of default
|
||||||
|
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
serialFeature.reset();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (isI2CEnabled) {
|
||||||
|
disableI2CPins();
|
||||||
|
}
|
||||||
|
|
||||||
|
for (byte i = 0; i < TOTAL_PORTS; i++) {
|
||||||
|
reportPINs[i] = false; // by default, reporting off
|
||||||
|
portConfigInputs[i] = 0; // until activated
|
||||||
|
previousPINs[i] = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (byte i = 0; i < TOTAL_PINS; i++) {
|
||||||
|
// pins with analog capability default to analog input
|
||||||
|
// otherwise, pins default to digital output
|
||||||
|
if (IS_PIN_ANALOG(i)) {
|
||||||
|
// turns off pullup, configures everything
|
||||||
|
setPinModeCallback(i, PIN_MODE_ANALOG);
|
||||||
|
} else if (IS_PIN_DIGITAL(i)) {
|
||||||
|
// sets the output to 0, configures portConfigInputs
|
||||||
|
setPinModeCallback(i, OUTPUT);
|
||||||
|
}
|
||||||
|
|
||||||
|
servoPinMap[i] = 255;
|
||||||
|
}
|
||||||
|
// by default, do not report any analog inputs
|
||||||
|
analogInputsToReport = 0;
|
||||||
|
|
||||||
|
detachedServoCount = 0;
|
||||||
|
servoCount = 0;
|
||||||
|
|
||||||
|
/* send digital inputs to set the initial state on the host computer,
|
||||||
|
* since once in the loop(), this firmware will only send on change */
|
||||||
|
/*
|
||||||
|
TODO: this can never execute, since no pins default to digital input
|
||||||
|
but it will be needed when/if we support EEPROM stored config
|
||||||
|
for (byte i=0; i < TOTAL_PORTS; i++) {
|
||||||
|
outputPort(i, readPort(i, portConfigInputs[i]), true);
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
isResetting = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
Firmata.setFirmwareVersion(FIRMATA_FIRMWARE_MAJOR_VERSION, FIRMATA_FIRMWARE_MINOR_VERSION);
|
||||||
|
|
||||||
|
Firmata.attach(ANALOG_MESSAGE, analogWriteCallback);
|
||||||
|
Firmata.attach(DIGITAL_MESSAGE, digitalWriteCallback);
|
||||||
|
Firmata.attach(REPORT_ANALOG, reportAnalogCallback);
|
||||||
|
Firmata.attach(REPORT_DIGITAL, reportDigitalCallback);
|
||||||
|
Firmata.attach(SET_PIN_MODE, setPinModeCallback);
|
||||||
|
Firmata.attach(SET_DIGITAL_PIN_VALUE, setPinValueCallback);
|
||||||
|
Firmata.attach(START_SYSEX, sysexCallback);
|
||||||
|
Firmata.attach(SYSTEM_RESET, systemResetCallback);
|
||||||
|
|
||||||
|
// to use a port other than Serial, such as Serial1 on an Arduino Leonardo or Mega,
|
||||||
|
// Call begin(baud) on the alternate serial port and pass it to Firmata to begin like this:
|
||||||
|
// Serial1.begin(57600);
|
||||||
|
// Firmata.begin(Serial1);
|
||||||
|
// However do not do this if you are using SERIAL_MESSAGE
|
||||||
|
|
||||||
|
Firmata.begin(57600);
|
||||||
|
while (!Serial) {
|
||||||
|
; // wait for serial port to connect. Needed for ATmega32u4-based boards and Arduino 101
|
||||||
|
}
|
||||||
|
|
||||||
|
systemResetCallback(); // reset to default config
|
||||||
|
}
|
||||||
|
|
||||||
|
/*==============================================================================
|
||||||
|
* LOOP()
|
||||||
|
*============================================================================*/
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
byte pin, analogPin;
|
||||||
|
|
||||||
|
/* DIGITALREAD - as fast as possible, check for changes and output them to the
|
||||||
|
* FTDI buffer using Serial.print() */
|
||||||
|
checkDigitalInputs();
|
||||||
|
|
||||||
|
/* STREAMREAD - processing incoming messagse as soon as possible, while still
|
||||||
|
* checking digital inputs. */
|
||||||
|
while (Firmata.available())
|
||||||
|
Firmata.processInput();
|
||||||
|
|
||||||
|
// TODO - ensure that Stream buffer doesn't go over 60 bytes
|
||||||
|
|
||||||
|
currentMillis = millis();
|
||||||
|
if (currentMillis - previousMillis > samplingInterval) {
|
||||||
|
previousMillis += samplingInterval;
|
||||||
|
/* ANALOGREAD - do all analogReads() at the configured sampling interval */
|
||||||
|
for (pin = 0; pin < TOTAL_PINS; pin++) {
|
||||||
|
if (IS_PIN_ANALOG(pin) && Firmata.getPinMode(pin) == PIN_MODE_ANALOG) {
|
||||||
|
analogPin = PIN_TO_ANALOG(pin);
|
||||||
|
if (analogInputsToReport & (1 << analogPin)) {
|
||||||
|
Firmata.sendAnalog(analogPin, analogRead(analogPin));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// report i2c data for all device with read continuous mode enabled
|
||||||
|
if (queryIndex > -1) {
|
||||||
|
for (byte i = 0; i < queryIndex + 1; i++) {
|
||||||
|
readAndReportData(query[i].addr, query[i].reg, query[i].bytes, query[i].stopTX);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
serialFeature.update();
|
||||||
|
#endif
|
||||||
|
}
|
37
portail_coulissant/porcou-arduino/dc_motor/dc_motor.ino
Normal file
37
portail_coulissant/porcou-arduino/dc_motor/dc_motor.ino
Normal file
@ -0,0 +1,37 @@
|
|||||||
|
#include "Grove_Motor_Driver_TB6612FNG.h"
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
MotorDriver motor;
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
// join I2C bus (I2Cdev library doesn't do this automatically)
|
||||||
|
Wire.begin();
|
||||||
|
Serial.begin(9600);
|
||||||
|
motor.init();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
// drive 2 dc motors at speed=255, clockwise
|
||||||
|
Serial.println("run at speed=255");
|
||||||
|
motor.dcMotorRun(MOTOR_CHA, 255);
|
||||||
|
motor.dcMotorRun(MOTOR_CHB, 255);
|
||||||
|
delay(1000);
|
||||||
|
|
||||||
|
// brake
|
||||||
|
Serial.println("brake");
|
||||||
|
motor.dcMotorBrake(MOTOR_CHA);
|
||||||
|
motor.dcMotorBrake(MOTOR_CHB);
|
||||||
|
delay(1000);
|
||||||
|
|
||||||
|
// drive 2 dc motors at speed=200, anticlockwise
|
||||||
|
Serial.println("run at speed=-200");
|
||||||
|
motor.dcMotorRun(MOTOR_CHA, -200);
|
||||||
|
motor.dcMotorRun(MOTOR_CHB, -200);
|
||||||
|
delay(1000);
|
||||||
|
|
||||||
|
// stop 2 motors
|
||||||
|
Serial.println("stop");
|
||||||
|
motor.dcMotorStop(MOTOR_CHA);
|
||||||
|
motor.dcMotorStop(MOTOR_CHB);
|
||||||
|
delay(1000);
|
||||||
|
}
|
@ -0,0 +1,21 @@
|
|||||||
|
#include "Grove_Motor_Driver_TB6612FNG.h"
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
MotorDriver motor;
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
// join I2C bus (I2Cdev library doesn't do this automatically)
|
||||||
|
Wire.begin();
|
||||||
|
Serial.begin(9600);
|
||||||
|
motor.init();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
|
||||||
|
|
||||||
|
// stop 2 motors
|
||||||
|
Serial.println("stop");
|
||||||
|
motor.dcMotorStop(MOTOR_CHA);
|
||||||
|
motor.dcMotorStop(MOTOR_CHB);
|
||||||
|
delay(1000);
|
||||||
|
}
|
Binary file not shown.
6
portail_coulissant/porcou-arduino/lib/README.md
Normal file
6
portail_coulissant/porcou-arduino/lib/README.md
Normal file
@ -0,0 +1,6 @@
|
|||||||
|
## Bibliothèques pour Arduino
|
||||||
|
|
||||||
|
### Grove - I2C Motor Driver (TB6612FNG) :
|
||||||
|
- Wiki : https://wiki.seeedstudio.com/Grove-I2C_Motor_Driver-TB6612FNG/
|
||||||
|
- Forge : https://github.com/Seeed-Studio/Grove_Motor_Driver_TB6612FNG
|
||||||
|
- Licence : MIT Licence
|
870
portail_coulissant/porcou-arduino/porcou-arduino.ino
Normal file
870
portail_coulissant/porcou-arduino/porcou-arduino.ino
Normal file
@ -0,0 +1,870 @@
|
|||||||
|
/*
|
||||||
|
Firmata is a generic protocol for communicating with microcontrollers
|
||||||
|
from software on a host computer. It is intended to work with
|
||||||
|
any host computer software package.
|
||||||
|
|
||||||
|
To download a host software package, please click on the following link
|
||||||
|
to open the list of Firmata client libraries in your default browser.
|
||||||
|
|
||||||
|
https://github.com/firmata/arduino#firmata-client-libraries
|
||||||
|
|
||||||
|
Copyright (C) 2006-2008 Hans-Christoph Steiner. All rights reserved.
|
||||||
|
Copyright (C) 2010-2011 Paul Stoffregen. All rights reserved.
|
||||||
|
Copyright (C) 2009 Shigeru Kobayashi. All rights reserved.
|
||||||
|
Copyright (C) 2009-2016 Jeff Hoefs. All rights reserved.
|
||||||
|
|
||||||
|
This library is free software; you can redistribute it and/or
|
||||||
|
modify it under the terms of the GNU Lesser General Public
|
||||||
|
License as published by the Free Software Foundation; either
|
||||||
|
version 2.1 of the License, or (at your option) any later version.
|
||||||
|
|
||||||
|
See file LICENSE.txt for further informations on licensing terms.
|
||||||
|
|
||||||
|
Last updated August 17th, 2017
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "Grove_Motor_Driver_TB6612FNG.h"
|
||||||
|
#include <Servo.h>
|
||||||
|
#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_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
|
||||||
|
|
||||||
|
// the minimum interval for sampling analog input
|
||||||
|
#define MINIMUM_SAMPLING_INTERVAL 1
|
||||||
|
|
||||||
|
|
||||||
|
/*==============================================================================
|
||||||
|
* GLOBAL VARIABLES
|
||||||
|
*============================================================================*/
|
||||||
|
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
SerialFirmata serialFeature;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* analog inputs */
|
||||||
|
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
|
||||||
|
|
||||||
|
/* pins configuration */
|
||||||
|
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)
|
||||||
|
|
||||||
|
/* i2c data */
|
||||||
|
struct i2c_device_info {
|
||||||
|
byte addr;
|
||||||
|
int reg;
|
||||||
|
byte bytes;
|
||||||
|
byte stopTX;
|
||||||
|
};
|
||||||
|
|
||||||
|
/* for i2c read continuous more */
|
||||||
|
i2c_device_info query[I2C_MAX_QUERIES];
|
||||||
|
|
||||||
|
byte i2cRxData[64];
|
||||||
|
boolean isI2CEnabled = false;
|
||||||
|
signed char queryIndex = -1;
|
||||||
|
// default delay time between i2c read request and Wire.requestFrom()
|
||||||
|
unsigned int i2cReadDelayTime = 0;
|
||||||
|
|
||||||
|
Servo servos[MAX_SERVOS];
|
||||||
|
byte servoPinMap[TOTAL_PINS];
|
||||||
|
byte detachedServos[MAX_SERVOS];
|
||||||
|
byte detachedServoCount = 0;
|
||||||
|
byte servoCount = 0;
|
||||||
|
|
||||||
|
boolean isResetting = false;
|
||||||
|
|
||||||
|
MotorDriver motor;
|
||||||
|
|
||||||
|
// Forward declare a few functions to avoid compiler errors with older versions
|
||||||
|
// of the Arduino IDE.
|
||||||
|
void setPinModeCallback(byte, int);
|
||||||
|
void reportAnalogCallback(byte analogPin, int value);
|
||||||
|
void sysexCallback(byte, byte, byte*);
|
||||||
|
|
||||||
|
/* utility functions */
|
||||||
|
void wireWrite(byte data)
|
||||||
|
{
|
||||||
|
#if ARDUINO >= 100
|
||||||
|
Wire.write((byte)data);
|
||||||
|
#else
|
||||||
|
Wire.send(data);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
byte wireRead(void)
|
||||||
|
{
|
||||||
|
#if ARDUINO >= 100
|
||||||
|
return Wire.read();
|
||||||
|
#else
|
||||||
|
return Wire.receive();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/*==============================================================================
|
||||||
|
* FUNCTIONS
|
||||||
|
*============================================================================*/
|
||||||
|
|
||||||
|
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) {
|
||||||
|
servoPinMap[pin] = detachedServos[detachedServoCount - 1];
|
||||||
|
if (detachedServoCount > 0) detachedServoCount--;
|
||||||
|
} else {
|
||||||
|
servoPinMap[pin] = servoCount;
|
||||||
|
servoCount++;
|
||||||
|
}
|
||||||
|
if (minPulse > 0 && maxPulse > 0) {
|
||||||
|
servos[servoPinMap[pin]].attach(PIN_TO_DIGITAL(pin), minPulse, maxPulse);
|
||||||
|
} else {
|
||||||
|
servos[servoPinMap[pin]].attach(PIN_TO_DIGITAL(pin));
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
Firmata.sendString("Max servos attached");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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
|
||||||
|
if (servoPinMap[pin] == servoCount && servoCount > 0) {
|
||||||
|
servoCount--;
|
||||||
|
} else if (servoCount > 0) {
|
||||||
|
// keep track of detached servos because we want to reuse their indexes
|
||||||
|
// before incrementing the count of attached servos
|
||||||
|
detachedServoCount++;
|
||||||
|
detachedServos[detachedServoCount - 1] = servoPinMap[pin];
|
||||||
|
}
|
||||||
|
|
||||||
|
servoPinMap[pin] = 255;
|
||||||
|
}
|
||||||
|
|
||||||
|
void enableI2CPins()
|
||||||
|
{
|
||||||
|
byte i;
|
||||||
|
// is there a faster way to do this? would probaby require importing
|
||||||
|
// Arduino.h to get SCL and SDA pins
|
||||||
|
for (i = 0; i < TOTAL_PINS; i++) {
|
||||||
|
if (IS_PIN_I2C(i)) {
|
||||||
|
// mark pins as i2c so they are ignore in non i2c data requests
|
||||||
|
setPinModeCallback(i, PIN_MODE_I2C);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
isI2CEnabled = true;
|
||||||
|
|
||||||
|
Wire.begin();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* disable the i2c pins so they can be used for other functions */
|
||||||
|
void disableI2CPins() {
|
||||||
|
isI2CEnabled = false;
|
||||||
|
// disable read continuous mode for all devices
|
||||||
|
queryIndex = -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void readAndReportData(byte address, int theRegister, byte numBytes, byte stopTX) {
|
||||||
|
// allow I2C requests that don't require a register read
|
||||||
|
// for example, some devices using an interrupt pin to signify new data available
|
||||||
|
// do not always require the register read so upon interrupt you call Wire.requestFrom()
|
||||||
|
if (theRegister != I2C_REGISTER_NOT_SPECIFIED) {
|
||||||
|
Wire.beginTransmission(address);
|
||||||
|
wireWrite((byte)theRegister);
|
||||||
|
Wire.endTransmission(stopTX); // default = true
|
||||||
|
// do not set a value of 0
|
||||||
|
if (i2cReadDelayTime > 0) {
|
||||||
|
// delay is necessary for some devices such as WiiNunchuck
|
||||||
|
delayMicroseconds(i2cReadDelayTime);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
theRegister = 0; // fill the register with a dummy value
|
||||||
|
}
|
||||||
|
|
||||||
|
Wire.requestFrom(address, numBytes); // all bytes are returned in requestFrom
|
||||||
|
|
||||||
|
// check to be sure correct number of bytes were returned by slave
|
||||||
|
if (numBytes < Wire.available()) {
|
||||||
|
Firmata.sendString("I2C: Too many bytes received");
|
||||||
|
} else if (numBytes > Wire.available()) {
|
||||||
|
Firmata.sendString("I2C: Too few bytes received");
|
||||||
|
numBytes = Wire.available();
|
||||||
|
}
|
||||||
|
|
||||||
|
i2cRxData[0] = address;
|
||||||
|
i2cRxData[1] = theRegister;
|
||||||
|
|
||||||
|
for (int i = 0; i < numBytes && Wire.available(); i++) {
|
||||||
|
i2cRxData[2 + i] = wireRead();
|
||||||
|
}
|
||||||
|
|
||||||
|
// send slave address, register and received bytes
|
||||||
|
Firmata.sendSysex(SYSEX_I2C_REPLY, numBytes + 2, i2cRxData);
|
||||||
|
}
|
||||||
|
|
||||||
|
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
|
||||||
|
if (forceSend || previousPINs[portNumber] != portValue) {
|
||||||
|
Firmata.sendDigitalPort(portNumber, portValue);
|
||||||
|
previousPINs[portNumber] = portValue;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* -----------------------------------------------------------------------------
|
||||||
|
* 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)
|
||||||
|
{
|
||||||
|
/* 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. */
|
||||||
|
if (TOTAL_PORTS > 0 && reportPINs[0]) outputPort(0, readPort(0, portConfigInputs[0]), false);
|
||||||
|
if (TOTAL_PORTS > 1 && reportPINs[1]) outputPort(1, readPort(1, portConfigInputs[1]), false);
|
||||||
|
if (TOTAL_PORTS > 2 && reportPINs[2]) outputPort(2, readPort(2, portConfigInputs[2]), false);
|
||||||
|
if (TOTAL_PORTS > 3 && reportPINs[3]) outputPort(3, readPort(3, portConfigInputs[3]), false);
|
||||||
|
if (TOTAL_PORTS > 4 && reportPINs[4]) outputPort(4, readPort(4, portConfigInputs[4]), false);
|
||||||
|
if (TOTAL_PORTS > 5 && reportPINs[5]) outputPort(5, readPort(5, portConfigInputs[5]), false);
|
||||||
|
if (TOTAL_PORTS > 6 && reportPINs[6]) outputPort(6, readPort(6, portConfigInputs[6]), false);
|
||||||
|
if (TOTAL_PORTS > 7 && reportPINs[7]) outputPort(7, readPort(7, portConfigInputs[7]), false);
|
||||||
|
if (TOTAL_PORTS > 8 && reportPINs[8]) outputPort(8, readPort(8, portConfigInputs[8]), false);
|
||||||
|
if (TOTAL_PORTS > 9 && reportPINs[9]) outputPort(9, readPort(9, portConfigInputs[9]), false);
|
||||||
|
if (TOTAL_PORTS > 10 && reportPINs[10]) outputPort(10, readPort(10, portConfigInputs[10]), false);
|
||||||
|
if (TOTAL_PORTS > 11 && reportPINs[11]) outputPort(11, readPort(11, portConfigInputs[11]), false);
|
||||||
|
if (TOTAL_PORTS > 12 && reportPINs[12]) outputPort(12, readPort(12, portConfigInputs[12]), false);
|
||||||
|
if (TOTAL_PORTS > 13 && reportPINs[13]) outputPort(13, readPort(13, portConfigInputs[13]), false);
|
||||||
|
if (TOTAL_PORTS > 14 && reportPINs[14]) outputPort(14, readPort(14, portConfigInputs[14]), false);
|
||||||
|
if (TOTAL_PORTS > 15 && reportPINs[15]) outputPort(15, readPort(15, portConfigInputs[15]), false);
|
||||||
|
}
|
||||||
|
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
/* 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)
|
||||||
|
{
|
||||||
|
if (Firmata.getPinMode(pin) == PIN_MODE_IGNORE)
|
||||||
|
return;
|
||||||
|
|
||||||
|
if (Firmata.getPinMode(pin) == PIN_MODE_I2C && isI2CEnabled && mode != PIN_MODE_I2C) {
|
||||||
|
// disable i2c so pins can be used for other functions
|
||||||
|
// the following if statements should reconfigure the pins properly
|
||||||
|
disableI2CPins();
|
||||||
|
}
|
||||||
|
if (IS_PIN_DIGITAL(pin) && mode != PIN_MODE_SERVO) {
|
||||||
|
if (servoPinMap[pin] < MAX_SERVOS && servos[servoPinMap[pin]].attached()) {
|
||||||
|
detachServo(pin);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (IS_PIN_ANALOG(pin)) {
|
||||||
|
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) {
|
||||||
|
portConfigInputs[pin / 8] |= (1 << (pin & 7));
|
||||||
|
} else {
|
||||||
|
portConfigInputs[pin / 8] &= ~(1 << (pin & 7));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
Firmata.setPinState(pin, 0);
|
||||||
|
switch (mode) {
|
||||||
|
case PIN_MODE_ANALOG:
|
||||||
|
if (IS_PIN_ANALOG(pin)) {
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
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
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
Firmata.setPinMode(pin, PIN_MODE_ANALOG);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case INPUT:
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
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
|
||||||
|
#endif
|
||||||
|
Firmata.setPinMode(pin, INPUT);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case PIN_MODE_PULLUP:
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
pinMode(PIN_TO_DIGITAL(pin), INPUT_PULLUP);
|
||||||
|
Firmata.setPinMode(pin, PIN_MODE_PULLUP);
|
||||||
|
Firmata.setPinState(pin, 1);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OUTPUT:
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
if (Firmata.getPinMode(pin) == PIN_MODE_PWM) {
|
||||||
|
// Disable PWM if pin mode was previously set to PWM.
|
||||||
|
digitalWrite(PIN_TO_DIGITAL(pin), LOW);
|
||||||
|
}
|
||||||
|
pinMode(PIN_TO_DIGITAL(pin), OUTPUT);
|
||||||
|
Firmata.setPinMode(pin, OUTPUT);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case PIN_MODE_PWM:
|
||||||
|
if (IS_PIN_PWM(pin)) {
|
||||||
|
pinMode(PIN_TO_PWM(pin), OUTPUT);
|
||||||
|
analogWrite(PIN_TO_PWM(pin), 0);
|
||||||
|
Firmata.setPinMode(pin, PIN_MODE_PWM);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case PIN_MODE_SERVO:
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
Firmata.setPinMode(pin, PIN_MODE_SERVO);
|
||||||
|
if (servoPinMap[pin] == 255 || !servos[servoPinMap[pin]].attached()) {
|
||||||
|
// pass -1 for min and max pulse values to use default values set
|
||||||
|
// by Servo library
|
||||||
|
attachServo(pin, -1, -1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case PIN_MODE_I2C:
|
||||||
|
if (IS_PIN_I2C(pin)) {
|
||||||
|
// mark the pin as i2c
|
||||||
|
// the user must call I2C_CONFIG to enable I2C for a device
|
||||||
|
Firmata.setPinMode(pin, PIN_MODE_I2C);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case PIN_MODE_SERIAL:
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
serialFeature.handlePinMode(pin, PIN_MODE_SERIAL);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
Firmata.sendString("Unknown pin mode"); // TODO: put error msgs in EEPROM
|
||||||
|
}
|
||||||
|
// TODO: save status to EEPROM here, if changed
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Sets the value of an individual pin. Useful if you want to set a pin value but
|
||||||
|
* are not tracking the digital port state.
|
||||||
|
* 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)
|
||||||
|
{
|
||||||
|
if (pin < TOTAL_PINS && IS_PIN_DIGITAL(pin)) {
|
||||||
|
if (Firmata.getPinMode(pin) == OUTPUT) {
|
||||||
|
Firmata.setPinState(pin, value);
|
||||||
|
digitalWrite(PIN_TO_DIGITAL(pin), value);
|
||||||
|
|
||||||
|
// Gestion des moteurs (ajout : porcou-arduino.ino)
|
||||||
|
if (digitalRead(2) == LOW && digitalRead(3) == LOW) {
|
||||||
|
motor.dcMotorStop(MOTOR_CHA);
|
||||||
|
/* Serial.println("motor.dcMotorStop(MOTOR_CHA);"); */
|
||||||
|
/* motor.dcMotorBrake(MOTOR_CHA); */
|
||||||
|
}
|
||||||
|
if (digitalRead(2) == HIGH && digitalRead(3) == HIGH) {
|
||||||
|
motor.dcMotorStop(MOTOR_CHA);
|
||||||
|
/* Serial.println("motor.dcMotorStop(MOTOR_CHA);"); */
|
||||||
|
}
|
||||||
|
if (digitalRead(2) == HIGH && digitalRead(3) == LOW) {
|
||||||
|
motor.dcMotorRun(MOTOR_CHA, 255);
|
||||||
|
/* Serial.println("motor.dcMotorRun(MOTOR_CHA, 255);"); */
|
||||||
|
}
|
||||||
|
if (digitalRead(2) == LOW && digitalRead(3) == HIGH) {
|
||||||
|
motor.dcMotorRun(MOTOR_CHA, -255);
|
||||||
|
/* Serial.println("motor.dcMotorRun(MOTOR_CHA, -255);"); */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void analogWriteCallback(byte pin, int value)
|
||||||
|
{
|
||||||
|
if (pin < TOTAL_PINS) {
|
||||||
|
switch (Firmata.getPinMode(pin)) {
|
||||||
|
case PIN_MODE_SERVO:
|
||||||
|
if (IS_PIN_DIGITAL(pin))
|
||||||
|
servos[servoPinMap[pin]].write(value);
|
||||||
|
Firmata.setPinState(pin, value);
|
||||||
|
break;
|
||||||
|
case PIN_MODE_PWM:
|
||||||
|
if (IS_PIN_PWM(pin))
|
||||||
|
analogWrite(PIN_TO_PWM(pin), value);
|
||||||
|
Firmata.setPinState(pin, value);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void digitalWriteCallback(byte port, int value)
|
||||||
|
{
|
||||||
|
byte pin, lastPin, pinValue, mask = 1, pinWriteMask = 0;
|
||||||
|
|
||||||
|
if (port < TOTAL_PORTS) {
|
||||||
|
// create a mask of the pins on this port that are writable.
|
||||||
|
lastPin = port * 8 + 8;
|
||||||
|
if (lastPin > TOTAL_PINS) lastPin = TOTAL_PINS;
|
||||||
|
for (pin = port * 8; pin < lastPin; pin++) {
|
||||||
|
// do not disturb non-digital pins (eg, Rx & Tx)
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
// do not touch pins in PWM, ANALOG, SERVO or other modes
|
||||||
|
if (Firmata.getPinMode(pin) == OUTPUT || Firmata.getPinMode(pin) == INPUT) {
|
||||||
|
pinValue = ((byte)value & mask) ? 1 : 0;
|
||||||
|
if (Firmata.getPinMode(pin) == OUTPUT) {
|
||||||
|
pinWriteMask |= mask;
|
||||||
|
} else if (Firmata.getPinMode(pin) == INPUT && pinValue == 1 && Firmata.getPinState(pin) != 1) {
|
||||||
|
// only handle INPUT here for backwards compatibility
|
||||||
|
#if ARDUINO > 100
|
||||||
|
pinMode(pin, INPUT_PULLUP);
|
||||||
|
#else
|
||||||
|
// only write to the INPUT pin to enable pullups if Arduino v1.0.0 or earlier
|
||||||
|
pinWriteMask |= mask;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
Firmata.setPinState(pin, pinValue);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
mask = mask << 1;
|
||||||
|
}
|
||||||
|
writePort(port, (byte)value, pinWriteMask);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
/* sets bits in a bit array (int) to toggle the reporting of the analogIns
|
||||||
|
*/
|
||||||
|
//void FirmataClass::setAnalogPinReporting(byte pin, byte state) {
|
||||||
|
//}
|
||||||
|
void reportAnalogCallback(byte analogPin, int value)
|
||||||
|
{
|
||||||
|
if (analogPin < TOTAL_ANALOG_PINS) {
|
||||||
|
if (value == 0) {
|
||||||
|
analogInputsToReport = analogInputsToReport & ~ (1 << analogPin);
|
||||||
|
} else {
|
||||||
|
analogInputsToReport = analogInputsToReport | (1 << analogPin);
|
||||||
|
// prevent during system reset or all analog pin values will be reported
|
||||||
|
// which may report noise for unconnected analog pins
|
||||||
|
if (!isResetting) {
|
||||||
|
// Send pin value immediately. This is helpful when connected via
|
||||||
|
// ethernet, wi-fi or bluetooth so pin states can be known upon
|
||||||
|
// reconnecting.
|
||||||
|
Firmata.sendAnalog(analogPin, analogRead(analogPin));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// TODO: save status to EEPROM here, if changed
|
||||||
|
}
|
||||||
|
|
||||||
|
void reportDigitalCallback(byte port, int value)
|
||||||
|
{
|
||||||
|
if (port < TOTAL_PORTS) {
|
||||||
|
reportPINs[port] = (byte)value;
|
||||||
|
// Send port value immediately. This is helpful when connected via
|
||||||
|
// ethernet, wi-fi or bluetooth so pin states can be known upon
|
||||||
|
// reconnecting.
|
||||||
|
if (value) outputPort(port, readPort(port, portConfigInputs[port]), true);
|
||||||
|
}
|
||||||
|
// do not disable analog reporting on these 8 pins, to allow some
|
||||||
|
// pins used for digital, others analog. Instead, allow both types
|
||||||
|
// of reporting to be enabled, but check if the pin is configured
|
||||||
|
// as analog when sampling the analog inputs. Likewise, while
|
||||||
|
// scanning digital pins, portConfigInputs will mask off values from any
|
||||||
|
// pins configured as analog
|
||||||
|
}
|
||||||
|
|
||||||
|
/*==============================================================================
|
||||||
|
* SYSEX-BASED commands
|
||||||
|
*============================================================================*/
|
||||||
|
|
||||||
|
void sysexCallback(byte command, byte argc, byte *argv)
|
||||||
|
{
|
||||||
|
byte mode;
|
||||||
|
byte stopTX;
|
||||||
|
byte slaveAddress;
|
||||||
|
byte data;
|
||||||
|
int slaveRegister;
|
||||||
|
unsigned int delayTime;
|
||||||
|
|
||||||
|
switch (command) {
|
||||||
|
case I2C_REQUEST:
|
||||||
|
mode = argv[1] & I2C_READ_WRITE_MODE_MASK;
|
||||||
|
if (argv[1] & I2C_10BIT_ADDRESS_MODE_MASK) {
|
||||||
|
Firmata.sendString("10-bit addressing not supported");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
slaveAddress = argv[0];
|
||||||
|
}
|
||||||
|
|
||||||
|
// need to invert the logic here since 0 will be default for client
|
||||||
|
// 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
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (mode) {
|
||||||
|
case I2C_WRITE:
|
||||||
|
Wire.beginTransmission(slaveAddress);
|
||||||
|
for (byte i = 2; i < argc; i += 2) {
|
||||||
|
data = argv[i] + (argv[i + 1] << 7);
|
||||||
|
wireWrite(data);
|
||||||
|
}
|
||||||
|
Wire.endTransmission();
|
||||||
|
delayMicroseconds(70);
|
||||||
|
break;
|
||||||
|
case I2C_READ:
|
||||||
|
if (argc == 6) {
|
||||||
|
// a slave register is specified
|
||||||
|
slaveRegister = argv[2] + (argv[3] << 7);
|
||||||
|
data = argv[4] + (argv[5] << 7); // bytes to read
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// a slave register is NOT specified
|
||||||
|
slaveRegister = I2C_REGISTER_NOT_SPECIFIED;
|
||||||
|
data = argv[2] + (argv[3] << 7); // bytes to read
|
||||||
|
}
|
||||||
|
readAndReportData(slaveAddress, (int)slaveRegister, data, stopTX);
|
||||||
|
break;
|
||||||
|
case I2C_READ_CONTINUOUSLY:
|
||||||
|
if ((queryIndex + 1) >= I2C_MAX_QUERIES) {
|
||||||
|
// too many queries, just ignore
|
||||||
|
Firmata.sendString("too many queries");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (argc == 6) {
|
||||||
|
// a slave register is specified
|
||||||
|
slaveRegister = argv[2] + (argv[3] << 7);
|
||||||
|
data = argv[4] + (argv[5] << 7); // bytes to read
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// a slave register is NOT specified
|
||||||
|
slaveRegister = (int)I2C_REGISTER_NOT_SPECIFIED;
|
||||||
|
data = argv[2] + (argv[3] << 7); // bytes to read
|
||||||
|
}
|
||||||
|
queryIndex++;
|
||||||
|
query[queryIndex].addr = slaveAddress;
|
||||||
|
query[queryIndex].reg = slaveRegister;
|
||||||
|
query[queryIndex].bytes = data;
|
||||||
|
query[queryIndex].stopTX = stopTX;
|
||||||
|
break;
|
||||||
|
case I2C_STOP_READING:
|
||||||
|
byte queryIndexToSkip;
|
||||||
|
// if read continuous mode is enabled for only 1 i2c device, disable
|
||||||
|
// read continuous reporting for that device
|
||||||
|
if (queryIndex <= 0) {
|
||||||
|
queryIndex = -1;
|
||||||
|
} else {
|
||||||
|
queryIndexToSkip = 0;
|
||||||
|
// if read continuous mode is enabled for multiple devices,
|
||||||
|
// determine which device to stop reading and remove it's data from
|
||||||
|
// the array, shifiting other array data to fill the space
|
||||||
|
for (byte i = 0; i < queryIndex + 1; i++) {
|
||||||
|
if (query[i].addr == slaveAddress) {
|
||||||
|
queryIndexToSkip = i;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
for (byte i = queryIndexToSkip; i < queryIndex + 1; i++) {
|
||||||
|
if (i < I2C_MAX_QUERIES) {
|
||||||
|
query[i].addr = query[i + 1].addr;
|
||||||
|
query[i].reg = query[i + 1].reg;
|
||||||
|
query[i].bytes = query[i + 1].bytes;
|
||||||
|
query[i].stopTX = query[i + 1].stopTX;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
queryIndex--;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case I2C_CONFIG:
|
||||||
|
delayTime = (argv[0] + (argv[1] << 7));
|
||||||
|
|
||||||
|
if (argc > 1 && delayTime > 0) {
|
||||||
|
i2cReadDelayTime = delayTime;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!isI2CEnabled) {
|
||||||
|
enableI2CPins();
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
case SERVO_CONFIG:
|
||||||
|
if (argc > 4) {
|
||||||
|
// these vars are here for clarity, they'll optimized away by the compiler
|
||||||
|
byte pin = argv[0];
|
||||||
|
int minPulse = argv[1] + (argv[2] << 7);
|
||||||
|
int maxPulse = argv[3] + (argv[4] << 7);
|
||||||
|
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
if (servoPinMap[pin] < MAX_SERVOS && servos[servoPinMap[pin]].attached()) {
|
||||||
|
detachServo(pin);
|
||||||
|
}
|
||||||
|
attachServo(pin, minPulse, maxPulse);
|
||||||
|
setPinModeCallback(pin, PIN_MODE_SERVO);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case SAMPLING_INTERVAL:
|
||||||
|
if (argc > 1) {
|
||||||
|
samplingInterval = argv[0] + (argv[1] << 7);
|
||||||
|
if (samplingInterval < MINIMUM_SAMPLING_INTERVAL) {
|
||||||
|
samplingInterval = MINIMUM_SAMPLING_INTERVAL;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
//Firmata.sendString("Not enough data");
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case EXTENDED_ANALOG:
|
||||||
|
if (argc > 1) {
|
||||||
|
int val = argv[1];
|
||||||
|
if (argc > 2) val |= (argv[2] << 7);
|
||||||
|
if (argc > 3) val |= (argv[3] << 14);
|
||||||
|
analogWriteCallback(argv[0], val);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case CAPABILITY_QUERY:
|
||||||
|
Firmata.write(START_SYSEX);
|
||||||
|
Firmata.write(CAPABILITY_RESPONSE);
|
||||||
|
for (byte pin = 0; pin < TOTAL_PINS; pin++) {
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
Firmata.write((byte)INPUT);
|
||||||
|
Firmata.write(1);
|
||||||
|
Firmata.write((byte)PIN_MODE_PULLUP);
|
||||||
|
Firmata.write(1);
|
||||||
|
Firmata.write((byte)OUTPUT);
|
||||||
|
Firmata.write(1);
|
||||||
|
}
|
||||||
|
if (IS_PIN_ANALOG(pin)) {
|
||||||
|
Firmata.write(PIN_MODE_ANALOG);
|
||||||
|
Firmata.write(10); // 10 = 10-bit resolution
|
||||||
|
}
|
||||||
|
if (IS_PIN_PWM(pin)) {
|
||||||
|
Firmata.write(PIN_MODE_PWM);
|
||||||
|
Firmata.write(DEFAULT_PWM_RESOLUTION);
|
||||||
|
}
|
||||||
|
if (IS_PIN_DIGITAL(pin)) {
|
||||||
|
Firmata.write(PIN_MODE_SERVO);
|
||||||
|
Firmata.write(14);
|
||||||
|
}
|
||||||
|
if (IS_PIN_I2C(pin)) {
|
||||||
|
Firmata.write(PIN_MODE_I2C);
|
||||||
|
Firmata.write(1); // TODO: could assign a number to map to SCL or SDA
|
||||||
|
}
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
serialFeature.handleCapability(pin);
|
||||||
|
#endif
|
||||||
|
Firmata.write(127);
|
||||||
|
}
|
||||||
|
Firmata.write(END_SYSEX);
|
||||||
|
break;
|
||||||
|
case PIN_STATE_QUERY:
|
||||||
|
if (argc > 0) {
|
||||||
|
byte pin = argv[0];
|
||||||
|
Firmata.write(START_SYSEX);
|
||||||
|
Firmata.write(PIN_STATE_RESPONSE);
|
||||||
|
Firmata.write(pin);
|
||||||
|
if (pin < TOTAL_PINS) {
|
||||||
|
Firmata.write(Firmata.getPinMode(pin));
|
||||||
|
Firmata.write((byte)Firmata.getPinState(pin) & 0x7F);
|
||||||
|
if (Firmata.getPinState(pin) & 0xFF80) Firmata.write((byte)(Firmata.getPinState(pin) >> 7) & 0x7F);
|
||||||
|
if (Firmata.getPinState(pin) & 0xC000) Firmata.write((byte)(Firmata.getPinState(pin) >> 14) & 0x7F);
|
||||||
|
}
|
||||||
|
Firmata.write(END_SYSEX);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case ANALOG_MAPPING_QUERY:
|
||||||
|
Firmata.write(START_SYSEX);
|
||||||
|
Firmata.write(ANALOG_MAPPING_RESPONSE);
|
||||||
|
for (byte pin = 0; pin < TOTAL_PINS; pin++) {
|
||||||
|
Firmata.write(IS_PIN_ANALOG(pin) ? PIN_TO_ANALOG(pin) : 127);
|
||||||
|
}
|
||||||
|
Firmata.write(END_SYSEX);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SERIAL_MESSAGE:
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
serialFeature.handleSysex(command, argc, argv);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*==============================================================================
|
||||||
|
* SETUP()
|
||||||
|
*============================================================================*/
|
||||||
|
|
||||||
|
void systemResetCallback()
|
||||||
|
{
|
||||||
|
isResetting = true;
|
||||||
|
|
||||||
|
// initialize a defalt state
|
||||||
|
// TODO: option to load config from EEPROM instead of default
|
||||||
|
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
serialFeature.reset();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (isI2CEnabled) {
|
||||||
|
disableI2CPins();
|
||||||
|
}
|
||||||
|
|
||||||
|
for (byte i = 0; i < TOTAL_PORTS; i++) {
|
||||||
|
reportPINs[i] = false; // by default, reporting off
|
||||||
|
portConfigInputs[i] = 0; // until activated
|
||||||
|
previousPINs[i] = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (byte i = 0; i < TOTAL_PINS; i++) {
|
||||||
|
// pins with analog capability default to analog input
|
||||||
|
// otherwise, pins default to digital output
|
||||||
|
if (IS_PIN_ANALOG(i)) {
|
||||||
|
// turns off pullup, configures everything
|
||||||
|
setPinModeCallback(i, PIN_MODE_ANALOG);
|
||||||
|
} else if (IS_PIN_DIGITAL(i)) {
|
||||||
|
// sets the output to 0, configures portConfigInputs
|
||||||
|
setPinModeCallback(i, OUTPUT);
|
||||||
|
}
|
||||||
|
|
||||||
|
servoPinMap[i] = 255;
|
||||||
|
}
|
||||||
|
// by default, do not report any analog inputs
|
||||||
|
analogInputsToReport = 0;
|
||||||
|
|
||||||
|
detachedServoCount = 0;
|
||||||
|
servoCount = 0;
|
||||||
|
|
||||||
|
/* send digital inputs to set the initial state on the host computer,
|
||||||
|
* since once in the loop(), this firmware will only send on change */
|
||||||
|
/*
|
||||||
|
TODO: this can never execute, since no pins default to digital input
|
||||||
|
but it will be needed when/if we support EEPROM stored config
|
||||||
|
for (byte i=0; i < TOTAL_PORTS; i++) {
|
||||||
|
outputPort(i, readPort(i, portConfigInputs[i]), true);
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
isResetting = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
Firmata.setFirmwareVersion(FIRMATA_FIRMWARE_MAJOR_VERSION, FIRMATA_FIRMWARE_MINOR_VERSION);
|
||||||
|
|
||||||
|
Firmata.attach(ANALOG_MESSAGE, analogWriteCallback);
|
||||||
|
Firmata.attach(DIGITAL_MESSAGE, digitalWriteCallback);
|
||||||
|
Firmata.attach(REPORT_ANALOG, reportAnalogCallback);
|
||||||
|
Firmata.attach(REPORT_DIGITAL, reportDigitalCallback);
|
||||||
|
Firmata.attach(SET_PIN_MODE, setPinModeCallback);
|
||||||
|
Firmata.attach(SET_DIGITAL_PIN_VALUE, setPinValueCallback);
|
||||||
|
Firmata.attach(START_SYSEX, sysexCallback);
|
||||||
|
Firmata.attach(SYSTEM_RESET, systemResetCallback);
|
||||||
|
|
||||||
|
// to use a port other than Serial, such as Serial1 on an Arduino Leonardo or Mega,
|
||||||
|
// Call begin(baud) on the alternate serial port and pass it to Firmata to begin like this:
|
||||||
|
// Serial1.begin(57600);
|
||||||
|
// Firmata.begin(Serial1);
|
||||||
|
// However do not do this if you are using SERIAL_MESSAGE
|
||||||
|
|
||||||
|
Firmata.begin(57600);
|
||||||
|
while (!Serial) {
|
||||||
|
; // wait for serial port to connect. Needed for ATmega32u4-based boards and Arduino 101
|
||||||
|
}
|
||||||
|
|
||||||
|
systemResetCallback(); // reset to default config
|
||||||
|
|
||||||
|
motor.init(); // Gestion des moteurs (porcou-arduino.ino)
|
||||||
|
}
|
||||||
|
|
||||||
|
/*==============================================================================
|
||||||
|
* LOOP()
|
||||||
|
*============================================================================*/
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
byte pin, analogPin;
|
||||||
|
|
||||||
|
/* DIGITALREAD - as fast as possible, check for changes and output them to the
|
||||||
|
* FTDI buffer using Serial.print() */
|
||||||
|
checkDigitalInputs();
|
||||||
|
|
||||||
|
/* STREAMREAD - processing incoming messagse as soon as possible, while still
|
||||||
|
* checking digital inputs. */
|
||||||
|
while (Firmata.available())
|
||||||
|
Firmata.processInput();
|
||||||
|
|
||||||
|
// TODO - ensure that Stream buffer doesn't go over 60 bytes
|
||||||
|
|
||||||
|
currentMillis = millis();
|
||||||
|
if (currentMillis - previousMillis > samplingInterval) {
|
||||||
|
previousMillis += samplingInterval;
|
||||||
|
/* ANALOGREAD - do all analogReads() at the configured sampling interval */
|
||||||
|
for (pin = 0; pin < TOTAL_PINS; pin++) {
|
||||||
|
if (IS_PIN_ANALOG(pin) && Firmata.getPinMode(pin) == PIN_MODE_ANALOG) {
|
||||||
|
analogPin = PIN_TO_ANALOG(pin);
|
||||||
|
if (analogInputsToReport & (1 << analogPin)) {
|
||||||
|
Firmata.sendAnalog(analogPin, analogRead(analogPin));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// report i2c data for all device with read continuous mode enabled
|
||||||
|
if (queryIndex > -1) {
|
||||||
|
for (byte i = 0; i < queryIndex + 1; i++) {
|
||||||
|
readAndReportData(query[i].addr, query[i].reg, query[i].bytes, query[i].stopTX);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Gestion des moteurs (ajout : porcou-arduino.ino)
|
||||||
|
|
||||||
|
/* if (digitalRead(2) == LOW && digitalRead(3) == LOW) { */
|
||||||
|
/* motor.dcMotorStop(MOTOR_CHA); */
|
||||||
|
/* Serial.println("motor.dcMotorStop(MOTOR_CHA);"); */
|
||||||
|
/* /\* motor.dcMotorBrake(MOTOR_CHA); *\/ */
|
||||||
|
/* } */
|
||||||
|
/* if (digitalRead(2) == HIGH && digitalRead(3) == HIGH) { */
|
||||||
|
/* motor.dcMotorStop(MOTOR_CHA); */
|
||||||
|
/* Serial.println("motor.dcMotorStop(MOTOR_CHA);"); */
|
||||||
|
/* } */
|
||||||
|
/* if (digitalRead(2) == HIGH && digitalRead(3) == LOW) { */
|
||||||
|
/* motor.dcMotorRun(MOTOR_CHA, 255); */
|
||||||
|
/* Serial.println("motor.dcMotorRun(MOTOR_CHA, 255);"); */
|
||||||
|
/* } */
|
||||||
|
/* if (digitalRead(2) == LOW && digitalRead(3) == HIGH) { */
|
||||||
|
/* motor.dcMotorRun(MOTOR_CHA, -255); */
|
||||||
|
/* Serial.println("motor.dcMotorRun(MOTOR_CHA, -255);"); */
|
||||||
|
/* } */
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef FIRMATA_SERIAL_FEATURE
|
||||||
|
serialFeature.update();
|
||||||
|
#endif
|
||||||
|
}
|
@ -0,0 +1,91 @@
|
|||||||
|
#include "Wire.h"
|
||||||
|
#include "Grove_Motor_Driver_TB6612FNG.h"
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
|
/******************************************************************************
|
||||||
|
* porcou-arduino.ino
|
||||||
|
* @title: Programme pour la carte Arduino
|
||||||
|
* @project: Blender-EduTech - Jumeau numérique - Portail coulissant
|
||||||
|
* @lang: fr
|
||||||
|
* @authors: Philippe Roy <philippe.roy@ac-grenoble.fr>
|
||||||
|
* @copyright: Copyright (C) 2024 Philippe Roy
|
||||||
|
* @license: GNU GPL
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
/******************************************************************************
|
||||||
|
* Précautions :
|
||||||
|
* - Régler l'alimentation à 12V DC - 3 A maxi
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
/******************************************************************************
|
||||||
|
* Communication serie
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
String serial_msg = ""; // Message
|
||||||
|
bool serial_msg_complet = false; // Flag de message complet
|
||||||
|
|
||||||
|
/******************************************************************************
|
||||||
|
* Initialisation
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
|
||||||
|
// Liaison série
|
||||||
|
Serial.begin(115200);
|
||||||
|
}
|
||||||
|
|
||||||
|
/******************************************************************************
|
||||||
|
* Boucle principale
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
|
||||||
|
/*****
|
||||||
|
* Lecture des capteur/boutons
|
||||||
|
*****/
|
||||||
|
|
||||||
|
/* accelgyro.getMotion9(&ax, &ay, &az, &gx, &gy, &gz, &mx, &my, &mz); */
|
||||||
|
/* Axyz[0] = (double) ax / 16384; */
|
||||||
|
/* Axyz[1] = (double) ay / 16384; */
|
||||||
|
/* Axyz[2] = (double) az / 16384; */
|
||||||
|
/* roll = asin(-Axyz[0]); */
|
||||||
|
/* roll_deg = roll*57.3; */
|
||||||
|
/* roll_txt = String(roll_deg); */
|
||||||
|
/* pitch = -asin(Axyz[1]/cos(roll)); // position capteur (X vers la gauche, Y vers l'arriere, Z vers le haut) */
|
||||||
|
/* pitch_deg = pitch*57.3; */
|
||||||
|
/* pitch_txt = String(pitch_deg); */
|
||||||
|
|
||||||
|
/*****
|
||||||
|
* Capteur / boutons : Arduino -> UPBGE
|
||||||
|
*****/
|
||||||
|
|
||||||
|
Serial.print(roll_txt);
|
||||||
|
Serial.print(",");
|
||||||
|
Serial.print(pitch_txt);
|
||||||
|
Serial.println();
|
||||||
|
|
||||||
|
/*****
|
||||||
|
* Moteur / Led : UPBGE -> Arduino
|
||||||
|
*****/
|
||||||
|
|
||||||
|
if (serial_msg_complet) {
|
||||||
|
int xy= serial_msg.toInt(); // Message par chiffre : XY
|
||||||
|
|
||||||
|
serial_msg = "";
|
||||||
|
serial_msg_complet = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/******************************************************************************
|
||||||
|
* Évènement provoqué par UPBGE (via la liaison série)
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
void serialEvent() {
|
||||||
|
while (Serial.available()) {
|
||||||
|
char inChar = (char)Serial.read();
|
||||||
|
serial_msg += inChar;
|
||||||
|
if (inChar == '\n') {
|
||||||
|
serial_msg_complet = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
@ -43,10 +43,10 @@ from porcou_lib import * # Bibliothèque utilisateur du portail coulissant
|
|||||||
# Brochage du portail coulissant (Grove)
|
# Brochage du portail coulissant (Grove)
|
||||||
brochage={
|
brochage={
|
||||||
'bp_ext' : ['d',6,'i'],'bp_int' : ['d',5,'i'],
|
'bp_ext' : ['d',6,'i'],'bp_int' : ['d',5,'i'],
|
||||||
'fdc_o' : ['d',3,'i'],'fdc_f' : ['d',2,'i'],
|
'fdc_o' : ['a',1,'i'],'fdc_f' : ['a',0,'i'],
|
||||||
'mot_o' : ['d',7,'o'],'mot_f' : ['d',8,'o'],
|
'mot_o' : ['d',2,'o'],'mot_f' : ['d',3,'o'],
|
||||||
'gyr' : ['d',4,'o']}
|
'gyr' : ['d',4,'o'],
|
||||||
# 'ir_emet' : ['d',8,'o'],'ir_recep' : ['d',7,'i']}
|
'ir_emet' : ['d',8,'o'],'ir_recep' : ['d',7,'i']}
|
||||||
|
|
||||||
###############################################################################
|
###############################################################################
|
||||||
# Fonctions
|
# Fonctions
|
||||||
|
Loading…
x
Reference in New Issue
Block a user