Skip to content
Snippets Groups Projects
Commit 936b3d58 authored by Jake Read's avatar Jake Read
Browse files

write / plumb segmentAcks, segmentCompleteMsgs, and run first full queue

parent 3087001f
No related branches found
No related tags found
No related merge requests found
Subproject commit be9a5a919bc9c6324f4ce6dcdfccac6837b659df Subproject commit d1e3aafd55d1fa784b6f05fce71ee70e5630b3d7
...@@ -139,12 +139,13 @@ EP_ONDATA_RESPONSES onHaltInData(uint8_t* data, uint16_t len){ ...@@ -139,12 +139,13 @@ EP_ONDATA_RESPONSES onHaltInData(uint8_t* data, uint16_t len){
Endpoint haltInEP(&osap, "haltIn", onHaltInData); Endpoint haltInEP(&osap, "haltIn", onHaltInData);
// -------------------------------------------------------- 6, 7: Outputs // -------------------------------------------------------- 6, 7, 8: Outputs
Endpoint queueAckOutEP(&osap, "queueAckOut");
Endpoint haltOutEP(&osap, "haltOut"); Endpoint haltOutEP(&osap, "haltOut");
Endpoint segmentAckOutEP(&osap, "segmentAckOut");
Endpoint segmentCompleteOutEP(&osap, "segmentCompleteOut");
// -------------------------------------------------------- 8: Motor Settings // -------------------------------------------------------- 9: Motor Settings
uint8_t axisPick = 0; uint8_t axisPick = 0;
boolean invert = false; boolean invert = false;
...@@ -205,10 +206,15 @@ void loop() { ...@@ -205,10 +206,15 @@ void loop() {
if(axlDataLen){ if(axlDataLen){
haltOutEP.write(axlData, axlDataLen); haltOutEP.write(axlData, axlDataLen);
} }
// check for on-queue-completion info... // check for queueAck info...
axlDataLen = axl_getQueueAck(axlData); axlDataLen = axl_getSegmentAckMsg(axlData);
if(axlDataLen){ if(axlDataLen){
queueAckOutEP.write(axlData, axlDataLen); segmentAckOutEP.write(axlData, axlDataLen);
}
// check for queueMoveComplete
axlDataLen = axl_getSegmentCompleteMsg(axlData);
if(axlDataLen){
segmentCompleteOutEP.write(axlData, axlDataLen);
} }
// refresh stepper hw, // refresh stepper hw,
stepper_hw->dacRefresh(); stepper_hw->dacRefresh();
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment