Apply const, safe_delay in servo.*

2.0.x
Scott Lahteine 7 years ago
parent 3c2bfa5e53
commit e297748b22

@ -54,19 +54,15 @@
#include "../inc/MarlinConfig.h" #include "../inc/MarlinConfig.h"
#include "HAL.h"
#if HAS_SERVOS && !(IS_32BIT_TEENSY || defined(TARGET_LPC1768)) #if HAS_SERVOS && !(IS_32BIT_TEENSY || defined(TARGET_LPC1768))
//#include <Arduino.h> //#include <Arduino.h>
#include "servo.h" #include "servo.h"
#include "servo_private.h" #include "servo_private.h"
ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures
uint8_t ServoCount = 0; // the total number of attached servos 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_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_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
@ -92,11 +88,11 @@ Servo::Servo() {
this->servoIndex = INVALID_SERVO; // too many servos this->servoIndex = INVALID_SERVO; // too many servos
} }
int8_t Servo::attach(int pin) { int8_t Servo::attach(const int pin) {
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH); return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
} }
int8_t Servo::attach(int pin, int min, int max) { int8_t Servo::attach(const int pin, const int min, const int max) {
if (this->servoIndex >= MAX_SERVOS) return -1; if (this->servoIndex >= MAX_SERVOS) return -1;
@ -151,12 +147,12 @@ int Servo::readMicroseconds() {
bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; } bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; }
void Servo::move(int value) { void Servo::move(const int value) {
constexpr uint16_t servo_delay[] = SERVO_DELAY; constexpr uint16_t servo_delay[] = SERVO_DELAY;
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
if (this->attach(0) >= 0) { if (this->attach(0) >= 0) {
this->write(value); this->write(value);
delay(servo_delay[this->servoIndex]); safe_delay(servo_delay[this->servoIndex]);
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
this->detach(); this->detach();
#endif #endif

@ -89,12 +89,12 @@
class Servo { class Servo {
public: public:
Servo(); Servo();
int8_t attach(int pin); // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail) int8_t attach(const int pin); // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail)
int8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes. int8_t attach(const int pin, const int min, const int max); // as above but also sets min and max values for writes.
void detach(); void detach();
void write(int value); // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds void write(int value); // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
void writeMicroseconds(int value); // write pulse width in microseconds void writeMicroseconds(int value); // write pulse width in microseconds
void move(int value); // attach the servo, then move to value void move(const int value); // attach the servo, then move to value
// if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
// if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach // if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach
int read(); // returns current pulse width as an angle between 0 and 180 degrees int read(); // returns current pulse width as an angle between 0 and 180 degrees

Loading…
Cancel
Save