References are better for array args

This commit is contained in:
Scott Lahteine 2017-12-09 02:10:54 -06:00
parent 125c572d97
commit 73e32925e4
13 changed files with 48 additions and 42 deletions

View File

@ -121,7 +121,7 @@ script:
- opt_enable ULTIMAKERCONTROLLER SDSUPPORT - opt_enable ULTIMAKERCONTROLLER SDSUPPORT
- opt_enable PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PCA9632 USE_XMAX_PLUG - opt_enable PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PCA9632 USE_XMAX_PLUG
- opt_enable_adv BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS - opt_enable_adv BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS
- opt_enable_adv ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE LCD_INFO_MENU - opt_enable_adv ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE LCD_INFO_MENU M114_DETAIL
- opt_set_adv PWM_MOTOR_CURRENT {1300,1300,1250} - opt_set_adv PWM_MOTOR_CURRENT {1300,1300,1250}
- opt_set_adv I2C_SLAVE_ADDRESS 63 - opt_set_adv I2C_SLAVE_ADDRESS 63
- build_marlin_pio ${TRAVIS_BUILD_DIR} ${TEST_PLATFORM} - build_marlin_pio ${TRAVIS_BUILD_DIR} ${TEST_PLATFORM}

View File

@ -316,7 +316,7 @@ class unified_bed_leveling {
} }
static bool prepare_segmented_line_to(const float rtarget[XYZE], const float &feedrate); static bool prepare_segmented_line_to(const float rtarget[XYZE], const float &feedrate);
static void line_to_destination_cartesian(const float &fr, uint8_t e); static void line_to_destination_cartesian(const float &fr, const uint8_t e);
#define _CMPZ(a,b) (z_values[a][b] == z_values[a][b+1]) #define _CMPZ(a,b) (z_values[a][b] == z_values[a][b+1])
#define CMPZ(a) (_CMPZ(a, 0) && _CMPZ(a, 1)) #define CMPZ(a) (_CMPZ(a, 0) && _CMPZ(a, 1))

View File

