@@ -106,7 +106,7 @@ void init_motors() {
106106 if (n_axis >= 2 ) {
107107 // this WILL be done better with settings
108108#ifdef Y_TRINAMIC_DRIVER
109- # if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
109+ # if (Y_TRINAMIC_DRIVER == 2130 || Y_TRINAMIC_DRIVER == 5160)
110110 {
111111 myMotor[Y_AXIS][0 ] =
112112 new Motors::TrinamicDriver (Y_AXIS, Y_STEP_PIN, Y_DIRECTION_PIN, Y_DISABLE_PIN, Y_CS_PIN, Y_TRINAMIC_DRIVER, Y_RSENSE);
@@ -132,7 +132,7 @@ void init_motors() {
132132#endif
133133
134134#ifdef Y2_TRINAMIC_DRIVER
135- # if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
135+ # if (Y2_TRINAMIC_DRIVER == 2130 || Y2_TRINAMIC_DRIVER == 5160)
136136 {
137137 myMotor[Y_AXIS][1 ] =
138138 new Motors::TrinamicDriver (Y2_AXIS, Y2_STEP_PIN, Y2_DIRECTION_PIN, Y2_DISABLE_PIN, Y2_CS_PIN, Y2_TRINAMIC_DRIVER, Y2_RSENSE);
@@ -160,7 +160,7 @@ void init_motors() {
160160 if (n_axis >= 3 ) {
161161 // this WILL be done better with settings
162162#ifdef Z_TRINAMIC_DRIVER
163- # if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
163+ # if (Z_TRINAMIC_DRIVER == 2130 || Z_TRINAMIC_DRIVER == 5160)
164164 {
165165 myMotor[Z_AXIS][0 ] =
166166 new Motors::TrinamicDriver (Z_AXIS, Z_STEP_PIN, Z_DIRECTION_PIN, Z_DISABLE_PIN, Z_CS_PIN, Z_TRINAMIC_DRIVER, Z_RSENSE);
@@ -186,7 +186,7 @@ void init_motors() {
186186#endif
187187
188188#ifdef Z2_TRINAMIC_DRIVER
189- # if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
189+ # if (Z2_TRINAMIC_DRIVER == 2130 || Z2_TRINAMIC_DRIVER == 5160)
190190 {
191191 myMotor[Z_AXIS][1 ] =
192192 new Motors::TrinamicDriver (Z2_AXIS, Z2_STEP_PIN, Z2_DIRECTION_PIN, Z2_DISABLE_PIN, Z2_CS_PIN, Z2_TRINAMIC_DRIVER, Z2_RSENSE);
@@ -214,9 +214,9 @@ void init_motors() {
214214 if (n_axis >= 4 ) {
215215 // this WILL be done better with settings
216216#ifdef A_TRINAMIC_DRIVER
217- # if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
217+ # if (A_TRINAMIC_DRIVER == 2130 || A_TRINAMIC_DRIVER == 5160)
218218 {
219- myMotor[A_AXIS][1 ] =
219+ myMotor[A_AXIS][0 ] =
220220 new Motors::TrinamicDriver (A_AXIS, A_STEP_PIN, A_DIRECTION_PIN, A_DISABLE_PIN, A_CS_PIN, A_TRINAMIC_DRIVER, A_RSENSE);
221221 }
222222# elif (A_TRINAMIC_DRIVER == 2208 || A_TRINAMIC_DRIVER == 2209)
@@ -240,7 +240,7 @@ void init_motors() {
240240#endif
241241
242242#ifdef A2_TRINAMIC_DRIVER
243- # if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
243+ # if (A2_TRINAMIC_DRIVER == 2130 || A2_TRINAMIC_DRIVER == 5160)
244244 {
245245 myMotor[A_AXIS][1 ] =
246246 new Motors::TrinamicDriver (A2_AXIS, A2_STEP_PIN, A2_DIRECTION_PIN, A2_DISABLE_PIN, A2_CS_PIN, A2_TRINAMIC_DRIVER, A2_RSENSE);
@@ -268,9 +268,9 @@ void init_motors() {
268268 if (n_axis >= 5 ) {
269269 // this WILL be done better with settings
270270#ifdef B_TRINAMIC_DRIVER
271- # if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
271+ # if (B_TRINAMIC_DRIVER == 2130 || B_TRINAMIC_DRIVER == 5160)
272272 {
273- myMotor[B_AXIS][1 ] =
273+ myMotor[B_AXIS][0 ] =
274274 new Motors::TrinamicDriver (B_AXIS, B_STEP_PIN, B_DIRECTION_PIN, B_DISABLE_PIN, B_CS_PIN, B_TRINAMIC_DRIVER, B_RSENSE);
275275 }
276276# elif (B_TRINAMIC_DRIVER == 2208 || B_TRINAMIC_DRIVER == 2209)
@@ -294,7 +294,7 @@ void init_motors() {
294294#endif
295295
296296#ifdef B2_TRINAMIC_DRIVER
297- # if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
297+ # if (B2_TRINAMIC_DRIVER == 2130 || B2_TRINAMIC_DRIVER == 5160)
298298 {
299299 myMotor[B_AXIS][1 ] =
300300 new Motors::TrinamicDriver (B2_AXIS, B2_STEP_PIN, B2_DIRECTION_PIN, B2_DISABLE_PIN, B2_CS_PIN, B2_TRINAMIC_DRIVER, B2_RSENSE);
@@ -322,9 +322,9 @@ void init_motors() {
322322 if (n_axis >= 6 ) {
323323 // this WILL be done better with settings
324324#ifdef C_TRINAMIC_DRIVER
325- # if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
325+ # if (C_TRINAMIC_DRIVER == 2130 || C_TRINAMIC_DRIVER == 5160)
326326 {
327- myMotor[C_AXIS][1 ] =
327+ myMotor[C_AXIS][0 ] =
328328 new Motors::TrinamicDriver (C_AXIS, C_STEP_PIN, C_DIRECTION_PIN, C_DISABLE_PIN, C_CS_PIN, C_TRINAMIC_DRIVER, C_RSENSE);
329329 }
330330# elif (C_TRINAMIC_DRIVER == 2208 || C_TRINAMIC_DRIVER == 2209)
@@ -348,7 +348,7 @@ void init_motors() {
348348#endif
349349
350350#ifdef C2_TRINAMIC_DRIVER
351- # if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
351+ # if (C2_TRINAMIC_DRIVER == 2130 || C2_TRINAMIC_DRIVER == 5160)
352352 {
353353 myMotor[C_AXIS][1 ] =
354354 new Motors::TrinamicDriver (C2_AXIS, C2_STEP_PIN, C2_DIRECTION_PIN, C2_DISABLE_PIN, C2_CS_PIN, C2_TRINAMIC_DRIVER, C2_RSENSE);
0 commit comments