Less use of "this"
This commit is contained in:
parent
661c3cfc99
commit
0b4aedf13e
@ -32,25 +32,25 @@
|
||||
int Servo::channel_next_free = 12;
|
||||
|
||||
Servo::Servo() {
|
||||
this->channel = channel_next_free++;
|
||||
channel = channel_next_free++;
|
||||
}
|
||||
|
||||
int8_t Servo::attach(const int pin) {
|
||||
if (this->channel >= CHANNEL_MAX_NUM) return -1;
|
||||
if (pin > 0) this->pin = pin;
|
||||
int8_t Servo::attach(const int inPin) {
|
||||
if (channel >= CHANNEL_MAX_NUM) return -1;
|
||||
if (pin > 0) pin = inPin;
|
||||
|
||||
ledcSetup(this->channel, 50, 16); // channel X, 50 Hz, 16-bit depth
|
||||
ledcAttachPin(this->pin, this->channel);
|
||||
ledcSetup(channel, 50, 16); // channel X, 50 Hz, 16-bit depth
|
||||
ledcAttachPin(pin, channel);
|
||||
return true;
|
||||
}
|
||||
|
||||
void Servo::detach() { ledcDetachPin(this->pin); }
|
||||
void Servo::detach() { ledcDetachPin(pin); }
|
||||
|
||||
int Servo::read() { return this->degrees; }
|
||||
int Servo::read() { return degrees; }
|
||||
|
||||
void Servo::write(int inDegrees) {
|
||||
this->degrees = constrain(inDegrees, MIN_ANGLE, MAX_ANGLE);
|
||||
int us = map(this->degrees, MIN_ANGLE, MAX_ANGLE, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
|
||||
degrees = constrain(inDegrees, MIN_ANGLE, MAX_ANGLE);
|
||||
int us = map(degrees, MIN_ANGLE, MAX_ANGLE, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
|
||||
int duty = map(us, 0, TAU_USEC, 0, MAX_COMPARE);
|
||||
ledcWrite(channel, duty);
|
||||
}
|
||||
@ -58,11 +58,11 @@ void Servo::write(int inDegrees) {
|
||||
void Servo::move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) {
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->channel]);
|
||||
if (attach(0) >= 0) {
|
||||
write(value);
|
||||
safe_delay(servo_delay[channel]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
detach();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
@ -57,11 +57,11 @@ class libServo: public Servo {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
|
||||
if (this->attach(servo_info[this->servoIndex].Pin.nbr) >= 0) { // try to reattach
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->servoIndex]); // delay to allow servo to reach position
|
||||
if (attach(servo_info[servoIndex].Pin.nbr) >= 0) { // try to reattach
|
||||
write(value);
|
||||
safe_delay(servo_delay[servoIndex]); // delay to allow servo to reach position
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
detach();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -31,24 +31,24 @@
|
||||
uint8_t servoPin[MAX_SERVOS] = { 0 };
|
||||
|
||||
int8_t libServo::attach(const int pin) {
|
||||
if (this->servoIndex >= MAX_SERVOS) return -1;
|
||||
if (pin > 0) servoPin[this->servoIndex] = pin;
|
||||
return Servo::attach(servoPin[this->servoIndex]);
|
||||
if (servoIndex >= MAX_SERVOS) return -1;
|
||||
if (pin > 0) servoPin[servoIndex] = pin;
|
||||
return super::attach(servoPin[servoIndex]);
|
||||
}
|
||||
|
||||
int8_t libServo::attach(const int pin, const int min, const int max) {
|
||||
if (pin > 0) servoPin[this->servoIndex] = pin;
|
||||
return Servo::attach(servoPin[this->servoIndex], min, max);
|
||||
if (pin > 0) servoPin[servoIndex] = pin;
|
||||
return super::attach(servoPin[servoIndex], min, max);
|
||||
}
|
||||
|
||||
void libServo::move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) {
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->servoIndex]);
|
||||
if (attach(0) >= 0) {
|
||||
write(value);
|
||||
safe_delay(servo_delay[servoIndex]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
detach();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
@ -213,31 +213,31 @@ void SPIClass::setDataSize(uint32_t datasize) {
|
||||
}
|
||||
|
||||
void SPIClass::setDataMode(uint8_t dataMode) {
|
||||
/*
|
||||
Notes:
|
||||
As far as we know the AVR numbers for dataMode match the numbers required by the STM32.
|
||||
From the AVR doc http://www.atmel.com/images/doc2585.pdf section 2.4
|
||||
|
||||
SPI Mode CPOL CPHA Shift SCK-edge Capture SCK-edge
|
||||
0 0 0 Falling Rising
|
||||
1 0 1 Rising Falling
|
||||
2 1 0 Rising Falling
|
||||
3 1 1 Falling Rising
|
||||
|
||||
On the STM32 it appears to be
|
||||
|
||||
bit 1 - CPOL : Clock polarity
|
||||
(This bit should not be changed when communication is ongoing)
|
||||
0 : CLK to 0 when idle
|
||||
1 : CLK to 1 when idle
|
||||
|
||||
bit 0 - CPHA : Clock phase
|
||||
(This bit should not be changed when communication is ongoing)
|
||||
0 : The first clock transition is the first data capture edge
|
||||
1 : The second clock transition is the first data capture edge
|
||||
|
||||
If someone finds this is not the case or sees a logic error with this let me know ;-)
|
||||
*/
|
||||
/**
|
||||
* Notes:
|
||||
* As far as we know the AVR numbers for dataMode match the numbers required by the STM32.
|
||||
* From the AVR doc http://www.atmel.com/images/doc2585.pdf section 2.4
|
||||
*
|
||||
* SPI Mode CPOL CPHA Shift SCK-edge Capture SCK-edge
|
||||
* 0 0 0 Falling Rising
|
||||
* 1 0 1 Rising Falling
|
||||
* 2 1 0 Rising Falling
|
||||
* 3 1 1 Falling Rising
|
||||
*
|
||||
* On the STM32 it appears to be
|
||||
*
|
||||
* bit 1 - CPOL : Clock polarity
|
||||
* (This bit should not be changed when communication is ongoing)
|
||||
* 0 : CLK to 0 when idle
|
||||
* 1 : CLK to 1 when idle
|
||||
*
|
||||
* bit 0 - CPHA : Clock phase
|
||||
* (This bit should not be changed when communication is ongoing)
|
||||
* 0 : The first clock transition is the first data capture edge
|
||||
* 1 : The second clock transition is the first data capture edge
|
||||
*
|
||||
* If someone finds this is not the case or sees a logic error with this let me know ;-)
|
||||
*/
|
||||
_currentSetting->dataMode = dataMode;
|
||||
uint32_t cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_CPOL|SPI_CR1_CPHA);
|
||||
_currentSetting->spi_d->regs->CR1 = cr1 | (dataMode & (SPI_CR1_CPOL|SPI_CR1_CPHA));
|
||||
@ -593,7 +593,7 @@ void SPIClass::detachInterrupt() {
|
||||
// Should be disableInterrupt()
|
||||
}
|
||||
|
||||
/*
|
||||
/**
|
||||
* Pin accessors
|
||||
*/
|
||||
|
||||
@ -613,25 +613,14 @@ uint8_t SPIClass::nssPin() {
|
||||
return dev_to_spi_pins(_currentSetting->spi_d)->nss;
|
||||
}
|
||||
|
||||
/*
|
||||
/**
|
||||
* Deprecated functions
|
||||
*/
|
||||
uint8_t SPIClass::send(uint8_t data) { write(data); return 1; }
|
||||
uint8_t SPIClass::send(uint8_t *buf, uint32_t len) { write(buf, len); return len; }
|
||||
uint8_t SPIClass::recv() { return read(); }
|
||||
|
||||
uint8_t SPIClass::send(uint8_t data) {
|
||||
this->write(data);
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint8_t SPIClass::send(uint8_t *buf, uint32_t len) {
|
||||
this->write(buf, len);
|
||||
return len;
|
||||
}
|
||||
|
||||
uint8_t SPIClass::recv() {
|
||||
return this->read();
|
||||
}
|
||||
|
||||
/*
|
||||
/**
|
||||
* DMA call back functions, one per port.
|
||||
*/
|
||||
#if BOARD_NR_SPI >= 1
|
||||
@ -650,7 +639,7 @@ uint8_t SPIClass::recv() {
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
/**
|
||||
* Auxiliary functions
|
||||
*/
|
||||
static const spi_pins* dev_to_spi_pins(spi_dev *dev) {
|
||||
|
@ -96,36 +96,36 @@ typedef enum {
|
||||
|
||||
class SPISettings {
|
||||
public:
|
||||
SPISettings(uint32_t clock, BitOrder bitOrder, uint8_t dataMode) {
|
||||
if (__builtin_constant_p(clock))
|
||||
init_AlwaysInline(clock, bitOrder, dataMode, DATA_SIZE_8BIT);
|
||||
SPISettings(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode) {
|
||||
if (__builtin_constant_p(inClock))
|
||||
init_AlwaysInline(inClock, inBitOrder, inDataMode, DATA_SIZE_8BIT);
|
||||
else
|
||||
init_MightInline(clock, bitOrder, dataMode, DATA_SIZE_8BIT);
|
||||
init_MightInline(inClock, inBitOrder, inDataMode, DATA_SIZE_8BIT);
|
||||
}
|
||||
SPISettings(uint32_t clock, BitOrder bitOrder, uint8_t dataMode, uint32_t dataSize) {
|
||||
if (__builtin_constant_p(clock))
|
||||
init_AlwaysInline(clock, bitOrder, dataMode, dataSize);
|
||||
SPISettings(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode, uint32_t inDataSize) {
|
||||
if (__builtin_constant_p(inClock))
|
||||
init_AlwaysInline(inClock, inBitOrder, inDataMode, inDataSize);
|
||||
else
|
||||
init_MightInline(clock, bitOrder, dataMode, dataSize);
|
||||
init_MightInline(inClock, inBitOrder, inDataMode, inDataSize);
|
||||
}
|
||||
SPISettings(uint32_t clock) {
|
||||
if (__builtin_constant_p(clock))
|
||||
init_AlwaysInline(clock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
|
||||
SPISettings(uint32_t inClock) {
|
||||
if (__builtin_constant_p(inClock))
|
||||
init_AlwaysInline(inClock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
|
||||
else
|
||||
init_MightInline(clock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
|
||||
init_MightInline(inClock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
|
||||
}
|
||||
SPISettings() {
|
||||
init_AlwaysInline(4000000, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
|
||||
}
|
||||
private:
|
||||
void init_MightInline(uint32_t clock, BitOrder bitOrder, uint8_t dataMode, uint32_t dataSize) {
|
||||
init_AlwaysInline(clock, bitOrder, dataMode, dataSize);
|
||||
void init_MightInline(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode, uint32_t inDataSize) {
|
||||
init_AlwaysInline(inClock, inBitOrder, inDataMode, inDataSize);
|
||||
}
|
||||
void init_AlwaysInline(uint32_t clock, BitOrder bitOrder, uint8_t dataMode, uint32_t dataSize) __attribute__((__always_inline__)) {
|
||||
this->clock = clock;
|
||||
this->bitOrder = bitOrder;
|
||||
this->dataMode = dataMode;
|
||||
this->dataSize = dataSize;
|
||||
void init_AlwaysInline(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode, uint32_t inDataSize) __attribute__((__always_inline__)) {
|
||||
clock = inClock;
|
||||
bitOrder = inBitOrder;
|
||||
dataMode = inDataMode;
|
||||
dataSize = inDataSize;
|
||||
}
|
||||
uint32_t clock;
|
||||
uint32_t dataSize;
|
||||
@ -339,7 +339,7 @@ public:
|
||||
* or 1-3 in high density devices.
|
||||
*/
|
||||
void setModule(int spi_num) {
|
||||
_currentSetting=&_settings[spi_num-1];// SPI channels are called 1 2 and 3 but the array is zero indexed
|
||||
_currentSetting = &_settings[spi_num - 1];// SPI channels are called 1 2 and 3 but the array is zero indexed
|
||||
}
|
||||
|
||||
/* -- The following methods are deprecated --------------------------- */
|
||||
|
@ -56,52 +56,50 @@ uint8_t ServoCount = 0;
|
||||
#define SERVO_OVERFLOW ((uint16_t)round((double)TAU_CYC / SERVO_PRESCALER))
|
||||
|
||||
// Unit conversions
|
||||
#define US_TO_COMPARE(us) ((uint16_t)map((us), 0, TAU_USEC, 0, SERVO_OVERFLOW))
|
||||
#define COMPARE_TO_US(c) ((uint32_t)map((c), 0, SERVO_OVERFLOW, 0, TAU_USEC))
|
||||
#define ANGLE_TO_US(a) ((uint16_t)(map((a), this->minAngle, this->maxAngle, \
|
||||
SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW)))
|
||||
#define US_TO_ANGLE(us) ((int16_t)(map((us), SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW, \
|
||||
this->minAngle, this->maxAngle)))
|
||||
#define US_TO_COMPARE(us) uint16_t(map((us), 0, TAU_USEC, 0, SERVO_OVERFLOW))
|
||||
#define COMPARE_TO_US(c) uint32_t(map((c), 0, SERVO_OVERFLOW, 0, TAU_USEC))
|
||||
#define ANGLE_TO_US(a) uint16_t(map((a), minAngle, maxAngle, SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW))
|
||||
#define US_TO_ANGLE(us) int16_t(map((us), SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW, minAngle, maxAngle))
|
||||
|
||||
void libServo::servoWrite(uint8_t pin, uint16_t duty_cycle) {
|
||||
void libServo::servoWrite(uint8_t inPin, uint16_t duty_cycle) {
|
||||
#ifdef SERVO0_TIMER_NUM
|
||||
if (this->servoIndex == 0) {
|
||||
this->pwmSetDuty(duty_cycle);
|
||||
if (servoIndex == 0) {
|
||||
pwmSetDuty(duty_cycle);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
timer_dev *tdev = PIN_MAP[pin].timer_device;
|
||||
uint8_t tchan = PIN_MAP[pin].timer_channel;
|
||||
timer_dev *tdev = PIN_MAP[inPin].timer_device;
|
||||
uint8_t tchan = PIN_MAP[inPin].timer_channel;
|
||||
if (tdev) timer_set_compare(tdev, tchan, duty_cycle);
|
||||
}
|
||||
|
||||
libServo::libServo() {
|
||||
this->servoIndex = ServoCount < MAX_SERVOS ? ServoCount++ : INVALID_SERVO;
|
||||
servoIndex = ServoCount < MAX_SERVOS ? ServoCount++ : INVALID_SERVO;
|
||||
}
|
||||
|
||||
bool libServo::attach(const int32_t pin, const int32_t minAngle, const int32_t maxAngle) {
|
||||
if (this->servoIndex >= MAX_SERVOS) return false;
|
||||
if (pin >= BOARD_NR_GPIO_PINS) return false;
|
||||
bool libServo::attach(const int32_t inPin, const int32_t inMinAngle, const int32_t inMaxAngle) {
|
||||
if (servoIndex >= MAX_SERVOS) return false;
|
||||
if (inPin >= BOARD_NR_GPIO_PINS) return false;
|
||||
|
||||
this->minAngle = minAngle;
|
||||
this->maxAngle = maxAngle;
|
||||
this->angle = -1;
|
||||
minAngle = inMinAngle;
|
||||
maxAngle = inMaxAngle;
|
||||
angle = -1;
|
||||
|
||||
#ifdef SERVO0_TIMER_NUM
|
||||
if (this->servoIndex == 0 && this->setupSoftPWM(pin)) {
|
||||
this->pin = pin; // set attached()
|
||||
if (servoIndex == 0 && setupSoftPWM(inPin)) {
|
||||
pin = inPin; // set attached()
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!PWM_PIN(pin)) return false;
|
||||
if (!PWM_PIN(inPin)) return false;
|
||||
|
||||
timer_dev *tdev = PIN_MAP[pin].timer_device;
|
||||
//uint8_t tchan = PIN_MAP[pin].timer_channel;
|
||||
timer_dev *tdev = PIN_MAP[inPin].timer_device;
|
||||
//uint8_t tchan = PIN_MAP[inPin].timer_channel;
|
||||
|
||||
SET_PWM(pin);
|
||||
servoWrite(pin, 0);
|
||||
SET_PWM(inPin);
|
||||
servoWrite(inPin, 0);
|
||||
|
||||
timer_pause(tdev);
|
||||
timer_set_prescaler(tdev, SERVO_PRESCALER - 1); // prescaler is 1-based
|
||||
@ -109,25 +107,24 @@ bool libServo::attach(const int32_t pin, const int32_t minAngle, const int32_t m
|
||||
timer_generate_update(tdev);
|
||||
timer_resume(tdev);
|
||||
|
||||
this->pin = pin; // set attached()
|
||||
|
||||
pin = inPin; // set attached()
|
||||
return true;
|
||||
}
|
||||
|
||||
bool libServo::detach() {
|
||||
if (!this->attached()) return false;
|
||||
this->angle = -1;
|
||||
servoWrite(this->pin, 0);
|
||||
if (!attached()) return false;
|
||||
angle = -1;
|
||||
servoWrite(pin, 0);
|
||||
return true;
|
||||
}
|
||||
|
||||
int32_t libServo::read() const {
|
||||
if (this->attached()) {
|
||||
if (attached()) {
|
||||
#ifdef SERVO0_TIMER_NUM
|
||||
if (this->servoIndex == 0) return this->angle;
|
||||
if (servoIndex == 0) return angle;
|
||||
#endif
|
||||
timer_dev *tdev = PIN_MAP[this->pin].timer_device;
|
||||
uint8_t tchan = PIN_MAP[this->pin].timer_channel;
|
||||
timer_dev *tdev = PIN_MAP[pin].timer_device;
|
||||
uint8_t tchan = PIN_MAP[pin].timer_channel;
|
||||
return US_TO_ANGLE(COMPARE_TO_US(timer_get_compare(tdev, tchan)));
|
||||
}
|
||||
return 0;
|
||||
@ -137,12 +134,12 @@ void libServo::move(const int32_t value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
|
||||
if (this->attached()) {
|
||||
this->angle = constrain(value, this->minAngle, this->maxAngle);
|
||||
servoWrite(this->pin, US_TO_COMPARE(ANGLE_TO_US(this->angle)));
|
||||
safe_delay(servo_delay[this->servoIndex]);
|
||||
if (attached()) {
|
||||
angle = constrain(value, minAngle, maxAngle);
|
||||
servoWrite(pin, US_TO_COMPARE(ANGLE_TO_US(angle)));
|
||||
safe_delay(servo_delay[servoIndex]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
detach();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
@ -169,13 +166,13 @@ void libServo::move(const int32_t value) {
|
||||
}
|
||||
}
|
||||
|
||||
bool libServo::setupSoftPWM(const int32_t pin) {
|
||||
bool libServo::setupSoftPWM(const int32_t inPin) {
|
||||
timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM);
|
||||
if (!tdev) return false;
|
||||
#ifdef SERVO0_PWM_OD
|
||||
OUT_WRITE_OD(pin, 1);
|
||||
OUT_WRITE_OD(inPin, 1);
|
||||
#else
|
||||
OUT_WRITE(pin, 0);
|
||||
OUT_WRITE(inPin, 0);
|
||||
#endif
|
||||
|
||||
timer_pause(tdev);
|
||||
@ -206,9 +203,9 @@ void libServo::move(const int32_t value) {
|
||||
timer_disable_irq(tdev, 1);
|
||||
timer_disable_irq(tdev, 2);
|
||||
#ifdef SERVO0_PWM_OD
|
||||
OUT_WRITE_OD(this->pin, 1); // off
|
||||
OUT_WRITE_OD(pin, 1); // off
|
||||
#else
|
||||
OUT_WRITE(this->pin, 0);
|
||||
OUT_WRITE(pin, 0);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
@ -221,7 +218,7 @@ void libServo::move(const int32_t value) {
|
||||
|
||||
#else
|
||||
|
||||
bool libServo::setupSoftPWM(const int32_t pin) { return false; }
|
||||
bool libServo::setupSoftPWM(const int32_t inPin) { return false; }
|
||||
void libServo::pwmSetDuty(const uint16_t duty_cycle) {}
|
||||
void libServo::pauseSoftPWM() {}
|
||||
|
||||
|
@ -41,7 +41,7 @@ class libServo {
|
||||
public:
|
||||
libServo();
|
||||
bool attach(const int32_t pin, const int32_t minAngle=SERVO_DEFAULT_MIN_ANGLE, const int32_t maxAngle=SERVO_DEFAULT_MAX_ANGLE);
|
||||
bool attached() const { return this->pin != NOT_ATTACHED; }
|
||||
bool attached() const { return pin != NOT_ATTACHED; }
|
||||
bool detach();
|
||||
void move(const int32_t value);
|
||||
int32_t read() const;
|
||||
|
@ -30,22 +30,22 @@
|
||||
#include "Servo.h"
|
||||
|
||||
int8_t libServo::attach(const int pin) {
|
||||
if (this->servoIndex >= MAX_SERVOS) return -1;
|
||||
return Servo::attach(pin);
|
||||
if (servoIndex >= MAX_SERVOS) return -1;
|
||||
return super::attach(pin);
|
||||
}
|
||||
|
||||
int8_t libServo::attach(const int pin, const int min, const int max) {
|
||||
return Servo::attach(pin, min, max);
|
||||
return super::attach(pin, min, max);
|
||||
}
|
||||
|
||||
void libServo::move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) {
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->servoIndex]);
|
||||
if (attach(0) >= 0) {
|
||||
write(value);
|
||||
safe_delay(servo_delay[servoIndex]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
detach();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
@ -29,25 +29,25 @@
|
||||
|
||||
uint8_t servoPin[MAX_SERVOS] = { 0 };
|
||||
|
||||
int8_t libServo::attach(const int pin) {
|
||||
if (this->servoIndex >= MAX_SERVOS) return -1;
|
||||
if (pin > 0) servoPin[this->servoIndex] = pin;
|
||||
return Servo::attach(servoPin[this->servoIndex]);
|
||||
int8_t libServo::attach(const int inPin) {
|
||||
if (servoIndex >= MAX_SERVOS) return -1;
|
||||
if (inPin > 0) servoPin[servoIndex] = inPin;
|
||||
return super::attach(servoPin[servoIndex]);
|
||||
}
|
||||
|
||||
int8_t libServo::attach(const int pin, const int min, const int max) {
|
||||
if (pin > 0) servoPin[this->servoIndex] = pin;
|
||||
return Servo::attach(servoPin[this->servoIndex], min, max);
|
||||
int8_t libServo::attach(const int inPin, const int inMin, const int inMax) {
|
||||
if (inPin > 0) servoPin[servoIndex] = inPin;
|
||||
return super::attach(servoPin[servoIndex], inMin, inMax);
|
||||
}
|
||||
|
||||
void libServo::move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) {
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->servoIndex]);
|
||||
if (attach(0) >= 0) {
|
||||
write(value);
|
||||
safe_delay(servo_delay[servoIndex]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
detach();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
@ -1,3 +1,24 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
@ -8,25 +29,25 @@
|
||||
|
||||
uint8_t servoPin[MAX_SERVOS] = { 0 };
|
||||
|
||||
int8_t libServo::attach(const int pin) {
|
||||
if (this->servoIndex >= MAX_SERVOS) return -1;
|
||||
if (pin > 0) servoPin[this->servoIndex] = pin;
|
||||
return Servo::attach(servoPin[this->servoIndex]);
|
||||
int8_t libServo::attach(const int inPin) {
|
||||
if (servoIndex >= MAX_SERVOS) return -1;
|
||||
if (inPin > 0) servoPin[servoIndex] = inPin;
|
||||
return super::attach(servoPin[servoIndex]);
|
||||
}
|
||||
|
||||
int8_t libServo::attach(const int pin, const int min, const int max) {
|
||||
if (pin > 0) servoPin[this->servoIndex] = pin;
|
||||
return Servo::attach(servoPin[this->servoIndex], min, max);
|
||||
int8_t libServo::attach(const int inPin, const int inMin, const int inMax) {
|
||||
if (inPin > 0) servoPin[servoIndex] = inPin;
|
||||
return super::attach(servoPin[servoIndex], inMin, inMax);
|
||||
}
|
||||
|
||||
void libServo::move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) {
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->servoIndex]);
|
||||
if (attach(0) >= 0) {
|
||||
write(value);
|
||||
safe_delay(servo_delay[servoIndex]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
detach();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
@ -58,11 +58,11 @@
|
||||
#include "servo.h"
|
||||
#include "servo_private.h"
|
||||
|
||||
ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures
|
||||
uint8_t ServoCount = 0; // the total number of attached servos
|
||||
ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures
|
||||
uint8_t ServoCount = 0; // the total number of attached servos
|
||||
|
||||
#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo
|
||||
#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
|
||||
#define SERVO_MIN(v) (MIN_PULSE_WIDTH - (v) * 4) // minimum value in uS for this servo
|
||||
#define SERVO_MAX(v) (MAX_PULSE_WIDTH - (v) * 4) // maximum value in uS for this servo
|
||||
|
||||
/************ static functions common to all instances ***********************/
|
||||
|
||||
@ -79,54 +79,54 @@ static boolean isTimerActive(timer16_Sequence_t timer) {
|
||||
|
||||
Servo::Servo() {
|
||||
if (ServoCount < MAX_SERVOS) {
|
||||
this->servoIndex = ServoCount++; // assign a servo index to this instance
|
||||
servo_info[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
|
||||
servoIndex = ServoCount++; // assign a servo index to this instance
|
||||
servo_info[servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
|
||||
}
|
||||
else
|
||||
this->servoIndex = INVALID_SERVO; // too many servos
|
||||
servoIndex = INVALID_SERVO; // too many servos
|
||||
}
|
||||
|
||||
int8_t Servo::attach(const int pin) {
|
||||
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
|
||||
int8_t Servo::attach(const int inPin) {
|
||||
return attach(inPin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
|
||||
}
|
||||
|
||||
int8_t Servo::attach(const int pin, const int min, const int max) {
|
||||
int8_t Servo::attach(const int inPin, const int inMin, const int inMax) {
|
||||
|
||||
if (this->servoIndex >= MAX_SERVOS) return -1;
|
||||
if (servoIndex >= MAX_SERVOS) return -1;
|
||||
|
||||
if (pin > 0) servo_info[this->servoIndex].Pin.nbr = pin;
|
||||
pinMode(servo_info[this->servoIndex].Pin.nbr, OUTPUT); // set servo pin to output
|
||||
if (inPin > 0) servo_info[servoIndex].Pin.nbr = inPin;
|
||||
pinMode(servo_info[servoIndex].Pin.nbr, OUTPUT); // set servo pin to output
|
||||
|
||||
// todo min/max check: ABS(min - MIN_PULSE_WIDTH) /4 < 128
|
||||
this->min = (MIN_PULSE_WIDTH - min) / 4; //resolution of min/max is 4 uS
|
||||
this->max = (MAX_PULSE_WIDTH - max) / 4;
|
||||
// TODO: min/max check: ABS(min - MIN_PULSE_WIDTH) / 4 < 128
|
||||
min = (MIN_PULSE_WIDTH - inMin) / 4; //resolution of min/max is 4 uS
|
||||
max = (MAX_PULSE_WIDTH - inMax) / 4;
|
||||
|
||||
// initialize the timer if it has not already been initialized
|
||||
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
|
||||
if (!isTimerActive(timer)) initISR(timer);
|
||||
servo_info[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
|
||||
servo_info[servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
|
||||
|
||||
return this->servoIndex;
|
||||
return servoIndex;
|
||||
}
|
||||
|
||||
void Servo::detach() {
|
||||
servo_info[this->servoIndex].Pin.isActive = false;
|
||||
servo_info[servoIndex].Pin.isActive = false;
|
||||
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
|
||||
if (!isTimerActive(timer)) finISR(timer);
|
||||
}
|
||||
|
||||
void Servo::write(int value) {
|
||||
if (value < MIN_PULSE_WIDTH) // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
|
||||
value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(), SERVO_MAX());
|
||||
this->writeMicroseconds(value);
|
||||
value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(min), SERVO_MAX(max));
|
||||
writeMicroseconds(value);
|
||||
}
|
||||
|
||||
void Servo::writeMicroseconds(int value) {
|
||||
// calculate and store the values for the given channel
|
||||
byte channel = this->servoIndex;
|
||||
byte channel = servoIndex;
|
||||
if (channel < MAX_SERVOS) { // ensure channel is valid
|
||||
// ensure pulse width is valid
|
||||
value = constrain(value, SERVO_MIN(), SERVO_MAX()) - (TRIM_DURATION);
|
||||
value = constrain(value, SERVO_MIN(min), SERVO_MAX(max)) - (TRIM_DURATION);
|
||||
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
|
||||
|
||||
CRITICAL_SECTION_START;
|
||||
@ -136,22 +136,22 @@ void Servo::writeMicroseconds(int value) {
|
||||
}
|
||||
|
||||
// return the value as degrees
|
||||
int Servo::read() { return map(this->readMicroseconds() + 1, SERVO_MIN(), SERVO_MAX(), 0, 180); }
|
||||
int Servo::read() { return map(readMicroseconds() + 1, SERVO_MIN(min), SERVO_MAX(max), 0, 180); }
|
||||
|
||||
int Servo::readMicroseconds() {
|
||||
return (this->servoIndex == INVALID_SERVO) ? 0 : ticksToUs(servo_info[this->servoIndex].ticks) + (TRIM_DURATION);
|
||||
return (servoIndex == INVALID_SERVO) ? 0 : ticksToUs(servo_info[servoIndex].ticks) + (TRIM_DURATION);
|
||||
}
|
||||
|
||||
bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; }
|
||||
bool Servo::attached() { return servo_info[servoIndex].Pin.isActive; }
|
||||
|
||||
void Servo::move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) {
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->servoIndex]);
|
||||
if (attach(0) >= 0) {
|
||||
write(value);
|
||||
safe_delay(servo_delay[servoIndex]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
detach();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
@ -34,12 +34,12 @@ TWIBus::TWIBus() {
|
||||
#else
|
||||
Wire.begin(I2C_SLAVE_ADDRESS); // Join the bus as a slave
|
||||
#endif
|
||||
this->reset();
|
||||
reset();
|
||||
}
|
||||
|
||||
void TWIBus::reset() {
|
||||
this->buffer_s = 0;
|
||||
this->buffer[0] = 0x00;
|
||||
buffer_s = 0;
|
||||
buffer[0] = 0x00;
|
||||
}
|
||||
|
||||
void TWIBus::address(const uint8_t adr) {
|
||||
@ -47,7 +47,7 @@ void TWIBus::address(const uint8_t adr) {
|
||||
SERIAL_ECHO_MSG("Bad I2C address (8-127)");
|
||||
}
|
||||
|
||||
this->addr = adr;
|
||||
addr = adr;
|
||||
|
||||
#if ENABLED(DEBUG_TWIBUS)
|
||||
debug(PSTR("address"), adr);
|
||||
@ -55,8 +55,8 @@ void TWIBus::address(const uint8_t adr) {
|
||||
}
|
||||
|
||||
void TWIBus::addbyte(const char c) {
|
||||
if (this->buffer_s >= COUNT(this->buffer)) return;
|
||||
this->buffer[this->buffer_s++] = c;
|
||||
if (buffer_s >= COUNT(buffer)) return;
|
||||
buffer[buffer_s++] = c;
|
||||
#if ENABLED(DEBUG_TWIBUS)
|
||||
debug(PSTR("addbyte"), c);
|
||||
#endif
|
||||
@ -66,26 +66,26 @@ void TWIBus::addbytes(char src[], uint8_t bytes) {
|
||||
#if ENABLED(DEBUG_TWIBUS)
|
||||
debug(PSTR("addbytes"), bytes);
|
||||
#endif
|
||||
while (bytes--) this->addbyte(*src++);
|
||||
while (bytes--) addbyte(*src++);
|
||||
}
|
||||
|
||||
void TWIBus::addstring(char str[]) {
|
||||
#if ENABLED(DEBUG_TWIBUS)
|
||||
debug(PSTR("addstring"), str);
|
||||
#endif
|
||||
while (char c = *str++) this->addbyte(c);
|
||||
while (char c = *str++) addbyte(c);
|
||||
}
|
||||
|
||||
void TWIBus::send() {
|
||||
#if ENABLED(DEBUG_TWIBUS)
|
||||
debug(PSTR("send"), this->addr);
|
||||
debug(PSTR("send"), addr);
|
||||
#endif
|
||||
|
||||
Wire.beginTransmission(I2C_ADDRESS(this->addr));
|
||||
Wire.write(this->buffer, this->buffer_s);
|
||||
Wire.beginTransmission(I2C_ADDRESS(addr));
|
||||
Wire.write(buffer, buffer_s);
|
||||
Wire.endTransmission();
|
||||
|
||||
this->reset();
|
||||
reset();
|
||||
}
|
||||
|
||||
// static
|
||||
@ -103,22 +103,22 @@ void TWIBus::echodata(uint8_t bytes, const char prefix[], uint8_t adr) {
|
||||
}
|
||||
|
||||
void TWIBus::echobuffer(const char prefix[], uint8_t adr) {
|
||||
echoprefix(this->buffer_s, prefix, adr);
|
||||
for (uint8_t i = 0; i < this->buffer_s; i++) SERIAL_CHAR(this->buffer[i]);
|
||||
echoprefix(buffer_s, prefix, adr);
|
||||
for (uint8_t i = 0; i < buffer_s; i++) SERIAL_CHAR(buffer[i]);
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
bool TWIBus::request(const uint8_t bytes) {
|
||||
if (!this->addr) return false;
|
||||
if (!addr) return false;
|
||||
|
||||
#if ENABLED(DEBUG_TWIBUS)
|
||||
debug(PSTR("request"), bytes);
|
||||
#endif
|
||||
|
||||
// requestFrom() is a blocking function
|
||||
if (Wire.requestFrom(this->addr, bytes) == 0) {
|
||||
if (Wire.requestFrom(addr, bytes) == 0) {
|
||||
#if ENABLED(DEBUG_TWIBUS)
|
||||
debug("request fail", this->addr);
|
||||
debug("request fail", addr);
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
@ -131,12 +131,12 @@ void TWIBus::relay(const uint8_t bytes) {
|
||||
debug(PSTR("relay"), bytes);
|
||||
#endif
|
||||
|
||||
if (this->request(bytes))
|
||||
echodata(bytes, PSTR("i2c-reply"), this->addr);
|
||||
if (request(bytes))
|
||||
echodata(bytes, PSTR("i2c-reply"), addr);
|
||||
}
|
||||
|
||||
uint8_t TWIBus::capture(char *dst, const uint8_t bytes) {
|
||||
this->reset();
|
||||
reset();
|
||||
uint8_t count = 0;
|
||||
while (count < bytes && Wire.available())
|
||||
dst[count++] = Wire.read();
|
||||
@ -168,13 +168,13 @@ void TWIBus::flush() {
|
||||
#endif
|
||||
|
||||
if (str) {
|
||||
this->reset();
|
||||
this->addstring(str);
|
||||
reset();
|
||||
addstring(str);
|
||||
}
|
||||
|
||||
Wire.write(this->buffer, this->buffer_s);
|
||||
Wire.write(buffer, buffer_s);
|
||||
|
||||
this->reset();
|
||||
reset();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -218,7 +218,7 @@ class TWIBus {
|
||||
* If a string is passed, write it into the buffer first.
|
||||
*/
|
||||
void reply(char str[]=nullptr);
|
||||
inline void reply(const char str[]) { this->reply((char*)str); }
|
||||
inline void reply(const char str[]) { reply((char*)str); }
|
||||
|
||||
#endif
|
||||
|
||||
|
@ -52,8 +52,8 @@ class CircularQueue {
|
||||
* items that can be stored on the queue.
|
||||
*/
|
||||
CircularQueue<T, N>() {
|
||||
this->buffer.size = N;
|
||||
this->buffer.count = this->buffer.head = this->buffer.tail = 0;
|
||||
buffer.size = N;
|
||||
buffer.count = buffer.head = buffer.tail = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -63,15 +63,15 @@ class CircularQueue {
|
||||
* @return type T item
|
||||
*/
|
||||
T dequeue() {
|
||||
if (this->isEmpty()) return T();
|
||||
if (isEmpty()) return T();
|
||||
|
||||
uint8_t index = this->buffer.head;
|
||||
uint8_t index = buffer.head;
|
||||
|
||||
--this->buffer.count;
|
||||
if (++this->buffer.head == this->buffer.size)
|
||||
this->buffer.head = 0;
|
||||
--buffer.count;
|
||||
if (++buffer.head == buffer.size)
|
||||
buffer.head = 0;
|
||||
|
||||
return this->buffer.queue[index];
|
||||
return buffer.queue[index];
|
||||
}
|
||||
|
||||
/**
|
||||
@ -82,13 +82,13 @@ class CircularQueue {
|
||||
* @return true if the operation was successful
|
||||
*/
|
||||
bool enqueue(T const &item) {
|
||||
if (this->isFull()) return false;
|
||||
if (isFull()) return false;
|
||||
|
||||
this->buffer.queue[this->buffer.tail] = item;
|
||||
buffer.queue[buffer.tail] = item;
|
||||
|
||||
++this->buffer.count;
|
||||
if (++this->buffer.tail == this->buffer.size)
|
||||
this->buffer.tail = 0;
|
||||
++buffer.count;
|
||||
if (++buffer.tail == buffer.size)
|
||||
buffer.tail = 0;
|
||||
|
||||
return true;
|
||||
}
|
||||
@ -98,27 +98,21 @@ class CircularQueue {
|
||||
* @details Returns true if there are no items on the queue, false otherwise.
|
||||
* @return true if queue is empty
|
||||
*/
|
||||
bool isEmpty() {
|
||||
return this->buffer.count == 0;
|
||||
}
|
||||
bool isEmpty() { return buffer.count == 0; }
|
||||
|
||||
/**
|
||||
* @brief Checks if the queue is full
|
||||
* @details Returns true if the queue is full, false otherwise.
|
||||
* @return true if queue is full
|
||||
*/
|
||||
bool isFull() {
|
||||
return this->buffer.count == this->buffer.size;
|
||||
}
|
||||
bool isFull() { return buffer.count == buffer.size; }
|
||||
|
||||
/**
|
||||
* @brief Gets the queue size
|
||||
* @details Returns the maximum number of items a queue can have.
|
||||
* @return the queue size
|
||||
*/
|
||||
uint8_t size() {
|
||||
return this->buffer.size;
|
||||
}
|
||||
uint8_t size() { return buffer.size; }
|
||||
|
||||
/**
|
||||
* @brief Gets the next item from the queue without removing it
|
||||
@ -126,16 +120,12 @@ class CircularQueue {
|
||||
* or updating the pointers.
|
||||
* @return first item in the queue
|
||||
*/
|
||||
T peek() {
|
||||
return this->buffer.queue[this->buffer.head];
|
||||
}
|
||||
T peek() { return buffer.queue[buffer.head]; }
|
||||
|
||||
/**
|
||||
* @brief Gets the number of items on the queue
|
||||
* @details Returns the current number of items stored on the queue.
|
||||
* @return number of items in the queue
|
||||
*/
|
||||
uint8_t count() {
|
||||
return this->buffer.count;
|
||||
}
|
||||
uint8_t count() { return buffer.count; }
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user