Skip to content

Commit

Permalink
encoders: fix carriage detection on the right
Browse files Browse the repository at this point in the history
Mostly by copying the logic from encA_rising into encA_falling, and
special-casing the KH910 with its inverted K-only reading.
  • Loading branch information
jonathanperret committed Oct 13, 2024
1 parent 656810b commit 163db4f
Show file tree
Hide file tree
Showing 4 changed files with 101 additions and 35 deletions.
61 changes: 46 additions & 15 deletions src/ayab/encoders.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,9 @@ void Encoders::encA_rising() {
}
} else if (m_carriage == Carriage_t::NoCarriage) {
m_carriage = detected_carriage;
} else if (m_carriage != detected_carriage && m_position > start_position) {
} else if (m_carriage == Carriage::Lace &&
detected_carriage == Carriage::Knit &&
m_position > start_position) {
m_carriage = Carriage_t::Garter;

// We swap the belt shift for the g-carriage because the point of work for
Expand Down Expand Up @@ -238,14 +240,8 @@ void Encoders::encA_falling() {

// In front of Right Hall Sensor?
uint16_t hallValue = analogRead(EOL_PIN_R);

// Avoid 'comparison of unsigned expression < 0 is always false'
// by being explicit about that behaviour being expected.
bool hallValueSmall = false;

hallValueSmall = (hallValue < FILTER_R_MIN[static_cast<uint8_t>(m_machineType)]);

if (hallValueSmall || hallValue > FILTER_R_MAX[static_cast<uint8_t>(m_machineType)]) {
if ((hallValue < FILTER_R_MIN[static_cast<uint8_t>(m_machineType)]) ||
(hallValue > FILTER_R_MAX[static_cast<uint8_t>(m_machineType)])) {
m_hallActive = Direction_t::Right;

// The garter carriage has a second set of magnets that are going to
Expand All @@ -265,18 +261,53 @@ void Encoders::encA_falling() {
// Shift doens't need to be swapped for the g-carriage in this direction.
}

// The garter carriage has extra magnets that are going to
// pass the sensor and will reset state incorrectly if allowed to
// continue.
if (m_carriage == Carriage_t::Garter) {
// If the carriage is already set, ignore the rest.
if ((Carriage_t::Knit == m_carriage) && (Machine_t::Kh270 == m_machineType)) {
return;
}

if (hallValueSmall) {
Carriage detected_carriage = Carriage_t::NoCarriage;
uint8_t start_position = END_RIGHT_MINUS_OFFSET[static_cast<uint8_t>(m_machineType)];

if (m_machineType == MachineType::Kh910) {
// Due to an error in wiring on the shield, the sensor only triggers for the K carriage,
// and with a low voltage so we can't use the same logic as for other machines.
detected_carriage = Carriage_t::Knit;
} else {
if (hallValue >= FILTER_R_MIN[static_cast<uint8_t>(m_machineType)]) {
detected_carriage = Carriage_t::Knit;
} else {
detected_carriage = Carriage_t::Lace;
}
}

if (m_machineType == Machine_t::Kh270) {
m_carriage = Carriage_t::Knit;

// The first magnet on the carriage looks like Lace, the second looks like Knit
if (detected_carriage == Carriage_t::Knit) {
start_position = start_position + MAGNET_DISTANCE_270;
}
} else if (m_carriage == Carriage_t::NoCarriage) {
m_carriage = detected_carriage;
} else if (m_carriage == Carriage::Lace &&
detected_carriage == Carriage::Knit &&
m_position < start_position) {
m_carriage = Carriage_t::Garter;

// Belt shift and start position were set when the first magnet passed
// the sensor and we assumed we were working with a standard carriage.

// Because we detected the leftmost magnet on the G-carriage first,
// for consistency with the left side where we detect the rightmost magnet
// first, we need to adjust the carriage position.
m_position += GARTER_L_MAGNET_SPACING;
return;
} else {
m_carriage = detected_carriage;
}

// Known position of the carriage -> overwrite position
m_position = END_RIGHT_MINUS_OFFSET[static_cast<uint8_t>(m_machineType)];
m_position = start_position;
}
}
6 changes: 5 additions & 1 deletion src/ayab/encoders.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,10 @@ constexpr uint8_t ALL_MAGNETS_CLEARED_RIGHT[NUM_MACHINES] = {199U, 199U, 130U};
// If we didn't have it, we'd decide which carriage we had when the first magnet passed the sensor.
// For the garter carriage we need to see both magnets.
constexpr uint8_t GARTER_SLOP = 2U;
// Spacing between a garter carriage's outer (L-carriage-like) magnets.
// For consistency between a garter carriage starting on the left or the right,
// we need to adjust the position by this distance when starting from the right.
constexpr uint8_t GARTER_L_MAGNET_SPACING = 24U;

constexpr uint8_t START_OFFSET[NUM_MACHINES][NUM_DIRECTIONS][NUM_CARRIAGES] = {
// KH910
Expand Down Expand Up @@ -108,7 +112,7 @@ constexpr uint8_t START_OFFSET[NUM_MACHINES][NUM_DIRECTIONS][NUM_CARRIAGES] = {
// KH910 KH930 KH270
constexpr uint16_t FILTER_L_MIN[NUM_MACHINES] = { 200U, 200U, 200U};
constexpr uint16_t FILTER_L_MAX[NUM_MACHINES] = { 600U, 600U, 600U};
constexpr uint16_t FILTER_R_MIN[NUM_MACHINES] = { 200U, 0U, 0U};
constexpr uint16_t FILTER_R_MIN[NUM_MACHINES] = { 200U, 200U, 200U};
constexpr uint16_t FILTER_R_MAX[NUM_MACHINES] = {1023U, 600U, 600U};

constexpr uint16_t SOLENOIDS_BITMASK = 0xFFFFU;
Expand Down
44 changes: 34 additions & 10 deletions test/test_e2e.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -390,10 +390,6 @@ TEST_F(E2ETest, EncodersDetectKCarriageOnTheRight_KH910) {
}

TEST_F(E2ETest, EncodersDetectKCarriageOnTheRight_KH930) {
GTEST_SKIP()
<< "Known failing "
"(https://github.com/AllYarnsAreBeautiful/ayab-firmware/issues/175)";

KnittingMachine km;
KnittingMachineAdapter kma(km, *m_arduinoMock);

Expand All @@ -414,15 +410,11 @@ TEST_F(E2ETest, EncodersDetectKCarriageOnTheRight_KH930) {
// Position should have been reset to END_RIGHT_MINUS_OFFSET when the magnet
// passed the right sensor
ASSERT_NEAR(m_Encoders.getPosition(),
END_RIGHT_MINUS_OFFSET[(uint8_t)MachineType::Kh930], 1);
END_RIGHT_MINUS_OFFSET[(uint8_t)MachineType::Kh930], 2);
ASSERT_EQ(m_Encoders.getCarriage(), Carriage::Knit);
}

TEST_F(E2ETest, EncodersDetectLCarriageOnTheRight_KH930) {
GTEST_SKIP()
<< "Known failing "
"(https://github.com/AllYarnsAreBeautiful/ayab-firmware/issues/176)";

KnittingMachine km;
KnittingMachineAdapter kma(km, *m_arduinoMock);

Expand All @@ -443,10 +435,42 @@ TEST_F(E2ETest, EncodersDetectLCarriageOnTheRight_KH930) {
// Position should have been reset to END_RIGHT_MINUS_OFFSET when the magnet
// passed the right sensor
ASSERT_NEAR(m_Encoders.getPosition(),
END_RIGHT_MINUS_OFFSET[(uint8_t)MachineType::Kh930], 1);
END_RIGHT_MINUS_OFFSET[(uint8_t)MachineType::Kh930], 2);
ASSERT_EQ(m_Encoders.getCarriage(), Carriage::Lace);
}

TEST_F(E2ETest, EncodersDetectGCarriageOnTheRight_KH930) {
KnittingMachine km;
KnittingMachineAdapter kma(km, *m_arduinoMock);

// Simulate a KH-930 G carriage, starting outside of the bed to the right
km.addGCarriageMagnets();
km.putCarriageCenterInFrontOfNeedle(250);

// TODO trigger this from simulated serial communication
GlobalKnitter::initMachine(MachineType::Kh930);
ASSERT_EQ(m_Encoders.getCarriage(), Carriage::NoCarriage);

// Move the carriage to the left until its magnets get past the right
// sensor
const int targetNeedle = 100;
while (km.moveCarriageCenterTowardsNeedle(targetNeedle)) {
GlobalKnitter::isr();
}

// Position should be reset to END_LEFT_PLUS_OFFSET at the time the
// rightmost magnet passes the sensor, so we can add that plus the
// position of the rightmost magnet to get the expected position.
const int internalPositionOffset =
END_LEFT_PLUS_OFFSET[(uint8_t)MachineType::Kh930] + 12;

// Position should have been reset to END_RIGHT_MINUS_OFFSET,
// minus the magnet distance, when the magnet passed the right sensor
ASSERT_NEAR(m_Encoders.getPosition(),
targetNeedle + internalPositionOffset, 2);
ASSERT_EQ(m_Encoders.getCarriage(), Carriage::Garter);
}

TEST_P(WithMachineAndTargetNeedle, EncodersKeepTrackOfKCarriage) {
const MachineType machineType = std::get<0>(GetParam());
const int targetNeedle = std::get<1>(GetParam());
Expand Down
25 changes: 16 additions & 9 deletions test/test_encoders.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,30 +131,34 @@ TEST_F(EncodersTest, test_encA_rising_in_front_G_carriage) {
// Create a rising edge
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_A)).WillOnce(Return(true));
// Enter rising function, direction is right
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_B)).WillOnce(Return(true)).WillOnce(Return(false));
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_B)).WillOnce(Return(true));
// In front of Left Hall Sensor
EXPECT_CALL(*arduinoMock, analogRead(EOL_PIN_L))
.WillOnce(Return(FILTER_L_MAX[static_cast<int8_t>(encoders->getMachineType())] + 1));
.WillOnce(Return(FILTER_L_MIN[static_cast<int8_t>(encoders->getMachineType())] - 1));
// BeltShift is regular
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_C)).WillOnce(Return(true));

