Browse Source

Adjust comments, spacing

Scott Lahteine 8 years ago
parent
commit
2c2688d7ad
1 changed files with 13 additions and 13 deletions
  1. 13
    13
      Marlin/Marlin_main.cpp

+ 13
- 13
Marlin/Marlin_main.cpp View File

1372
       // SERIAL_ECHOLNPAIR(" Y:", homeposition[Y_AXIS]);
1372
       // SERIAL_ECHOLNPAIR(" Y:", homeposition[Y_AXIS]);
1373
 
1373
 
1374
       /**
1374
       /**
1375
-       * Works out real Homeposition angles using inverse kinematics,
1376
-       * and calculates homing offset using forward kinematics
1375
+       * Get Home position SCARA arm angles using inverse kinematics,
1376
+       * and calculate homing offset using forward kinematics
1377
        */
1377
        */
1378
       inverse_kinematics(homeposition);
1378
       inverse_kinematics(homeposition);
1379
       forward_kinematics_SCARA(delta[A_AXIS], delta[B_AXIS]);
1379
       forward_kinematics_SCARA(delta[A_AXIS], delta[B_AXIS]);
2030
         SERIAL_ECHOLNPGM(")");
2030
         SERIAL_ECHOLNPGM(")");
2031
       }
2031
       }
2032
     #endif
2032
     #endif
2033
+
2033
     feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S;
2034
     feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S;
2035
+
2036
+    // Move the probe to the given XY
2034
     do_blocking_move_to_xy(x - (X_PROBE_OFFSET_FROM_EXTRUDER), y - (Y_PROBE_OFFSET_FROM_EXTRUDER));
2037
     do_blocking_move_to_xy(x - (X_PROBE_OFFSET_FROM_EXTRUDER), y - (Y_PROBE_OFFSET_FROM_EXTRUDER));
2035
 
2038
 
2036
     if (DEPLOY_PROBE()) return NAN;
2039
     if (DEPLOY_PROBE()) return NAN;
2167
 #endif // AUTO_BED_LEVELING_NONLINEAR
2170
 #endif // AUTO_BED_LEVELING_NONLINEAR
2168
 
2171
 
2169
 /**
2172
 /**
2170
- * Home an individual axis
2173
+ * Home an individual linear axis
2171
  */
2174
  */
2172
 
2175
 
2173
 static void do_homing_move(AxisEnum axis, float where, float fr_mm_s = 0.0) {
2176
 static void do_homing_move(AxisEnum axis, float where, float fr_mm_s = 0.0) {
3328
       return;
3331
       return;
3329
     }
3332
     }
3330
 
3333
 
3331
-    bool dryrun = code_seen('D');
3332
-    bool stow_probe_after_each = code_seen('E');
3334
+    bool dryrun = code_seen('D'),
3335
+         stow_probe_after_each = code_seen('E');
3333
 
3336
 
3334
     #if ENABLED(AUTO_BED_LEVELING_GRID)
3337
     #if ENABLED(AUTO_BED_LEVELING_GRID)
3335
 
3338
 
3418
       #endif // !DELTA
3421
       #endif // !DELTA
3419
 
3422
 
3420
       // Inform the planner about the new coordinates
3423
       // Inform the planner about the new coordinates
3421
-      // (This is probably not needed here)
3422
       SYNC_PLAN_POSITION_KINEMATIC();
3424
       SYNC_PLAN_POSITION_KINEMATIC();
3423
     }
3425
     }
3424
 
3426
 
3790
  * G92: Set current position to given X Y Z E
3792
  * G92: Set current position to given X Y Z E
3791
  */
3793
  */
3792
 inline void gcode_G92() {
3794
 inline void gcode_G92() {
3793
-  bool didE = code_seen('E');
3795
+  bool didXYZ = false,
3796
+       didE = code_seen('E');
3794
 
3797
 
3795
   if (!didE) stepper.synchronize();
3798
   if (!didE) stepper.synchronize();
3796
 
3799
 
3797
-  bool didXYZ = false;
3798
   LOOP_XYZE(i) {
3800
   LOOP_XYZE(i) {
3799
     if (code_seen(axis_codes[i])) {
3801
     if (code_seen(axis_codes[i])) {
3800
       float p = current_position[i],
3802
       float p = current_position[i],
4179
     if (verbose_level > 2)
4181
     if (verbose_level > 2)
4180
       SERIAL_PROTOCOLLNPGM("Positioning the probe...");
4182
       SERIAL_PROTOCOLLNPGM("Positioning the probe...");
4181
 
4183
 
4182
-    // we don't do bed level correction in M48 because we want the raw data when we probe
4184
+    // Disable bed level correction in M48 because we want the raw data when we probe
4183
     #if ENABLED(AUTO_BED_LEVELING_FEATURE)
4185
     #if ENABLED(AUTO_BED_LEVELING_FEATURE)
4184
       reset_bed_level();
4186
       reset_bed_level();
4185
     #endif
4187
     #endif
5776
 }
5778
 }
5777
 
5779
 
5778
 #if ENABLED(MORGAN_SCARA)
5780
 #if ENABLED(MORGAN_SCARA)
5781
+
5779
   bool SCARA_move_to_cal(uint8_t delta_a, uint8_t delta_b) {
5782
   bool SCARA_move_to_cal(uint8_t delta_a, uint8_t delta_b) {
5780
-    //SoftEndsEnabled = false;              // Ignore soft endstops during calibration
5781
-    //SERIAL_ECHOLNPGM(" Soft endstops disabled");
5782
     if (IsRunning()) {
5783
     if (IsRunning()) {
5783
       //gcode_get_destination(); // For X Y Z E F
5784
       //gcode_get_destination(); // For X Y Z E F
5784
       forward_kinematics_SCARA(delta_a, delta_b);
5785
       forward_kinematics_SCARA(delta_a, delta_b);
5786
       destination[Y_AXIS] = cartes[Y_AXIS];
5787
       destination[Y_AXIS] = cartes[Y_AXIS];
5787
       destination[Z_AXIS] = current_position[Z_AXIS];
5788
       destination[Z_AXIS] = current_position[Z_AXIS];
5788
       prepare_move_to_destination();
5789
       prepare_move_to_destination();
5789
-      //ok_to_send();
5790
       return true;
5790
       return true;
5791
     }
5791
     }
5792
     return false;
5792
     return false;
7977
     mesh_line_to_destination(fr_mm_s, x_splits, y_splits);
7977
     mesh_line_to_destination(fr_mm_s, x_splits, y_splits);
7978
   }
7978
   }
7979
 
7979
 
7980
-#endif  // MESH_BED_LEVELING
7980
+#endif // MESH_BED_LEVELING
7981
 
7981
 
7982
 #if IS_KINEMATIC
7982
 #if IS_KINEMATIC
7983
 
7983
 

Loading…
Cancel
Save