Skip to content

Commit

Permalink
Merge pull request #1717 from thinkyhead/fixup_warnings
Browse files Browse the repository at this point in the history
Fixup warnings
  • Loading branch information
thinkyhead committed Mar 28, 2015
2 parents b14be72 + 29a713e commit f47fc87
Show file tree
Hide file tree
Showing 21 changed files with 435 additions and 362 deletions.
4 changes: 1 addition & 3 deletions Marlin/ConfigurationStore.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -263,8 +263,6 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, dummy);
}

int storageSize = i;

char ver2[4] = EEPROM_VERSION;
int j = EEPROM_OFFSET;
EEPROM_WRITE_VAR(j, ver2); // validate data
Expand Down Expand Up @@ -446,7 +444,7 @@ void Config_ResetDefault() {
float tmp1[] = DEFAULT_AXIS_STEPS_PER_UNIT;
float tmp2[] = DEFAULT_MAX_FEEDRATE;
long tmp3[] = DEFAULT_MAX_ACCELERATION;
for (int i = 0; i < NUM_AXIS; i++) {
for (uint16_t i = 0; i < NUM_AXIS; i++) {
axis_steps_per_unit[i] = tmp1[i];
max_feedrate[i] = tmp2[i];
max_acceleration_units_per_sq_second[i] = tmp3[i];
Expand Down
165 changes: 75 additions & 90 deletions Marlin/Marlin_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -388,16 +388,20 @@ const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
static float destination[NUM_AXIS] = { 0, 0, 0, 0 };

static float offset[3] = { 0, 0, 0 };
static bool home_all_axis = true;

#ifndef DELTA
static bool home_all_axis = true;
#endif

static float feedrate = 1500.0, next_feedrate, saved_feedrate;
static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0;

static bool relative_mode = false; //Determines Absolute or Relative Coordinates

static char cmdbuffer[BUFSIZE][MAX_CMD_SIZE];
#ifdef SDSUPPORT
static bool fromsd[BUFSIZE];
#endif //!SDSUPPORT
static bool fromsd[BUFSIZE];
#endif
static int bufindr = 0;
static int bufindw = 0;
static int buflen = 0;
Expand Down Expand Up @@ -933,24 +937,22 @@ void get_command()

}


float code_value()
{
float code_value() {
float ret;
char *e = strchr(strchr_pointer, 'E');
if (e != NULL) *e = 0;
ret = strtod(strchr_pointer+1, NULL);
if (e != NULL) *e = 'E';
if (e) {
*e = 0;
ret = strtod(strchr_pointer+1, NULL);
*e = 'E';
}
else
ret = strtod(strchr_pointer+1, NULL);
return ret;
}

long code_value_long()
{
return (strtol(strchr_pointer + 1, NULL, 10));
}
long code_value_long() { return (strtol(strchr_pointer + 1, NULL, 10)); }

bool code_seen(char code)
{
bool code_seen(char code) {
strchr_pointer = strchr(cmdbuffer[bufindr], code);
return (strchr_pointer != NULL); //Return True if a character was found
}
Expand Down Expand Up @@ -1009,76 +1011,70 @@ XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
#endif //DUAL_X_CARRIAGE

static void axis_is_at_home(int axis) {
#ifdef DUAL_X_CARRIAGE
if (axis == X_AXIS) {
if (active_extruder != 0) {
current_position[X_AXIS] = x_home_pos(active_extruder);
min_pos[X_AXIS] = X2_MIN_POS;
max_pos[X_AXIS] = max(extruder_offset[X_AXIS][1], X2_MAX_POS);
return;
}
else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && active_extruder == 0) {
current_position[X_AXIS] = base_home_pos(X_AXIS) + home_offset[X_AXIS];
min_pos[X_AXIS] = base_min_pos(X_AXIS) + home_offset[X_AXIS];
max_pos[X_AXIS] = min(base_max_pos(X_AXIS) + home_offset[X_AXIS],
max(extruder_offset[X_AXIS][1], X2_MAX_POS) - duplicate_extruder_x_offset);
return;

#ifdef DUAL_X_CARRIAGE
if (axis == X_AXIS) {
if (active_extruder != 0) {
current_position[X_AXIS] = x_home_pos(active_extruder);
min_pos[X_AXIS] = X2_MIN_POS;
max_pos[X_AXIS] = max(extruder_offset[X_AXIS][1], X2_MAX_POS);
return;
}
else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) {
current_position[X_AXIS] = base_home_pos(X_AXIS) + home_offset[X_AXIS];
min_pos[X_AXIS] = base_min_pos(X_AXIS) + home_offset[X_AXIS];
max_pos[X_AXIS] = min(base_max_pos(X_AXIS) + home_offset[X_AXIS],
max(extruder_offset[X_AXIS][1], X2_MAX_POS) - duplicate_extruder_x_offset);
return;
}
}
}
#endif
#ifdef SCARA
float homeposition[3];
char i;

if (axis < 2)
{
#endif

#ifdef SCARA
float homeposition[3];

for (i=0; i<3; i++)
{
homeposition[i] = base_home_pos(i);
}
// SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]);
// SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]);
// Works out real Homeposition angles using inverse kinematics,
// and calculates homing offset using forward kinematics
calculate_delta(homeposition);
if (axis < 2) {

for (int i = 0; i < 3; i++) homeposition[i] = base_home_pos(i);

// SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]);
// SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]);
// Works out real Homeposition angles using inverse kinematics,
// and calculates homing offset using forward kinematics
calculate_delta(homeposition);

// SERIAL_ECHOPGM("base Theta= "); SERIAL_ECHO(delta[X_AXIS]);
// SERIAL_ECHOPGM(" base Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
// SERIAL_ECHOPGM("base Theta= "); SERIAL_ECHO(delta[X_AXIS]);
// SERIAL_ECHOPGM(" base Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);

for (i=0; i<2; i++)
{
delta[i] -= home_offset[i];
}
for (int i = 0; i < 2; i++) delta[i] -= home_offset[i];

// SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(home_offset[X_AXIS]);
// SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(home_offset[Y_AXIS]);
// SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]);
// SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
// SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(home_offset[X_AXIS]);
// SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(home_offset[Y_AXIS]);
// SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]);
// SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);

calculate_SCARA_forward_Transform(delta);
calculate_SCARA_forward_Transform(delta);

// SERIAL_ECHOPGM("Delta X="); SERIAL_ECHO(delta[X_AXIS]);
// SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]);
// SERIAL_ECHOPGM("Delta X="); SERIAL_ECHO(delta[X_AXIS]);
// SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]);

current_position[axis] = delta[axis];
current_position[axis] = delta[axis];

// SCARA home positions are based on configuration since the actual limits are determined by the
// inverse kinematic transform.
min_pos[axis] = base_min_pos(axis); // + (delta[axis] - base_home_pos(axis));
max_pos[axis] = base_max_pos(axis); // + (delta[axis] - base_home_pos(axis));
}
else
{
// SCARA home positions are based on configuration since the actual limits are determined by the
// inverse kinematic transform.
min_pos[axis] = base_min_pos(axis); // + (delta[axis] - base_home_pos(axis));
max_pos[axis] = base_max_pos(axis); // + (delta[axis] - base_home_pos(axis));
}
else {
current_position[axis] = base_home_pos(axis) + home_offset[axis];
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
}
#else
current_position[axis] = base_home_pos(axis) + home_offset[axis];
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
#endif
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
}
#else
current_position[axis] = base_home_pos(axis) + home_offset[axis];
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
#endif
}

#ifdef ENABLE_AUTO_BED_LEVELING
Expand Down Expand Up @@ -1233,10 +1229,6 @@ static void do_blocking_move_to(float x, float y, float z) {
feedrate = oldFeedRate;
}

static void do_blocking_move_relative(float offset_x, float offset_y, float offset_z) {
do_blocking_move_to(current_position[X_AXIS] + offset_x, current_position[Y_AXIS] + offset_y, current_position[Z_AXIS] + offset_z);
}

static void setup_for_endstop_move() {
saved_feedrate = feedrate;
saved_feedmultiply = feedmultiply;
Expand Down Expand Up @@ -2156,7 +2148,6 @@ inline void gcode_G28() {
}

int verbose_level = 1;
float x_tmp, y_tmp, z_tmp, real_z;

if (code_seen('V') || code_seen('v')) {
verbose_level = code_value_long();
Expand Down Expand Up @@ -2444,6 +2435,7 @@ inline void gcode_G28() {
// When the bed is uneven, this height must be corrected.
if (!dryrun)
{
float x_tmp, y_tmp, z_tmp, real_z;
real_z = float(st_get_position(Z_AXIS)) / axis_steps_per_unit[Z_AXIS]; //get the real Z (since the auto bed leveling is already correcting the plane)
x_tmp = current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER;
y_tmp = current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER;
Expand Down Expand Up @@ -4590,7 +4582,6 @@ inline void gcode_T() {
#if EXTRUDERS > 1
bool make_move = false;
#endif

if (code_seen('F')) {
#if EXTRUDERS > 1
make_move = true;
Expand Down Expand Up @@ -5193,16 +5184,10 @@ void ClearToSend()

void get_coordinates() {
for (int i = 0; i < NUM_AXIS; i++) {
float dest;
if (code_seen(axis_codes[i])) {
dest = code_value();
if (axis_relative_modes[i] || relative_mode)
dest += current_position[i];
}
if (code_seen(axis_codes[i]))
destination[i] = code_value() + (axis_relative_modes[i] || relative_mode ? current_position[i] : 0);
else
dest = current_position[i];

destination[i] = dest;
destination[i] = current_position[i];
}
if (code_seen('F')) {
next_feedrate = code_value();
Expand Down
2 changes: 1 addition & 1 deletion Marlin/cardreader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -489,7 +489,7 @@ void CardReader::updir() {
if (workDirDepth > 0) {
--workDirDepth;
workDir = workDirParents[0];
for (int d = 0; d < workDirDepth; d++)
for (uint16_t d = 0; d < workDirDepth; d++)
workDirParents[d] = workDirParents[d+1];
}
}
Expand Down
5 changes: 3 additions & 2 deletions Marlin/configurator/config/language.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@
#endif

#define PROTOCOL_VERSION "1.0"
#define FIRMWARE_URL "https://github.com/MarlinFirmware/Marlin"

#if MB(ULTIMAKER)|| MB(ULTIMAKER_OLD)|| MB(ULTIMAIN_2)
#define MACHINE_NAME "Ultimaker"
Expand All @@ -59,14 +58,16 @@
#define FIRMWARE_URL "http://www.bq.com/gb/downloads-prusa-i3-hephestos.html"
#else // Default firmware set to Mendel
#define MACHINE_NAME "Mendel"
#define FIRMWARE_URL "https://github.com/MarlinFirmware/Marlin"
#endif

#ifdef CUSTOM_MENDEL_NAME
#undef MACHINE_NAME
#define MACHINE_NAME CUSTOM_MENDEL_NAME
#endif

#ifndef MACHINE_UUID
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
#endif


Expand Down
6 changes: 1 addition & 5 deletions Marlin/example_configurations/SCARA/Configuration_adv.h
Original file line number Diff line number Diff line change
Expand Up @@ -275,13 +275,9 @@

#ifdef ADVANCE
#define EXTRUDER_ADVANCE_K .0

#define D_FILAMENT 1.75
#define STEPS_MM_E 1000
#define EXTRUSION_AREA (0.25 * D_FILAMENT * D_FILAMENT * 3.14159)
#define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS]/ EXTRUSION_AREA)

#endif // ADVANCE
#endif

// Arc interpretation settings:
#define MM_PER_ARC_SEGMENT 1
Expand Down
6 changes: 6 additions & 0 deletions Marlin/language.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,31 +40,37 @@
#define FIRMWARE_URL "https://github.com/MarlinFirmware/Marlin"

#if MB(ULTIMAKER)|| MB(ULTIMAKER_OLD)|| MB(ULTIMAIN_2)
#undef FIRMWARE_URL
#define MACHINE_NAME "Ultimaker"
#define FIRMWARE_URL "http://firmware.ultimaker.com"
#elif MB(RUMBA)
#define MACHINE_NAME "Rumba"
#elif MB(3DRAG)
#define MACHINE_NAME "3Drag"
#undef FIRMWARE_URL
#define FIRMWARE_URL "http://3dprint.elettronicain.it/"
#elif MB(K8200)
#define MACHINE_NAME "K8200"
#elif MB(5DPRINT)
#define MACHINE_NAME "Makibox"
#elif MB(SAV_MKI)
#define MACHINE_NAME "SAV MkI"
#undef FIRMWARE_URL
#define FIRMWARE_URL "https://github.com/fmalpartida/Marlin/tree/SAV-MkI-config"
#elif MB(WITBOX)
#define MACHINE_NAME "WITBOX"
#undef FIRMWARE_URL
#define FIRMWARE_URL "http://www.bq.com/gb/downloads-witbox.html"
#elif MB(HEPHESTOS)
#define MACHINE_NAME "HEPHESTOS"
#undef FIRMWARE_URL
#define FIRMWARE_URL "http://www.bq.com/gb/downloads-prusa-i3-hephestos.html"
#else // Default firmware set to Mendel
#define MACHINE_NAME "Mendel"
#endif

#ifdef CUSTOM_MENDEL_NAME
#undef MACHINE_NAME
#define MACHINE_NAME CUSTOM_MENDEL_NAME
#endif

Expand Down
9 changes: 9 additions & 0 deletions Marlin/pins.h
Original file line number Diff line number Diff line change
Expand Up @@ -127,10 +127,13 @@
#define _E3_PINS

#if EXTRUDERS > 1
#undef _E1_PINS
#define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN, HEATER_1_PIN, analogInputToDigitalPin(TEMP_1_PIN),
#if EXTRUDERS > 2
#undef _E2_PINS
#define _E2_PINS E2_STEP_PIN, E2_DIR_PIN, E2_ENABLE_PIN, HEATER_2_PIN, analogInputToDigitalPin(TEMP_2_PIN),
#if EXTRUDERS > 3
#undef _E3_PINS
#define _E3_PINS E3_STEP_PIN, E3_DIR_PIN, E3_ENABLE_PIN, HEATER_3_PIN, analogInputToDigitalPin(TEMP_3_PIN),
#endif
#endif
Expand Down Expand Up @@ -167,12 +170,18 @@
#endif

#ifdef DISABLE_MAX_ENDSTOPS
#undef X_MAX_PIN
#undef Y_MAX_PIN
#undef Z_MAX_PIN
#define X_MAX_PIN -1
#define Y_MAX_PIN -1
#define Z_MAX_PIN -1
#endif

#ifdef DISABLE_MIN_ENDSTOPS
#undef X_MIN_PIN
#undef Y_MIN_PIN
#undef Z_MIN_PIN
#define X_MIN_PIN -1
#define Y_MIN_PIN -1
#define Z_MIN_PIN -1
Expand Down
Loading

0 comments on commit f47fc87

Please sign in to comment.