Skip to content

Commit

Permalink
move first run from knit() to begin()
Browse files Browse the repository at this point in the history
  • Loading branch information
t0mpr1c3 committed Oct 4, 2023
1 parent 3c82e46 commit 2156789
Show file tree
Hide file tree
Showing 4 changed files with 52 additions and 64 deletions.
32 changes: 12 additions & 20 deletions src/ayab/opKnit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,6 @@
#include "opReady.h"
#include "opKnit.h"

#ifdef CLANG_TIDY
// clang-tidy doesn't find these macros for some reason,
// no problem when building or testing though.
constexpr uint8_t UINT8_MAX = 0xFFU;
constexpr uint16_t UINT16_MAX = 0xFFFFU;
#endif

/*!
* \brief enum OpState
* \return OpState_t::Knit
Expand All @@ -69,7 +62,6 @@ void OpKnit::init() {
m_currentLineNumber = 0U;
m_lastLineFlag = false;
m_sOldPosition = 0U;
m_firstRun = true;
m_workedOnLine = false;
#ifdef DBG_NOMACHINE
m_prevState = false;
Expand All @@ -85,6 +77,12 @@ void OpKnit::init() {
void OpKnit::begin() {
GlobalEncoders::init(GlobalController::getMachineType());
GlobalEncoders::setUpInterrupt();

// first run
// TODO(who?): optimize delay for various Arduino models
delay(START_KNITTING_DELAY);
GlobalBeeper::finishedLine();
reqLine(0);
}

/*!
Expand All @@ -107,7 +105,11 @@ void OpKnit::com(const uint8_t *buffer, size_t size) {
GlobalCom::h_reqTest();
break;

// FIXME needs to be a `Cancel` command in the API that resets state from `OpKnit` to `OpInit`
// Resets state from `OpKnit` to `OpInit`
case static_cast<uint8_t>(API_t::quitCmd):
GlobalCom::h_quitCmd();
break;

default:
GlobalCom::h_unrecognized();
break;
Expand Down Expand Up @@ -154,8 +156,7 @@ Err_t OpKnit::startKnitting(uint8_t startNeedle,
m_continuousReportingEnabled = continuousReportingEnabled;

// reset variables to start conditions
m_currentLineNumber = UINT8_MAX; // because counter will
// be incremented before request
m_currentLineNumber = 0;
m_lineRequested = false;
m_lastLineFlag = false;

Expand All @@ -171,15 +172,6 @@ Err_t OpKnit::startKnitting(uint8_t startNeedle,
* \brief Function that is repeatedly called during state `OpKnit`
*/
void OpKnit::knit() {
if (m_firstRun) {
m_firstRun = false;
// TODO(who?): optimize delay for various Arduino models
delay(START_KNITTING_DELAY);
GlobalBeeper::finishedLine();
++m_currentLineNumber;
reqLine(m_currentLineNumber);
}

#ifdef DBG_NOMACHINE
// TODO(who?): check if debounce is needed
bool state = digitalRead(DBG_BTN_PIN);
Expand Down
1 change: 0 additions & 1 deletion src/ayab/opKnit.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,6 @@ class OpKnit : public OpKnitInterface {
bool m_lastLineFlag;

uint8_t m_sOldPosition;
bool m_firstRun;
bool m_workedOnLine;
#ifdef DBG_NOMACHINE
bool m_prevState;
Expand Down
81 changes: 39 additions & 42 deletions test/test_OpKnit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -225,14 +225,7 @@ class OpKnitTest : public ::testing::Test {
controller->update();
}

void expected_update_knit(bool first) {
if (first) {
get_to_knit(Machine_t::Kh910);
expect_first_knit();
//EXPECT_CALL(*arduinoMock, digitalWrite(LED_PIN_A, HIGH)); // green LED on
expected_update();
return;
}
void expected_update_knit() {
ASSERT_EQ(controller->getState(), opKnit);
//EXPECT_CALL(*arduinoMock, digitalWrite(LED_PIN_A, HIGH)); // green LED on
expected_update();
Expand Down Expand Up @@ -377,15 +370,15 @@ TEST_F(OpKnitTest, test_startKnitting_failures) {
}

TEST_F(OpKnitTest, test_setNextLine) {
get_to_knit(Machine_t::Kh910);

// set `m_lineRequested`
ASSERT_EQ(opKnit->setNextLine(1), false);

expected_update_knit(true);

// outside of the active needles
expected_cacheISR(NUM_NEEDLES[static_cast<uint8_t>(Machine_t::Kh910)] + END_OF_LINE_OFFSET_R[static_cast<uint8_t>(Machine_t::Kh910)] + 1 + opKnit->getStartOffset(Direction_t::Left));
EXPECT_CALL(*solenoidsMock, setSolenoid).Times(1);
expected_update_knit(false);
expected_update_knit();

// wrong line number
EXPECT_CALL(*beeperMock, finishedLine).Times(0);
Expand Down Expand Up @@ -418,30 +411,31 @@ TEST_F(OpKnitTest, test_knit_Kh910) {
const uint8_t STOP_NEEDLE = NUM_NEEDLES[static_cast<uint8_t>(Machine_t::Kh910)] - 1;
opKnit->startKnitting(START_NEEDLE, STOP_NEEDLE, pattern, true);
//EXPECT_CALL(*arduinoMock, digitalWrite(LED_PIN_A, LOW)); // green LED off
expected_update();

// first knit
expect_first_knit();
expect_indState();
expected_update_knit(false);
expected_update();

// no useful position calculated by `calculatePixelAndSolenoid()`
expected_cacheISR(100, Direction_t::NoDirection, Direction_t::Right, BeltShift::Shifted, Carriage_t::Knit);
EXPECT_CALL(*solenoidsMock, setSolenoid).Times(0);
expect_indState();
expected_update_knit(false);
expected_update_knit();

// don't set `m_workedonline` to `true`
const uint8_t OFFSET = END_OF_LINE_OFFSET_R[static_cast<uint8_t>(Machine_t::Kh910)];
expected_cacheISR(8 + STOP_NEEDLE + OFFSET);
EXPECT_CALL(*solenoidsMock, setSolenoid);
expect_indState();
expected_update_knit(false);
expected_update_knit();

expected_cacheISR(START_NEEDLE);
EXPECT_CALL(*solenoidsMock, setSolenoid);
expect_indState();
expected_update_knit(false);
expected_update_knit();

// cancel
EXPECT_CALL(*comMock, h_quitCmd);
const uint8_t buffer[] = {static_cast<uint8_t>(API_t::quitCmd)};
opKnit->com(buffer, 1);

// test expectations without destroying instance
ASSERT_TRUE(Mock::VerifyAndClear(solenoidsMock));
Expand All @@ -462,36 +456,32 @@ TEST_F(OpKnitTest, test_knit_Kh270) {
const uint8_t STOP_NEEDLE = NUM_NEEDLES[static_cast<uint8_t>(Machine_t::Kh270)] - 1;
opKnit->startKnitting(START_NEEDLE, STOP_NEEDLE, pattern, true);
//EXPECT_CALL(*arduinoMock, digitalWrite(LED_PIN_A, LOW));
expect_first_knit();
expected_update();

// first knit
expect_first_knit();
expect_indState();
expected_update_knit(false);

// second knit
expected_cacheISR(START_NEEDLE);
expect_indState();
EXPECT_CALL(*solenoidsMock, setSolenoid);
expected_update_knit(false);
expected_update_knit();

// no useful position calculated by `calculatePixelAndSolenoid()`
expected_cacheISR(60, Direction_t::NoDirection, Direction_t::Right, BeltShift::Shifted, Carriage_t::Knit);
EXPECT_CALL(*solenoidsMock, setSolenoid).Times(0);
expect_indState();
expected_update_knit(false);
expected_update_knit();

// don't set `m_workedonline` to `true`
const uint8_t OFFSET = END_OF_LINE_OFFSET_R[static_cast<uint8_t>(Machine_t::Kh270)];
expected_cacheISR(8 + STOP_NEEDLE + OFFSET, Direction_t::Right, Direction_t::Left, BeltShift::Regular, Carriage_t::Knit);
EXPECT_CALL(*solenoidsMock, setSolenoid);
expect_indState();
expected_update_knit(false);
expected_update_knit();

expected_cacheISR(START_NEEDLE, Direction_t::Right, Direction_t::Left, BeltShift::Regular, Carriage_t::Knit);
EXPECT_CALL(*solenoidsMock, setSolenoid);
expect_indState();
expected_update_knit(false);
expected_update_knit();

// test expectations without destroying instance
ASSERT_TRUE(Mock::VerifyAndClear(solenoidsMock));
Expand All @@ -501,19 +491,21 @@ TEST_F(OpKnitTest, test_knit_Kh270) {
}

TEST_F(OpKnitTest, test_knit_line_request) {
get_to_knit(Machine_t::Kh910);

// `m_workedOnLine` is set to `true`
expected_update_knit(true);
expected_update_knit();

// Position has changed since last call to operate function
// `m_pixelToSet` is set above `m_stopNeedle` + END_OF_LINE_OFFSET_R
expected_cacheISR(NUM_NEEDLES[static_cast<uint8_t>(Machine_t::Kh910)] + 8 + END_OF_LINE_OFFSET_R[static_cast<uint8_t>(Machine_t::Kh910)] + 1);

EXPECT_CALL(*solenoidsMock, setSolenoid);
expected_update_knit(false);
expected_update_knit();

// no change in position, no action.
EXPECT_CALL(*solenoidsMock, setSolenoid).Times(0);
expected_update_knit(false);
expected_update_knit();

// test expectations without destroying instance
ASSERT_TRUE(Mock::VerifyAndClear(solenoidsMock));
Expand All @@ -523,13 +515,14 @@ TEST_F(OpKnitTest, test_knit_line_request) {
}

TEST_F(OpKnitTest, test_knit_lastLine) {
expected_update_knit(true);
get_to_knit(Machine_t::Kh910);
expected_update_knit();

// Run one knit inside the working needles.
EXPECT_CALL(*solenoidsMock, setSolenoid);
expected_cacheISR(opKnit->getStartOffset(Direction_t::Left) + 20);
// `m_workedOnLine` is set to true
expected_update_knit(false);
expected_update_knit();

// Position has changed since last call to operate function
// `m_pixelToSet` is above `m_stopNeedle` + END_OF_LINE_OFFSET_R
Expand All @@ -542,7 +535,7 @@ TEST_F(OpKnitTest, test_knit_lastLine) {
EXPECT_CALL(*beeperMock, endWork);
EXPECT_CALL(*solenoidsMock, setSolenoids(SOLENOIDS_BITMASK));
//EXPECT_CALL(*beeperMock, finishedLine);
expected_update_knit(false);
expected_update_knit();

// test expectations without destroying instance
ASSERT_TRUE(Mock::VerifyAndClear(solenoidsMock));
Expand All @@ -552,13 +545,14 @@ TEST_F(OpKnitTest, test_knit_lastLine) {
}

TEST_F(OpKnitTest, test_knit_lastLine_and_no_req) {
expected_update_knit(true);
get_to_knit(Machine_t::Kh910);
expected_update_knit();

// Run one knit inside the working needles.
EXPECT_CALL(*solenoidsMock, setSolenoid);
expected_cacheISR(opKnit->getStartOffset(Direction_t::Left) + 20);
// `m_workedOnLine` is set to true
expected_update_knit(false);
expected_update_knit();

// Position has changed since last call to operate function
// `m_pixelToSet` is above `m_stopNeedle` + END_OF_LINE_OFFSET_R
Expand All @@ -575,7 +569,7 @@ TEST_F(OpKnitTest, test_knit_lastLine_and_no_req) {
EXPECT_CALL(*beeperMock, endWork);
EXPECT_CALL(*solenoidsMock, setSolenoids(SOLENOIDS_BITMASK));
//EXPECT_CALL(*beeperMock, finishedLine);
expected_update_knit(false);
expected_update_knit();

// test expectations without destroying instance
ASSERT_TRUE(Mock::VerifyAndClear(solenoidsMock));
Expand All @@ -585,11 +579,12 @@ TEST_F(OpKnitTest, test_knit_lastLine_and_no_req) {
}

TEST_F(OpKnitTest, test_knit_same_position) {
expected_update_knit(true);
get_to_knit(Machine_t::Kh910);
expected_update_knit();

// no call to `setSolenoid()` since position was the same
EXPECT_CALL(*solenoidsMock, setSolenoid).Times(0);
expected_update_knit(false);
expected_update_knit();

// test expectations without destroying instance
ASSERT_TRUE(Mock::VerifyAndClear(solenoidsMock));
Expand All @@ -599,14 +594,16 @@ TEST_F(OpKnitTest, test_knit_same_position) {
}

TEST_F(OpKnitTest, test_knit_new_line) {
get_to_knit(Machine_t::Kh910);

// _workedOnLine is set to true
expected_update_knit(true);
expected_update_knit();

// Run one knit inside the working needles.
EXPECT_CALL(*solenoidsMock, setSolenoid);
expected_cacheISR(opKnit->getStartOffset(Direction_t::Left) + 20);
// `m_workedOnLine` is set to true
expected_update_knit(false);
expected_update_knit();

// Position has changed since last call to operate function
// `m_pixelToSet` is above `m_stopNeedle` + END_OF_LINE_OFFSET_R
Expand All @@ -620,7 +617,7 @@ TEST_F(OpKnitTest, test_knit_new_line) {

// `reqLine()` is called which calls `send_reqLine()`
expect_reqLine();
expected_update_knit(false);
expected_update_knit();

// test expectations without destroying instance
ASSERT_TRUE(Mock::VerifyAndClear(solenoidsMock));
Expand Down
2 changes: 1 addition & 1 deletion test/test_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,7 @@ class ControllerTest : public ::testing::Test {
ASSERT_EQ(controller->getState(), opReadyMock);

EXPECT_CALL(*opReadyMock, update);
expect_first_knit();
expected_update();

// test expectations without destroying instance
Expand Down Expand Up @@ -253,7 +254,6 @@ TEST_F(ControllerTest, test_update_knit) {
ASSERT_EQ(controller->getState(), opKnit);

// now in state `OpKnit`
expect_first_knit();
expected_update_knit();

// test expectations without destroying instance
Expand Down

0 comments on commit 2156789

Please sign in to comment.