encoders->encA_interrupt();

ASSERT_EQ(encoders->getCarriage(), Carriage_t::Knit);
ASSERT_EQ(encoders->getCarriage(), Carriage_t::Lace);

// Create a falling edge
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_A)).WillOnce(Return(false));
// Enter falling function, direction is right
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_B)).WillOnce(Return(false));
// Not in front of Right Hall sensor
EXPECT_CALL(*arduinoMock, analogRead(EOL_PIN_R))
.WillOnce(Return(FILTER_R_MAX[static_cast<int8_t>(encoders->getMachineType())] + 1));
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_C));
.WillOnce(Return(FILTER_R_MAX[static_cast<int8_t>(encoders->getMachineType())] - 1));

encoders->encA_interrupt();

// Create a rising edge
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_A)).WillOnce(Return(true));
// Enter rising function, direction is right
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_B)).WillOnce(Return(true));
// In front of Left Hall Sensor
EXPECT_CALL(*arduinoMock, analogRead(EOL_PIN_L))
.WillOnce(Return(FILTER_L_MIN[static_cast<int8_t>(encoders->getMachineType())] - 1));
.WillOnce(Return(FILTER_R_MAX[static_cast<int8_t>(encoders->getMachineType())] + 1));

encoders->encA_interrupt();

Expand Down Expand Up @@ -185,7 +189,8 @@ TEST_F(EncodersTest, test_encA_falling_not_in_front) {
}