@ -92,7 +92,7 @@
} }
void unified_bed_leveling::line_to_destination_cartesian(const float &feed_rate, uint8_t extruder) { void unified_bed_leveling::line_to_destination_cartesian(const float &feed_rate, const uint8_t extruder) {
/** /**
* Much of the nozzle movement will be within the same cell. So we will do as little computation * Much of the nozzle movement will be within the same cell. So we will do as little computation
* as possible to determine if this is the case. If this move is within the same cell, we will * as possible to determine if this is the case. If this move is within the same cell, we will
@ -475,7 +475,7 @@
// We don't want additional apply_leveling() performed by regular buffer_line or buffer_line_kinematic, // We don't want additional apply_leveling() performed by regular buffer_line or buffer_line_kinematic,
// so we call _buffer_line directly here. Per-segmented leveling and kinematics performed first. // so we call _buffer_line directly here. Per-segmented leveling and kinematics performed first.
inline void _O2 ubl_buffer_segment_raw(const float raw[XYZE], const float &fr) { inline void _O2 ubl_buffer_segment_raw(const float (&raw)[XYZE], const float &fr) {
#if ENABLED(DELTA) // apply delta inverse_kinematics #if ENABLED(DELTA) // apply delta inverse_kinematics

View File

@ -261,16 +261,16 @@ void move_to(const float &rx, const float &ry, const float &z, const float &e_de
set_destination_from_current(); set_destination_from_current();
} }
FORCE_INLINE void move_to(const float where[XYZE], const float &de) { move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], de); } FORCE_INLINE void move_to(const float (&where)[XYZE], const float &de) { move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], de); }
void retract_filament(const float where[XYZE]) { void retract_filament(const float (&where)[XYZE]) {
if (!g26_retracted) { // Only retract if we are not already retracted! if (!g26_retracted) { // Only retract if we are not already retracted!
g26_retracted = true; g26_retracted = true;
move_to(where, -1.0 * g26_retraction_multiplier); move_to(where, -1.0 * g26_retraction_multiplier);
} }
} }
void recover_filament(const float where[XYZE]) { void recover_filament(const float (&where)[XYZE]) {
if (g26_retracted) { // Only un-retract if we are retracted. if (g26_retracted) { // Only un-retract if we are retracted.
move_to(where, 1.2 * g26_retraction_multiplier); move_to(where, 1.2 * g26_retraction_multiplier);
g26_retracted = false; g26_retracted = false;

View File

@ -28,7 +28,7 @@
#if ENABLED(M114_DETAIL) #if ENABLED(M114_DETAIL)
void report_xyze(const float pos[XYZE], const uint8_t n = 4, const uint8_t precision = 3) { void report_xyze(const float pos[], const uint8_t n = 4, const uint8_t precision = 3) {
char str[12]; char str[12];
for (uint8_t i = 0; i < n; i++) { for (uint8_t i = 0; i < n; i++) {
SERIAL_CHAR(' '); SERIAL_CHAR(' ');
@ -39,7 +39,7 @@
SERIAL_EOL(); SERIAL_EOL();
} }
inline void report_xyz(const float pos[XYZ]) { report_xyze(pos, 3); } inline void report_xyz(const float pos[]) { report_xyze(pos, 3); }
void report_current_position_detail() { void report_current_position_detail() {

View File

@ -44,9 +44,9 @@
* options for G2/G3 arc generation. In future these options may be GCode tunable. * options for G2/G3 arc generation. In future these options may be GCode tunable.
*/ */
void plan_arc( void plan_arc(
float rtarget[XYZE], // Destination position const float (&cart)[XYZE], // Destination position
float *offset, // Center of rotation relative to current_position const float (&offset)[2], // Center of rotation relative to current_position
uint8_t clockwise // Clockwise? const uint8_t clockwise // Clockwise?
) { ) {
#if ENABLED(CNC_WORKSPACE_PLANES) #if ENABLED(CNC_WORKSPACE_PLANES)
AxisEnum p_axis, q_axis, l_axis; AxisEnum p_axis, q_axis, l_axis;
@ -66,10 +66,10 @@ void plan_arc(
const float radius = HYPOT(r_P, r_Q), const float radius = HYPOT(r_P, r_Q),
center_P = current_position[p_axis] - r_P, center_P = current_position[p_axis] - r_P,
center_Q = current_position[q_axis] - r_Q, center_Q = current_position[q_axis] - r_Q,
rt_X = rtarget[p_axis] - center_P, rt_X = cart[p_axis] - center_P,
rt_Y = rtarget[q_axis] - center_Q, rt_Y = cart[q_axis] - center_Q,
linear_travel = rtarget[l_axis] - current_position[l_axis], linear_travel = cart[l_axis] - current_position[l_axis],
extruder_travel = rtarget[E_AXIS] - current_position[E_AXIS]; extruder_travel = cart[E_AXIS] - current_position[E_AXIS];
// CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required. // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required.
float angular_travel = ATAN2(r_P * rt_Y - r_Q * rt_X, r_P * rt_X + r_Q * rt_Y); float angular_travel = ATAN2(r_P * rt_Y - r_Q * rt_X, r_P * rt_X + r_Q * rt_Y);
@ -77,7 +77,7 @@ void plan_arc(
if (clockwise) angular_travel -= RADIANS(360); if (clockwise) angular_travel -= RADIANS(360);
// Make a circle if the angular rotation is 0 and the target is current position // Make a circle if the angular rotation is 0 and the target is current position
if (angular_travel == 0 && current_position[p_axis] == rtarget[p_axis] && current_position[q_axis] == rtarget[q_axis]) if (angular_travel == 0 && current_position[p_axis] == cart[p_axis] && current_position[q_axis] == cart[q_axis])
angular_travel = RADIANS(360); angular_travel = RADIANS(360);
const float mm_of_travel = HYPOT(angular_travel * radius, FABS(linear_travel)); const float mm_of_travel = HYPOT(angular_travel * radius, FABS(linear_travel));
@ -177,7 +177,7 @@ void plan_arc(
} }
// Ensure last segment arrives at target location. // Ensure last segment arrives at target location.
planner.buffer_line_kinematic(rtarget, fr_mm_s, active_extruder); planner.buffer_line_kinematic(cart, fr_mm_s, active_extruder);
// As far as the parser is concerned, the position is now == target. In reality the // As far as the parser is concerned, the position is now == target. In reality the
// motion control system might still be processing the action and the real tool position // motion control system might still be processing the action and the real tool position

View File

@ -27,7 +27,7 @@
#include "../../module/motion.h" #include "../../module/motion.h"
#include "../../module/planner_bezier.h" #include "../../module/planner_bezier.h"
void plan_cubic_move(const float offset[4]) { void plan_cubic_move(const float (&offset)[4]) {
cubic_b_spline(current_position, destination, offset, MMS_SCALED(feedrate_mm_s), active_extruder); cubic_b_spline(current_position, destination, offset, MMS_SCALED(feedrate_mm_s), active_extruder);
// As far as the parser is concerned, the position is now == destination. In reality the // As far as the parser is concerned, the position is now == destination. In reality the
@ -62,7 +62,7 @@ void GcodeSuite::G5() {
get_destination_from_command(); get_destination_from_command();
const float offset[] = { const float offset[4] = {
parser.linearval('I'), parser.linearval('I'),
parser.linearval('J'), parser.linearval('J'),
parser.linearval('P'), parser.linearval('P'),

View File

@ -517,13 +517,19 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
/** /**
* Prepare a linear move in a DELTA or SCARA setup. * Prepare a linear move in a DELTA or SCARA setup.
* *
* Called from prepare_move_to_destination as the
* default Delta/SCARA segmenter.
*
* This calls planner.buffer_line several times, adding * This calls planner.buffer_line several times, adding
* small incremental moves for DELTA or SCARA. * small incremental moves for DELTA or SCARA.
* *
* For Unified Bed Leveling (Delta or Segmented Cartesian) * For Unified Bed Leveling (Delta or Segmented Cartesian)
* the ubl.prepare_segmented_line_to method replaces this. * the ubl.prepare_segmented_line_to method replaces this.
*
* For Auto Bed Leveling (Bilinear) with SEGMENT_LEVELED_MOVES
* this is replaced by segmented_line_to_destination below.
*/ */
inline bool prepare_kinematic_move_to(float rtarget[XYZE]) { inline bool prepare_kinematic_move_to(const float (&rtarget)[XYZE]) {
// Get the top feedrate of the move in the XY plane // Get the top feedrate of the move in the XY plane
const float _feedrate_mm_s = MMS_SCALED(feedrate_mm_s); const float _feedrate_mm_s = MMS_SCALED(feedrate_mm_s);

View File

@ -1466,18 +1466,18 @@ void Planner::_set_position_mm(const float &a, const float &b, const float &c, c
ZERO(previous_speed); ZERO(previous_speed);
} }
void Planner::set_position_mm_kinematic(const float position[NUM_AXIS]) { void Planner::set_position_mm_kinematic(const float (&cart)[XYZE]) {
#if PLANNER_LEVELING #if PLANNER_LEVELING
float lpos[XYZ] = { position[X_AXIS], position[Y_AXIS], position[Z_AXIS] }; float raw[XYZ] = { cart[X_AXIS], cart[Y_AXIS], cart[Z_AXIS] };
apply_leveling(lpos); apply_leveling(raw);
#else #else
const float * const lpos = position; const float (&raw)[XYZE] = cart;
#endif #endif
#if IS_KINEMATIC #if IS_KINEMATIC
inverse_kinematics(lpos); inverse_kinematics(raw);
_set_position_mm(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], position[E_AXIS]); _set_position_mm(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], cart[E_AXIS]);
#else #else
_set_position_mm(lpos[X_AXIS], lpos[Y_AXIS], lpos[Z_AXIS], position[E_AXIS]); _set_position_mm(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], cart[E_AXIS]);
#endif #endif
} }

View File

@ -356,7 +356,7 @@ class Planner {
* as it will be given to the planner and steppers. * as it will be given to the planner and steppers.
*/ */
static void apply_leveling(float &rx, float &ry, float &rz); static void apply_leveling(float &rx, float &ry, float &rz);
static void apply_leveling(float raw[XYZ]) { apply_leveling(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS]); } static void apply_leveling(float (&raw)[XYZ]) { apply_leveling(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS]); }
static void unapply_leveling(float raw[XYZ]); static void unapply_leveling(float raw[XYZ]);
#else #else
@ -421,12 +421,12 @@ class Planner {
* fr_mm_s - (target) speed of the move (mm/s) * fr_mm_s - (target) speed of the move (mm/s)
* extruder - target extruder * extruder - target extruder
*/ */
FORCE_INLINE static void buffer_line_kinematic(const float cart[XYZE], const float &fr_mm_s, const uint8_t extruder) { FORCE_INLINE static void buffer_line_kinematic(const float (&cart)[XYZE], const float &fr_mm_s, const uint8_t extruder) {
#if PLANNER_LEVELING #if PLANNER_LEVELING
float raw[XYZ] = { cart[X_AXIS], cart[Y_AXIS], cart[Z_AXIS] }; float raw[XYZ] = { cart[X_AXIS], cart[Y_AXIS], cart[Z_AXIS] };
apply_leveling(raw); apply_leveling(raw);
#else #else
const float * const raw = cart; const float (&raw)[XYZE] = cart;
#endif #endif
#if IS_KINEMATIC #if IS_KINEMATIC
inverse_kinematics(raw); inverse_kinematics(raw);
@ -451,7 +451,7 @@ class Planner {
#endif #endif
_set_position_mm(rx, ry, rz, e); _set_position_mm(rx, ry, rz, e);
} }
static void set_position_mm_kinematic(const float position[NUM_AXIS]); static void set_position_mm_kinematic(const float (&cart)[XYZE]);
static void set_position_mm(const AxisEnum axis, const float &v); static void set_position_mm(const AxisEnum axis, const float &v);
FORCE_INLINE static void set_z_position_mm(const float &z) { set_position_mm(Z_AXIS, z); } FORCE_INLINE static void set_z_position_mm(const float &z) { set_position_mm(Z_AXIS, z); }
FORCE_INLINE static void set_e_position_mm(const float &e) { set_position_mm(AxisEnum(E_AXIS), e); } FORCE_INLINE static void set_e_position_mm(const float &e) { set_position_mm(AxisEnum(E_AXIS), e); }

View File

@ -107,7 +107,7 @@ inline void do_probe_raise(const float z_raise) {
#elif ENABLED(Z_PROBE_ALLEN_KEY) #elif ENABLED(Z_PROBE_ALLEN_KEY)
FORCE_INLINE void do_blocking_move_to(const float raw[XYZ], const float &fr_mm_s) { FORCE_INLINE void do_blocking_move_to(const float (&raw)[XYZ], const float &fr_mm_s) {
do_blocking_move_to(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], fr_mm_s); do_blocking_move_to(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], fr_mm_s);
} }

View File

@ -1193,7 +1193,7 @@ void Stepper::set_e_position(const long &e) {
/** /**
* Get a stepper's position in steps. * Get a stepper's position in steps.
*/ */
long Stepper::position(AxisEnum axis) { long Stepper::position(const AxisEnum axis) {
CRITICAL_SECTION_START; CRITICAL_SECTION_START;
const long count_pos = count_position[axis]; const long count_pos = count_position[axis];
CRITICAL_SECTION_END; CRITICAL_SECTION_END;
@ -1204,7 +1204,7 @@ long Stepper::position(AxisEnum axis) {
* Get an axis position according to stepper position(s) * Get an axis position according to stepper position(s)
* For CORE machines apply translation from ABC to XYZ. * For CORE machines apply translation from ABC to XYZ.
*/ */
float Stepper::get_axis_position_mm(AxisEnum axis) { float Stepper::get_axis_position_mm(const AxisEnum axis) {
float axis_steps; float axis_steps;
#if IS_CORE #if IS_CORE
// Requesting one of the "core" axes? // Requesting one of the "core" axes?
@ -1242,7 +1242,7 @@ void Stepper::quick_stop() {
#endif #endif
} }
void Stepper::endstop_triggered(AxisEnum axis) { void Stepper::endstop_triggered(const AxisEnum axis) {
#if IS_CORE #if IS_CORE

View File

@ -183,7 +183,7 @@ class Stepper {
// //
// Get the position of a stepper, in steps // Get the position of a stepper, in steps
// //
static long position(AxisEnum axis); static long position(const AxisEnum axis);
// //
// Report the positions of the steppers, in steps // Report the positions of the steppers, in steps
@ -193,13 +193,13 @@ class Stepper {
// //
// Get the position (mm) of an axis based on stepper position(s) // Get the position (mm) of an axis based on stepper position(s)
// //
static float get_axis_position_mm(AxisEnum axis); static float get_axis_position_mm(const AxisEnum axis);
// //
// SCARA AB axes are in degrees, not mm // SCARA AB axes are in degrees, not mm
// //
#if IS_SCARA #if IS_SCARA
FORCE_INLINE static float get_axis_position_degrees(AxisEnum axis) { return get_axis_position_mm(axis); } FORCE_INLINE static float get_axis_position_degrees(const AxisEnum axis) { return get_axis_position_mm(axis); }
#endif #endif
// //
@ -221,7 +221,7 @@ class Stepper {
// //
// The direction of a single motor // The direction of a single motor
// //
FORCE_INLINE static bool motor_direction(AxisEnum axis) { return TEST(last_direction_bits, axis); } FORCE_INLINE static bool motor_direction(const AxisEnum axis) { return TEST(last_direction_bits, axis); }
#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM
static void digitalPotWrite(const int16_t address, const int16_t value); static void digitalPotWrite(const int16_t address, const int16_t value);
@ -263,12 +263,12 @@ class Stepper {
// //
// Handle a triggered endstop // Handle a triggered endstop
// //
static void endstop_triggered(AxisEnum axis); static void endstop_triggered(const AxisEnum axis);
// //
// Triggered position of an axis in mm (not core-savvy) // Triggered position of an axis in mm (not core-savvy)
// //
FORCE_INLINE static float triggered_position_mm(AxisEnum axis) { FORCE_INLINE static float triggered_position_mm(const AxisEnum axis) {
return endstops_trigsteps[axis] * planner.steps_to_mm[axis]; return endstops_trigsteps[axis] * planner.steps_to_mm[axis];
} }