Skip to content

Commit

Permalink
fix example building and linting
Browse files Browse the repository at this point in the history
  • Loading branch information
timhendriks93 committed Jan 11, 2024
1 parent 4076e09 commit 0d9a228
Show file tree
Hide file tree
Showing 31 changed files with 112 additions and 124 deletions.
8 changes: 5 additions & 3 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,14 @@ jobs:
example:
[
AdafruitPCA9685,
SerialLiveMode,
WebSocketLiveMode,
MultiplePCA9685,
Show,
MultipleScenes,
MultipleScenesSD,
SDAnimation,
SerialLiveMode,
StandardServoLib,
SwitchModeButton,
WebSocketLiveMode,
]
steps:
- uses: actions/checkout@v3
Expand Down
6 changes: 4 additions & 2 deletions examples/MultipleScenes/MultipleScenes.ino
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,10 @@ void setup() {
animation.onPositionChange(move);

// Add multiple scenes based on PROGMEM data
animation.addScene(SceneA::ANIMATION_DATA, SceneA::LENGTH, SceneA::FPS, SceneA::FRAMES);
animation.addScene(SceneB::ANIMATION_DATA, SceneB::LENGTH, SceneB::FPS, SceneB::FRAMES);
animation.addScene(SceneA::ANIMATION_DATA, SceneA::LENGTH, SceneA::FPS,
SceneA::FRAMES);
animation.addScene(SceneB::ANIMATION_DATA, SceneB::LENGTH, SceneB::FPS,
SceneB::FRAMES);

// Trigger the show loop mode
animation.loop();
Expand Down
3 changes: 2 additions & 1 deletion examples/SwitchModeButton/SwitchModeButton.ino
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,8 @@ BlenderServoAnimation::Animation animation;
void onPressed() {
// Get the current mode, act accordingly and trigger another mode
switch (animation.getMode()) {
// On short press in default or pause mode, we want to start or resume the animation
// On short press in default or pause mode, we want to start or resume the
// animation
case BlenderServoAnimation::Animation::MODE_DEFAULT:
case BlenderServoAnimation::Animation::MODE_PAUSE:
animation.play();
Expand Down
3 changes: 2 additions & 1 deletion examples/WebSocketLiveMode/WebSocketLiveMode.ino
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,8 @@ AsyncWebSocket ws("/");
// Servo object to send positions
Servo myServo;

// LiveStream instance acting as a middleware between web socket and animation instance
// LiveStream instance acting as a middleware between web socket and animation
// instance
BlenderServoAnimation::LiveStream liveStream;

// Callback function which is called whenever a servo needs to be moved
Expand Down
12 changes: 7 additions & 5 deletions src/internal/Animation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,15 @@ bool Animation::hasScene(byte index) {
return this->scenes[index] != nullptr;
}

void Animation::addScene(const byte PROGMEM *data, int dataLength, byte fps, int frames) {
ProgmemStream* stream = new ProgmemStream(data, dataLength);
void Animation::addScene(const byte *data, int dataLength, byte fps,
int frames) {
ProgmemStream *stream = new ProgmemStream(data, dataLength);
this->addScene(*stream, fps, frames);
}

void Animation::addScene(Stream &data, byte fps, int frames) {
this->scenes[this->addIndex] = new Scene(this->servoManager, data, fps, frames);
this->scenes[this->addIndex] =
new Scene(this->servoManager, data, fps, frames);
this->addIndex++;
}

Expand Down Expand Up @@ -111,7 +113,7 @@ void Animation::loop() {

void Animation::pause() {
if (!this->scene || !this->modeIsIn(4, MODE_PLAY, MODE_PLAY_SINGLE,
MODE_PLAY_RANDOM, MODE_LOOP)) {
MODE_PLAY_RANDOM, MODE_LOOP)) {
return;
}

Expand Down Expand Up @@ -215,7 +217,7 @@ void Animation::handleStopMode(unsigned long currentMicros) {
}
}

Scene* Animation::getCurrentScene() {
Scene *Animation::getCurrentScene() {
return this->scene;
}

Expand Down
9 changes: 4 additions & 5 deletions src/internal/Animation.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ class Animation {

int countScenes();

void addScene(const byte PROGMEM *data, int dataLength, byte fps, int frames);
void addScene(const byte *data, int dataLength, byte fps, int frames);
void addScene(Stream &data, byte fps = 0, int frames = 0);
void onPositionChange(pcb positionCallback);
void onModeChange(mcb modeCallback);
Expand All @@ -48,15 +48,15 @@ class Animation {
bool hasScene(byte index);
bool modeIsIn(byte modeAmount, ...);

Scene* getCurrentScene();
Scene *getCurrentScene();

private:
static const int MAX_SCENE_COUNT = 256;

ServoManager servoManager;

Scene* scenes[MAX_SCENE_COUNT] = {nullptr};
Scene* scene = nullptr;
Scene *scenes[MAX_SCENE_COUNT] = {nullptr};
Scene *scene = nullptr;

mcb modeCallback = nullptr;
scb sceneCallback = nullptr;
Expand All @@ -70,7 +70,6 @@ class Animation {
void handlePlayMode(unsigned long currentMicros);
void handleStopMode(unsigned long currentMicros);
void setRandomScene();

};

} // namespace BlenderServoAnimation
Expand Down
1 change: 0 additions & 1 deletion src/internal/Command.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@ class Command {
byte index = 0;

void reset();

};

} // namespace BlenderServoAnimation
Expand Down
2 changes: 1 addition & 1 deletion src/internal/LiveStream.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ int LiveStream::peek() {
return this->buffer[this->readIndex];
} else {
return -1;
}
}
}

int LiveStream::read() {
Expand Down
3 changes: 1 addition & 2 deletions src/internal/LiveStream.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ class LiveStream : public Stream {
int available();
int read();
int peek();

size_t write(uint8_t);

void flush();
Expand All @@ -22,7 +22,6 @@ class LiveStream : public Stream {
byte buffer[BUFFER_SIZE] = {0};
byte writeIndex = 0;
byte readIndex = 0;

};

} // namespace BlenderServoAnimation
Expand Down
32 changes: 16 additions & 16 deletions src/internal/ProgmemStream.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,35 +3,35 @@

using namespace BlenderServoAnimation;

ProgmemStream::ProgmemStream(const byte PROGMEM *data, size_t size) {
this->data = data;
this->size = size;
ProgmemStream::ProgmemStream(const byte *data, size_t size) {
this->data = data;
this->size = size;
}

int ProgmemStream::read() {
if (this->position < this->size) {
return pgm_read_byte_far(this->data + this->position++);
} else {
return -1;
}
if (this->position < this->size) {
return pgm_read_byte(this->data + this->position++);
} else {
return -1;
}
}

int ProgmemStream::available() {
return size - position;
return size - position;
}

int ProgmemStream::peek() {
if (position < size) {
return pgm_read_byte_far(this->data + this->position);
} else {
return -1;
}
if (position < size) {
return pgm_read_byte(this->data + this->position);
} else {
return -1;
}
}

size_t ProgmemStream::write(uint8_t value) {
return 0;
return 0;
}

void ProgmemStream::flush() {
this->position = 0;
this->position = 0;
}
21 changes: 10 additions & 11 deletions src/internal/ProgmemStream.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,22 +8,21 @@ namespace BlenderServoAnimation {
class ProgmemStream : public Stream {

public:
ProgmemStream(const byte PROGMEM *data, size_t size);
ProgmemStream(const byte *data, size_t size);

int available();
int read();
int peek();
int available();
int read();
int peek();

size_t write(uint8_t);

void flush();
size_t write(uint8_t);

private:
const byte PROGMEM *data = nullptr;
void flush();

size_t size = 0;
size_t position = 0;
private:
const byte *data = nullptr;

size_t size = 0;
size_t position = 0;
};

} // namespace BlenderServoAnimation
Expand Down
12 changes: 7 additions & 5 deletions src/internal/Scene.cpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
#include "Command.h"
#include "Scene.h"
#include "Servo.h"
#include "Command.h"
#include "ProgmemStream.h"
#include "Servo.h"
#include <Arduino.h>

using namespace BlenderServoAnimation;

Scene::Scene(ServoManager &servoManager, Stream &data, byte fps, int frames, bool hasProgmemStream) {
Scene::Scene(ServoManager &servoManager, Stream &data, byte fps, int frames,
bool hasProgmemStream) {
this->servoManager = &servoManager;
this->data = &data;
this->fps = fps;
Expand Down Expand Up @@ -60,7 +61,7 @@ void Scene::stop(unsigned long currentMicros) {
}
}

int Scene::getMicrosDiff(unsigned long currentMicros) {
unsigned int Scene::getMicrosDiff(unsigned long currentMicros) {
if (currentMicros >= this->lastMicros) {
return currentMicros - this->lastMicros;
}
Expand All @@ -69,7 +70,8 @@ int Scene::getMicrosDiff(unsigned long currentMicros) {
}

bool Scene::isNewFrame(unsigned long currentMicros) {
return this->lastMicros == 0 || this->getMicrosDiff(currentMicros) >= this->frameMicros;
return this->lastMicros == 0 ||
this->getMicrosDiff(currentMicros) >= this->frameMicros;
}

bool Scene::hasFinished() {
Expand Down
10 changes: 5 additions & 5 deletions src/internal/Scene.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@ namespace BlenderServoAnimation {
class Scene {

public:
Scene(ServoManager &servoManager, Stream &data, byte fps = 0, int frames = 0, bool hasProgmemStream = false);
Scene(ServoManager &servoManager, Stream &data, byte fps = 0, int frames = 0,
bool hasProgmemStream = false);
~Scene();

void play(unsigned long currentMicros);
Expand Down Expand Up @@ -39,16 +40,15 @@ class Scene {

bool hasProgmemStream = false;

ServoManager* servoManager;
ServoManager *servoManager;

Stream* data = nullptr;
Stream *data = nullptr;

void parseCommands();

bool isNewFrame(unsigned long currentMicros);

int getMicrosDiff(unsigned long currentMicros);

unsigned int getMicrosDiff(unsigned long currentMicros);
};

} // namespace BlenderServoAnimation
Expand Down
3 changes: 2 additions & 1 deletion src/internal/Servo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,8 @@ Servo::Servo(byte id, pcb positionCallback, byte threshold) {
}

void Servo::move(int position) {
if (position == this->currentPosition || this->positionExceedsThreshold(position)) {
if (position == this->currentPosition ||
this->positionExceedsThreshold(position)) {
return;
}

Expand Down
1 change: 0 additions & 1 deletion src/internal/Servo.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@ class Servo {
pcb positionCallback = nullptr;

bool positionExceedsThreshold(int position);

};

} // namespace BlenderServoAnimation
Expand Down
8 changes: 4 additions & 4 deletions src/internal/ServoManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ using namespace BlenderServoAnimation;
ServoManager::~ServoManager() {
for (int i = 0; i < MAX_SERVO_COUNT; i++) {
if (this->servos[i]) {
delete this->servos[i];
delete this->servos[i];
}
}
}
Expand All @@ -17,7 +17,7 @@ void ServoManager::setPositionCallback(pcb positionCallback) {

for (int i = 0; i < MAX_SERVO_COUNT; i++) {
if (this->servos[i]) {
this->servos[i]->setPositionCallback(positionCallback);
this->servos[i]->setPositionCallback(positionCallback);
}
}
}
Expand Down Expand Up @@ -51,7 +51,7 @@ void ServoManager::handleCommand(Command command) {

void ServoManager::moveAllServosToNeutral() {
for (int i = 0; i < MAX_SERVO_COUNT; i++) {
Servo* servo = this->servos[i];
Servo *servo = this->servos[i];

if (servo && !servo->isNeutral()) {
servo->moveTowardsNeutral();
Expand All @@ -65,7 +65,7 @@ bool ServoManager::hasPositionCallback() {

bool ServoManager::servosAreAllNeutral() {
for (int i = 0; i < MAX_SERVO_COUNT; i++) {
Servo* servo = this->servos[i];
Servo *servo = this->servos[i];

if (servo && !servo->isNeutral()) {
return false;
Expand Down
3 changes: 1 addition & 2 deletions src/internal/ServoManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,15 +25,14 @@ class ServoManager {
private:
static const int MAX_SERVO_COUNT = 256;

Servo* servos[MAX_SERVO_COUNT] = {nullptr};
Servo *servos[MAX_SERVO_COUNT] = {nullptr};

pcb positionCallback = nullptr;

byte defaultThreshold = 0;
byte thresholds[MAX_SERVO_COUNT] = {0};

void addServo(byte id);

};

} // namespace BlenderServoAnimation
Expand Down
2 changes: 1 addition & 1 deletion src/internal/typedefs.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include <Arduino.h>

typedef void (*mcb)(byte, byte); // Mode callback
typedef void (*pcb)(byte, int); // Position callback
typedef void (*pcb)(byte, int); // Position callback
typedef void (*scb)(byte, byte); // Scene callback
2 changes: 1 addition & 1 deletion test/animation/test_loop/test_loop.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "../test/helper.h"
#include "internal/Animation.h"
#include "internal/LiveStream.h"
#include "../test/helper.h"
#include <unity.h>

using namespace BlenderServoAnimation;
Expand Down
Loading

0 comments on commit 0d9a228

Please sign in to comment.