TEST_F(EncodersTest, test_encA_falling_in_front) {
ASSERT_TRUE(encoders->getMachineType() == Machine_t::Kh910);
encoders->init(Machine_t::Kh930);
ASSERT_TRUE(encoders->getMachineType() == Machine_t::Kh930);
// Create a falling edge
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_A))
.WillOnce(Return(true))
Expand All @@ -210,17 +215,19 @@ TEST_F(EncodersTest, test_encA_falling_in_front) {
ASSERT_EQ(encoders->getDirection(), Direction_t::Right);
ASSERT_EQ(encoders->getHallActive(), Direction_t::Right);
ASSERT_EQ(encoders->getPosition(), 227);
ASSERT_EQ(encoders->getCarriage(), Carriage_t::NoCarriage);
ASSERT_EQ(encoders->getCarriage(), Carriage_t::Knit);
}

// requires FILTER_R_MIN != 0
TEST_F(EncodersTest, test_encA_falling_set_K_carriage_KH910) {
encoders->init(Machine_t::Kh910);
ASSERT_TRUE(encoders->getMachineType() == Machine_t::Kh910);

// Create a rising edge
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_A)).WillOnce(Return(true));
EXPECT_CALL(*arduinoMock, digitalRead(ENC_PIN_B));
EXPECT_CALL(*arduinoMock, analogRead(EOL_PIN_L));
EXPECT_CALL(*arduinoMock, analogRead(EOL_PIN_L))
.WillOnce(Return(FILTER_R_MIN[static_cast<int8_t>(encoders->getMachineType())] + 1));
encoders->encA_interrupt();

// falling edge
Expand Down

0 comments on commit 163db4f

Please sign in to comment.