re,
merci
voici le début du programme 
/* Copyright (C) 2021 Sean D'Epagnier <seandepagnier@gmail.com>
/* ligne 118 à 121 activées pour moteur barre progressif à sésactiver // sinon
/* This Program is free software; you can redistribute it and/or
/* modify it under the terms of the GNU General Public
/* License as published by the Free Software Foundation; either
/* version 3 of the License, or (at your option) any later version.
This program is meant to interface with pwm based
motor controller either brushless or brushed, or a regular RC servo
You may need to modify the source code to support different hardware
adc pin0 is a resistor divider to measure voltage
allowing up to 20 volts (10k and 560 ohm, 1.1 volt reference)
adc pin1 goes to .01/.05 ohm shunt to measure current
adc pin2 goes to 100k resistor to 5v and 10k NTC thermistor to gnd ctrl temp
adc pin3 goes to 100k resistor to 5v and 10k NTC thermistor to gnd motor temp
adc pin4 rudder sense
unused analog pins should be grounded
digital pins 4 and 5 determine the current sense as folows:
pin 4 determines range
pin 5 determines high/low current (20A or 60A max)
D4 D5
1 1 .05 ohm, (or .001 ohm x 50 gain)
0 1 .01 ohm
1 0 .0005 ohm x 50 gain
0 0 .00025 ohm x 200 gain *ratiometric mode
digital pin6 determines:
1 - RC pwm:
digital pin9 pwm output standard ESC (1-2 ms pulse every 20 ms)
pin2 esc programming input/output (with arduinousblinker script)
0 - Hbridge
digital pin2 and pin3 for low side, pin9 and pin10 for high side
optional:digital pin7 forward fault for optional switch to stop forward travel
digital pin8 reverse fault for optional switch to stop reverse travel
Ratiometric Mode:
for D4=0 and D5=0, the adc operates over the 0-5 volt range
making it ratiometric (linearly accurate) for rudder feedback
and reduces impedance in the rudder measurement
the temperature resistors are changed to 10k and 10k ntc
voltage measurement accuracy is reduced, and the resistors used are
15k and 100k for a range of 38 volts. Pin 12 is not used in this mode.
Pin 11 drives mosfet (560ohm and 10k resistors) for clutch engage.
If Pin 12 has 560 ohm resistor to A0, then 24 volts is supported,
this allows for measuring voltage up to 40.4 volts
D12
1 0-20.75 volts (560 and 10k resistor) resolution 0.02 volts
0 0-40.4 volts (280 and 10k resistor) resolution 0.04 volts
digital pin13 is led on when engaged
The program uses a simple protocol to ensure only
corr96ncorrect or random data is very unlikely to
produce motor movement.
The input and output over uart has 4 byte packets
The first byte is the command or register, the next
two bytes is a 16bit value (signed or unsigned)
the last byte is a crc8 of the first 3 bytes
If incoming data has the correct crc for a few frames
the command can be recognized.
*/
/* vnh2sp30 is supported, but warning, I received 3 boards:
1) reverse is half power making chip very hot
2) reverse does not work
3) current sense does not work
3 out of 3 were defective, I do not recommend.
vnh2sp30 <-> arduino <-> CPC5001
+5V 5v
GND GND
EN D10
CS A1
INA D2
INB D3
PWM D9
If used with optical isolation (strongly recommended)
PWR+ VIN
5v vcc
tx rx
rx tx
gnd gnd
*/
#include <Arduino.h>
#include <stdint.h>
#include <stdarg.h>
#include <HardwareSerial.h>
//#include <Adafruit_BME280.h>
#include <avr/wdt.h>
#include <avr/sleep.h>
#include <avr/boot.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include "crc.h"
#define VNH2SP30 // defined if this board is used
//#define DISABLE_TEMP_SENSE // if no temp sensors avoid errors
//#define DISABLE_VOLTAGE_SENSE // if no voltage sense
//#define DISABLE_RUDDER_SENSE // if no rudder sense
//#Adafruit_BME280 bme;
// run at 4mhz instead of 16mhz to save power
// and somehow at slower clock atmega328 is able to measure lower current from the shunt
//#define DIV_CLOCK 2 // speed board runs at 1 for 16mhz, 2 for 8mhz, 4 for 4mhz (recommended 4 or 8mhz)
//#define BLINK // blink status led while detached to avoid quiecent consumption of on led (3mA)
static volatile uint8_t timer1_state;
// 1.5uS
#define dead_time4 \
asm volatile("nop"); \
asm volatile("nop"); \
asm volatile("nop"); \
asm volatile("nop"); \
asm volatile("nop"); \
asm volatile("nop");
#if DIV_CLOCK == 4
#define dead_time dead_time4
#elif DIV_CLOCK == 2
#define dead_time \
dead_time4 \
dead_time4
#elif DIV_CLOCK == 1
#define dead_time \
dead_time4 \
dead_time4 \
dead_time4 \
dead_time4
#warning "DIV_CLOCK set to 1, this will only work with 16mhz xtal"
#else
#error "invalid DIV_CLOCK"
#endif
// time to charge bootstrap capacitor twice dead time
#define charge_time \
dead_time; \
dead_time;
#define shunt_sense_pin 4 // use pin 4 to specify shunt resistance
uint8_t shunt_resistance = 1;
#define low_current_pin 5 // use pin 5 to specify low current (no amplifier)
uint8_t low_current = 1;
#define ratiometric_mode (!shunt_resistance && !low_current)
#define pwm_style_pin 6
// pwm style, 0 = hbridge, 1 = rc pwm, 2 = vnh2sp30
uint8_t pwm_style = 2; // detected to 0 or 1 unless detection disabled, default 2
#define port_fault_pin 7 // use pin 7 for optional fault
#define starboard_fault_pin 8 // use pin 8 for optional fault
// if switches pull this pin low, the motor is disengaged
// and will be noticed by the control program
#define pwm_output_pin 9
#define hbridge_a_bottom_pin 2
#define hbridge_b_bottom_pin 3
#define hbridge_a_top_pin 9
#define hbridge_b_top_pin 10
#define enable_pin 10 // for vnh2sp30
// for direct mosfet mode, define how to turn on/off mosfets
// do not use digitalWrite!
#define a_top_on PORTB |= _BV(PB1)
#define a_top_off PORTB &= ~_BV(PB1)
#define a_bottom_on PORTD |= _BV(PD2)
#define a_bottom_off PORTD &= ~_BV(PD2)
#define b_top_on PORTB |= _BV(PB2)
#define b_top_off PORTB &= ~_BV(PB2)
#define b_bottom_on PORTD |= _BV(PD3)
#define b_bottom_off PORTD &= ~_BV(PD3)
#define clutch_pin 11 // use pin 11 to engage clutch
#define clutch_sense_pwm_pin A5
//#define clutch_on PORTB |= _BV(PB3)
//#define clutch_off PORTB &= ~_BV(PB3)
uint8_t clutch_pwm = 192, clutch_start_time;
uint8_t use_brake = 0, brake_on = 0; // brake when stopped
#define USE_ADC_ISR 0 // set to 1 to use interrupt (recommend 0)
#define voltage_sense_pin 12
uint8_t voltage_sense = 1;
uint8_t voltage_mode = 0; // 0 = 12 volts, 1 = 24 volts
uint16_t max_voltage = 1600; // 16 volts max in 12 volt mode
#define led_pin 13 // led is on when engaged
void debug(const char *fmt, ...) {
char buf[128]; // resulting string limited to 128 chars
va_list args;
va_start(args, fmt);
vsnprintf(buf, 128, fmt, args);
va_end(args);
Serial.print(buf);
}
enum commands { COMMAND_CODE = 0xc7,
RESET_CODE = 0xe7,
MAX_CURRENT_CODE = 0x1e,
MAX_CONTROLLER_TEMP_CODE = 0xa4,
MAX_MOTOR_TEMP_CODE = 0x5a,
RUDDER_RANGE_CODE = 0xb6,
RUDDER_MIN_CODE = 0x2b,
RUDDER_MAX_CODE = 0x4d,
REPROGRAM_CODE = 0x19,
DISENGAGE_CODE = 0x68,
MAX_SLEW_CODE = 0x71,
EEPROM_READ_CODE = 0x91,
EEPROM_WRITE_CODE = 0x53,
CLUTCH_PWM_AND_BRAKE_CODE = 0x36 };
enum results { CURRENT_CODE = 0x1c,
VOLTAGE_CODE = 0xb3,
CONTROLLER_TEMP_CODE = 0xf9,
MOTOR_TEMP_CODE = 0x48,
RUDDER_SENSE_CODE = 0xa7,
FLAGS_CODE = 0x8f,
EEPROM_VALUE_CODE = 0x9a };
enum { SYNC = 1,
OVERTEMP_FAULT = 2,
OVERCURRENT_FAULT = 4,
ENGAGED = 8,
INVALID = 16,
PORT_PIN_FAULT = 32,
STARBOARD_PIN_FAULT = 64,
BADVOLTAGE_FAULT = 128,
MIN_RUDDER_FAULT = 256,
MAX_RUDDER_FAULT = 512,
CURRENT_RANGE = 1024,
BAD_FUSES = 2048,
/* PORT_FAULT=4096 STARBOARD_FAULT=8192 */ REBOOTED = 32768 };
uint16_t flags = REBOOTED, faults = 0;
uint8_t serialin;
// we need these to be atomic for 16 bytes
uint16_t eeprom_read_16(int address) {
// ensure atomic update of 16 bits with 3 banks
uint16_t v[3];
for (int i = 0; i < 3; i++) {
int addr = i * 256 + address;
v[i] = eeprom_read_word((uint16_t *)addr);
//eeprom_read_byte((unsigned char *)addr) | eeprom_read_byte((unsigned char *)addr+1)<<8;
}
if (v[1] == v[2])
return v[2];
return v[0];
}
void eeprom_update_16(int address, uint16_t value) {
// write in 3 locations
for (int i = 0; i < 3; i++) {
int addr = i * 256 + address;
eeprom_update_word((uint16_t *)addr, value);
}
}
uint8_t eeprom_read_8(int address, uint8_t &value) {
static uint8_t lastvalue, lastaddress = 255;
if (address & 1) { // odd
if (address == lastaddress + 1) {
value = lastvalue;
return 1;
} else
return 0;
}
// even
uint16_t v = eeprom_read_16(address);
value = v & 0xff;
lastvalue = v >> 8;
lastaddress = address;
return 1;
}
void eeprom_update_8(int address, uint8_t value) {
static uint8_t lastvalue, lastaddress = 255;
if (address & 1) { // odd
if (address == lastaddress + 1)
eeprom_update_16(lastaddress, lastvalue | value << 8);
} else {
lastvalue = value;
lastaddress = address;
}
}
uint16_t max_current = 2000; // 20 Amps
uint16_t max_controller_temp = 7000; // 70C
uint16_t max_motor_temp = 7000; // 70C
uint8_t max_slew_speed = 50, max_slew_slow = 75; // 200 is full power in 1/10th of a second
uint16_t rudder_min = 0, rudder_max = 65535;
uint8_t eeprom_read_addr = 0;
uint8_t eeprom_read_end = 0;
uint8_t adcref = _BV(REFS0) | _BV(REFS1); // 1.1v
volatile uint8_t calculated_clock = 0; // must be volatile to work correctly
uint8_t timeout;
uint16_t serial_data_timeout;
void setup() {
PCICR = 0;
PCMSK2 = 0;
cli(); // disable interrupts
CLKPR = _BV(CLKPCE);
CLKPR = _BV(CLKPS1); // divide clock by 4
/* Clear MCU Status Register. */
MCUSR = 0;
// set watchdog interrupt 16 ms to detect the clock speed (support 8mhz or 16mhz crystal)
wdt_reset();
WDTCSR = (1 << WDCE) | (1 << WDE);
WDTCSR = (1 << WDIE);
sei();
uint32_t start = micros();
while (!calculated_clock)
; // wait for watchdog to fire
uint16_t clock_time = micros() - start;
uint8_t div_board = 1; // 1 for 16mhz
if (clock_time < 2900) // 1800-2600 is 8mhz, 3800-4600 is 16mhz
div_board = 2; // detected 8mhz crystal, otherwise assume 16mhz
// after timing the clock frequency set the correct divider
uint8_t div_clock = DIV_CLOCK / div_board;
if (div_clock == 4) {
cli();
CLKPR = _BV(CLKPCE);
CLKPR = _BV(CLKPS1); // divide by 4
sei();
} else if (div_clock == 2) {
cli();
CLKPR = _BV(CLKPCE);
CLKPR = _BV(CLKPS0); // divide by 2
sei();
} else {
cli();
CLKPR = _BV(CLKPCE);
CLKPR = 0; // divide by 1
sei();
}
// Disable all interrupts
cli();
// set watchdog to interrupt in 1/4th second
WDTCSR = (1 << WDCE) | (1 << WDE);
WDTCSR = (1 << WDIE) | (1 << WDP2);
// read fuses, and report this as flag if they are wrong
uint8_t lowBits = boot_lock_fuse_bits_get(GET_LOW_FUSE_BITS);
uint8_t highBits = boot_lock_fuse_bits_get(GET_HIGH_FUSE_BITS);
uint8_t extendedBits = boot_lock_fuse_bits_get(GET_EXTENDED_FUSE_BITS);
// uint8_t lockBits = boot_lock_fuse_bits_get(GET_LOCK_BITS); // too many clones don't set lock bits and there is no spm
if ((lowBits != 0xFF && lowBits != 0x7F) || (highBits != 0xda && highBits != 0xde) || ((extendedBits & 0xF6) != 0xF4)
// || lockBits != 0xCF // too many clones don't set lock bits and there is no spm
)
flags |= BAD_FUSES;
sei(); // Enable all interrupts.
// enable pullup on unused pins (saves .5 mA)
pinMode(A4, INPUT);
digitalWrite(A4, LOW);
pinMode(shunt_sense_pin, INPUT_PULLUP);
pinMode(low_current_pin, INPUT_PULLUP);
pinMode(pwm_style_pin, INPUT_PULLUP);
pinMode(clutch_pin, INPUT_PULLUP);
pinMode(voltage_sense_pin, INPUT_PULLUP);
pinMode(clutch_sense_pwm_pin, INPUT_PULLUP);
serialin = 0;
// set up Serial library
Serial.begin(38400 * DIV_CLOCK);
digitalWrite(A0, LOW);
pinMode(A0, OUTPUT);
voltage_sense = digitalRead(voltage_sense_pin);
if (!voltage_sense)
pinMode(voltage_sense_pin, INPUT); // if attached, turn off pullup
pinMode(A0, INPUT);