def reverse_transform_vector(self, vec, cur_pos): """ Transform back from whatever """ ret_vec = np.copy(vec) if Path.axis_config == Path.AXIS_CONFIG_H_BELT: X = np.dot(Path.matrix_H, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_CORE_XY: X = np.dot(Path.matrix_XY_inv, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_DELTA: # Find the next column positions self.end_ABC = self.start_ABC + vec[:3] # We have the column translations and need to find what that # represents in cartesian. start_xyz = Delta.forward_kinematics2(self.start_ABC[0], self.start_ABC[1], self.start_ABC[2]) end_xyz = Delta.forward_kinematics2(self.end_ABC[0], self.end_ABC[1], self.end_ABC[2]) ret_vec[:3] = end_xyz - start_xyz # Apply Automatic bed compensation if self.use_bed_matrix: ret_vec[:3] = np.dot(Path.matrix_bed_comp_inv, ret_vec[:3]) return ret_vec
def __init__(self, robot: str): # Thread-safe event flags self.program_stopped = Event() self.ignore_controller = Event() self._current_mode = 'off' self.controller = None self.already_connected = False self.controller_poll_rate = 5 self.mode_poll_rate = 0.1 self.mode_lock = RLock() self.lcd = LCD() # Preprocess string robot_str = robot.strip().lower() if robot_str == '6rus': self.robot = SixRUS(stepper_mode=1 / 32, step_delay=0.002) elif robot_str == 'quattro': self.robot = Quattro(stepper_mode=1 / 32, step_delay=0.002) elif robot_str == 'delta': self.robot = Delta(stepper_mode=1 / 32, step_delay=0.002) else: raise ValueError(f"Unknown robot type: {robot}") self.lcd.print_status(f'Started {robot}')
def transform_vector(self, vec, cur_pos): """ Transform vector to whatever coordinate system is used """ ret_vec = np.copy(vec) if Path.axis_config == Path.AXIS_CONFIG_H_BELT: X = np.dot(Path.matrix_H_inv, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_CORE_XY: X = np.dot(Path.matrix_XY, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_DELTA: # Subtract the current column positions if hasattr(self.prev, "end_ABC"): self.start_ABC = self.prev.end_ABC else: self.start_ABC = Delta.inverse_kinematics2(cur_pos[0], cur_pos[1], cur_pos[2]) # Find the next column positions self.end_ABC = Delta.inverse_kinematics2(cur_pos[0] + vec[0], cur_pos[1] + vec[1], cur_pos[2] + vec[2]) ret_vec[:3] = self.end_ABC - self.start_ABC # Apply Automatic bed compensation if self.use_bed_matrix: ret_vec[:3] = np.dot(Path.matrix_bed_comp, ret_vec[:3]) return ret_vec
def execute(self, g): if g.has_letter("L"): Delta.L = float(g.get_value_by_letter("L")) if g.has_letter("R"): Delta.r = float(g.get_value_by_letter("R")) if g.has_letter("S"): logging.info("M665 S (segments/second) specified, but not implemented.") #Recalcualte delta settings Delta.recalculate()
def execute(self, g): if g.has_letter("L"): Delta.L = float(g.get_value_by_letter("L")) if g.has_letter("R"): Delta.r = float(g.get_value_by_letter("R")) if g.has_letter("S"): logging.info( "M665 S (segments/second) specified, but not implemented.") #Recalcualte delta settings Delta.recalculate()
def Torrent(itorrent, dir1, dir2, idelta, dirD, files): torrent = opentorrent(itorrent) sfiles = [] d = 0 files = sortByFiles(files) for i in files: S = True df1 = os.path.join(dir1, i[0]) df2 = os.path.join(dir2, i[1]) if not os.path.isfile(df1): print("File not found: {}".format(i[0])) S = False if not os.path.isfile(df2): print("File not found: {}".format(i[1])) S = False if not fileintorr(torrent, i[0]): print("File not found in torrent: {}".format(i[0])) S = False if S: execute('xdelta3 -e -s "{}" "{}" "{}.delta"'.format(df1, df2, d)) sfiles.append({ 'file1': i[0], 'file2': i[1], 'delta': Delta("d.delta".format(d), idelta, i[0], i[1]) }) d += 1 CDelta(sfiles, dirD, dir2)
def execute(self, g): if g.has_letter("A"): if g.has_letter("B") or g.has_letter("C"): g.set_answer("Only 1 column can be set per M667 call.") return if g.has_letter("X"): Delta.Apxe = float(g.get_value_by_letter("X")) if g.has_letter("Y"): Delta.Apye = float(g.get_value_by_letter("Y")) if g.has_letter("R"): Delta.Aco = float(g.get_value_by_letter("R")) if g.has_letter("B"): if g.has_letter("A") or g.has_letter("C"): g.set_answer("Only 1 column can be set per M667 call.") return if g.has_letter("X"): Delta.Bpxe = float(g.get_value_by_letter("X")) if g.has_letter("Y"): Delta.Bpye = float(g.get_value_by_letter("Y")) if g.has_letter("R"): Delta.Bco = float(g.get_value_by_letter("R")) if g.has_letter("C"): if g.has_letter("B") or g.has_letter("A"): g.set_answer("Only 1 column can be set per M667 call.") return if g.has_letter("X"): Delta.Cpxe = float(g.get_value_by_letter("X")) if g.has_letter("Y"): Delta.Cpye = float(g.get_value_by_letter("Y")) if g.has_letter("R"): Delta.Cco = float(g.get_value_by_letter("R")) Delta.recalculate()
def home(self, axis): """ Home the given axis using endstops (min) """ logging.debug("homing " + str(axis)) # Home axis for core X,Y and H-Belt independently to avoid hardware # damages. if Path.axis_config == Path.AXIS_CONFIG_CORE_XY or \ Path.axis_config == Path.AXIS_CONFIG_H_BELT: for a in axis: self._home_internal(a) # For delta, switch to cartesian when homing elif Path.axis_config == Path.AXIS_CONFIG_DELTA: if 0 < len({"X", "Y", "Z"}.intersection(set(axis))) < 3: axis = list(set(axis).union({"X", "Y", "Z"})) # Deltas must home all axes. Path.axis_config = Path.AXIS_CONFIG_XY path_center, speed = self._home_internal(axis) Path.axis_config = Path.AXIS_CONFIG_DELTA # homing was performed in cartesian mode # need to convert back to delta Az = path_center['X'] Bz = path_center['Y'] Cz = path_center['Z'] z_offset = Delta.vertical_offset(Az,Bz,Cz) # vertical offset xyz = Delta.forward_kinematics2(Az, Bz, Cz) # effector position xyz[2] += z_offset path = {'X':xyz[0], 'Y':xyz[1], 'Z':xyz[2]} p = G92Path(path, speed) self.add_path(p) self.wait_until_done() else: self._home_internal(axis) # go to the designated home position self._go_to_home(axis) # Reset backlash compensation Path.backlash_reset() logging.debug("homing done for " + str(axis)) return
def home(self, axis): """ Home the given axis using endstops (min) """ logging.debug("homing " + str(axis)) # Home axis for core X,Y and H-Belt independently to avoid hardware # damages. if Path.axis_config == Path.AXIS_CONFIG_CORE_XY or \ Path.axis_config == Path.AXIS_CONFIG_H_BELT: for a in axis: self._home_internal(a) # For delta, switch to cartesian when homing elif Path.axis_config == Path.AXIS_CONFIG_DELTA: if 0 < len({"X", "Y", "Z"}.intersection(set(axis))) < 3: axis = list(set(axis).union({"X", "Y", "Z"})) # Deltas must home all axes. Path.axis_config = Path.AXIS_CONFIG_XY path_center, speed = self._home_internal(axis) Path.axis_config = Path.AXIS_CONFIG_DELTA # homing was performed in cartesian mode # need to convert back to delta Az = path_center['X'] Bz = path_center['Y'] Cz = path_center['Z'] z_offset = Delta.vertical_offset(Az,Bz,Cz) # vertical offset xyz = Delta.forward_kinematics2(Az, Bz, Cz) # effector position xyz[2] += z_offset path = {'X':xyz[0], 'Y':xyz[1], 'Z':xyz[2]} p = G92Path(path, speed) self.add_path(p) self.wait_until_done() else: # AXIS_CONFIG_XY self._home_internal(axis) # go to the designated home position self._go_to_home(axis) # Reset backlash compensation Path.backlash_reset() logging.debug("homing done for " + str(axis)) return
def transform_vector(self, vec, cur_pos): """ Transform vector to whatever coordinate system is used """ ret_vec = np.copy(vec) if Path.axis_config == Path.AXIS_CONFIG_H_BELT: X = np.dot(Path.matrix_H_inv, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_CORE_XY: X = np.dot(Path.matrix_XY, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_DELTA: # Subtract the current column positions start_ABC = Delta.inverse_kinematics(cur_pos[0], cur_pos[1], cur_pos[2]) # Find the next column positions end_ABC = Delta.inverse_kinematics(cur_pos[0] + vec[0], cur_pos[1] + vec[1], cur_pos[2] + vec[2]) ret_vec[:3] = end_ABC - start_ABC return ret_vec
def transform_vector(self, vec, cur_pos): """ Transform vector to whatever coordinate system is used """ ret_vec = np.copy(vec) if Path.axis_config == Path.AXIS_CONFIG_H_BELT: X = np.dot(Path.matrix_H_inv, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_CORE_XY: X = np.dot(Path.matrix_XY, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_DELTA: # Subtract the current column positions if hasattr(self.prev, "end_ABC"): self.start_ABC = self.prev.end_ABC else: self.start_ABC = Delta.inverse_kinematics2(cur_pos[0], cur_pos[1], cur_pos[2]) # Find the next column positions self.end_ABC = Delta.inverse_kinematics2(cur_pos[0] + vec[0], cur_pos[1] + vec[1], cur_pos[2] + vec[2]) ret_vec[:3] = self.end_ABC - self.start_ABC if Path.axis_config == Path.AXIS_CONFIG_SCARA: # Subtract the current angle positions if hasattr(self.prev, "end_ABC"): self.start_ABC = self.prev.end_ABC else: self.start_ABC = Scara.inverse_kinematics(cur_pos[0], cur_pos[1], cur_pos[2]) # Find the next angle positions self.end_ABC = Scara.inverse_kinematics(cur_pos[0] + vec[0], cur_pos[1] + vec[1], cur_pos[2] + vec[2] ) ret_vec[:3] = self.end_ABC - self.start_ABC # Apply Automatic bed compensation if self.use_bed_matrix: ret_vec[:3] = np.dot(Path.matrix_bed_comp, ret_vec[:3]) return ret_vec
def reverse_transform_vector(self, vec, cur_pos): """ Transform back from whatever """ ret_vec = np.copy(vec) if Path.axis_config == Path.AXIS_CONFIG_H_BELT: X = np.dot(Path.matrix_H, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_CORE_XY: X = np.dot(Path.matrix_XY_inv, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_DELTA: # Find the next column positions self.end_ABC = self.start_ABC + vec[:3] # We have the column translations and need to find what that # represents in cartesian. start_xyz = Delta.forward_kinematics2(self.start_ABC[0], self.start_ABC[1], self.start_ABC[2]) end_xyz = Delta.forward_kinematics2(self.end_ABC[0], self.end_ABC[1], self.end_ABC[2]) ret_vec[:3] = end_xyz - start_xyz return ret_vec
def reverse_transform_vector(self, vec, cur_pos): """ Transform back from whatever """ ret_vec = np.copy(vec) if Path.axis_config == Path.AXIS_CONFIG_H_BELT: X = np.dot(Path.matrix_H, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_CORE_XY: X = np.dot(Path.matrix_XY_inv, vec[0:2]) ret_vec[:2] = X[0] if Path.axis_config == Path.AXIS_CONFIG_DELTA: # Subtract the current column positions start_ABC = Delta.inverse_kinematics(cur_pos[0], cur_pos[1], cur_pos[2]) # Find the next column positions end_ABC = start_ABC + vec[:3] # We have the column translations and need to find what that # represents in cartesian. start_xyz = Delta.forward_kinematics(start_ABC[0], start_ABC[1], start_ABC[2]) end_xyz = Delta.forward_kinematics(end_ABC[0], end_ABC[1], end_ABC[2]) ret_vec[:3] = end_xyz - start_xyz return ret_vec
def __init__(self): """ Init """ logging.info("Redeem initializing " + version) printer = Printer() self.printer = printer # check for config files if not os.path.exists("/etc/redeem/default.cfg"): logging.error("/etc/redeem/default.cfg does not exist, this file is required for operation") sys.exit() # maybe use something more graceful? # Parse the config files. printer.config = CascadingConfigParser( ['/etc/redeem/default.cfg', '/etc/redeem/printer.cfg', '/etc/redeem/local.cfg']) # Find out which capes are connected self.printer.config.parse_capes() self.revision = self.printer.config.replicape_revision if self.revision: logging.info("Found Replicape rev. " + self.revision) Path.set_axes(5) else: logging.warning("Oh no! No Replicape present!") self.revision = "0A4A" # We set it to 5 axis by default Path.set_axes(5) if self.printer.config.reach_revision: Path.set_axes(8) logging.info("Found Reach rev. "+self.printer.config.reach_revision) # Get the revision and loglevel from the Config file level = self.printer.config.getint('System', 'loglevel') if level > 0: logging.getLogger().setLevel(level) if self.revision in ["00A4", "0A4A", "00A3"]: PWM.set_frequency(100) elif self.revision in ["00B1"]: PWM.set_frequency(1000) # Init the Paths Path.axis_config = printer.config.getint('Geometry', 'axis_config') # Init the end stops EndStop.callback = self.end_stop_hit EndStop.inputdev = self.printer.config.get("Endstops", "inputdev") for es in ["X1", "X2", "Y1", "Y2", "Z1", "Z2"]: pin = self.printer.config.get("Endstops", "pin_"+es) keycode = self.printer.config.getint("Endstops", "keycode_"+es) invert = self.printer.config.getboolean("Endstops", "invert_"+es) self.printer.end_stops[es] = EndStop(pin, keycode, es, invert) # Backwards compatibility with A3 if self.revision == "00A3": # Init the 5 Stepper motors (step, dir, fault, DAC channel, name) printer.steppers["X"] = Stepper_00A3("GPIO0_27", "GPIO1_29", "GPIO2_4" , 0, "X", 0, 0) printer.steppers["Y"] = Stepper_00A3("GPIO1_12", "GPIO0_22", "GPIO2_5" , 1, "Y", 1, 1) printer.steppers["Z"] = Stepper_00A3("GPIO0_23", "GPIO0_26", "GPIO0_15", 2, "Z", 2, 2) printer.steppers["E"] = Stepper_00A3("GPIO1_28", "GPIO1_15", "GPIO2_1" , 3, "E", 3, 3) printer.steppers["H"] = Stepper_00A3("GPIO1_13", "GPIO1_14", "GPIO2_3" , 4, "H", 4, 4) elif self.revision == "00B1": # Init the 5 Stepper motors (step, dir, fault, DAC channel, name) printer.steppers["X"] = Stepper_00B1("GPIO0_27", "GPIO1_29", "GPIO2_4" , 11, 0, "X", 0, 0) printer.steppers["Y"] = Stepper_00B1("GPIO1_12", "GPIO0_22", "GPIO2_5" , 12, 1, "Y", 1, 1) printer.steppers["Z"] = Stepper_00B1("GPIO0_23", "GPIO0_26", "GPIO0_15", 13, 2, "Z", 2, 2) printer.steppers["E"] = Stepper_00B1("GPIO1_28", "GPIO1_15", "GPIO2_1" , 14, 3, "E", 3, 3) printer.steppers["H"] = Stepper_00B1("GPIO1_13", "GPIO1_14", "GPIO2_3" , 15, 4, "H", 4, 4) else: # Init the 5 Stepper motors (step, dir, fault, DAC channel, name) printer.steppers["X"] = Stepper_00A4("GPIO0_27", "GPIO1_29", "GPIO2_4" , 0, 0, "X", 0, 0) printer.steppers["Y"] = Stepper_00A4("GPIO1_12", "GPIO0_22", "GPIO2_5" , 1, 1, "Y", 1, 1) printer.steppers["Z"] = Stepper_00A4("GPIO0_23", "GPIO0_26", "GPIO0_15", 2, 2, "Z", 2, 2) printer.steppers["E"] = Stepper_00A4("GPIO1_28", "GPIO1_15", "GPIO2_1" , 3, 3, "E", 3, 3) printer.steppers["H"] = Stepper_00A4("GPIO1_13", "GPIO1_14", "GPIO2_3" , 4, 4, "H", 4, 4) if printer.config.reach_revision: printer.steppers["A"] = Stepper_00A4("GPIO2_2" , "GPIO1_18", "GPIO0_14", 5, 5, "A", 5, 5) printer.steppers["B"] = Stepper_00A4("GPIO1_14", "GPIO0_5" , "GPIO0_14", 6, 6, "B", 6, 6) printer.steppers["C"] = Stepper_00A4("GPIO0_3" , "GPIO3_19", "GPIO0_14", 7, 7, "C", 7, 7) # Enable the steppers and set the current, steps pr mm and # microstepping for name, stepper in self.printer.steppers.iteritems(): stepper.in_use = printer.config.getboolean('Steppers', 'in_use_' + name) stepper.direction = printer.config.getint('Steppers', 'direction_' + name) stepper.has_endstop = printer.config.getboolean('Endstops', 'has_' + name) stepper.set_current_value(printer.config.getfloat('Steppers', 'current_' + name)) stepper.set_steps_pr_mm(printer.config.getfloat('Steppers', 'steps_pr_mm_' + name)) stepper.set_microstepping(printer.config.getint('Steppers', 'microstepping_' + name)) stepper.set_decay(printer.config.getboolean("Steppers", "slow_decay_" + name)) # Add soft end stops Path.soft_min[Path.axis_to_index(name)] = printer.config.getfloat('Endstops', 'soft_end_stop_min_' + name) Path.soft_max[Path.axis_to_index(name)] = printer.config.getfloat('Endstops', 'soft_end_stop_max_' + name) # Commit changes for the Steppers #Stepper.commit() # Delta printer setup if Path.axis_config == Path.AXIS_CONFIG_DELTA: opts = ["Hez", "L", "r", "Ae", "Be", "Ce", "A_radial", "B_radial", "C_radial", "A_tangential", "B_tangential", "C_tangential" ] for opt in opts: Delta.__dict__[opt] = printer.config.getfloat('Delta', opt) Delta.recalculate() # Set up cold ends path = self.printer.config.get('Cold-ends', 'path', 0) if os.path.exists(path): self.printer.cold_ends.append(ColdEnd(path, "Cold End 0")) logging.info("Found Cold end on " + path) else: logging.info("No cold end present in path: " + path) # Make Mosfets, thermistors and extruders heaters = ["E", "H", "HBP"] if self.printer.config.reach_revision: heaters.extend(["A", "B", "C"]) for e in heaters: # Mosfets channel = self.printer.config.getint("Heaters", "mosfet_"+e) self.printer.mosfets[e] = Mosfet(channel) # Thermistors adc = self.printer.config.get("Heaters", "path_adc_"+e) chart = self.printer.config.get("Heaters", "temp_chart_"+e) self.printer.thermistors[e] = Thermistor(adc, "MOSFET "+e, chart) # Extruders onoff = self.printer.config.getboolean('Heaters', 'onoff_'+e) prefix = self.printer.config.get('Heaters', 'prefix_'+e) if e != "HBP": self.printer.heaters[e] = Extruder( self.printer.steppers[e], self.printer.thermistors[e], self.printer.mosfets[e], e, onoff) else: self.printer.heaters[e] = HBP( self.printer.thermistors[e], self.printer.mosfets[e], onoff) self.printer.heaters[e].prefix = prefix self.printer.heaters[e].P = self.printer.config.getfloat('Heaters', 'pid_p_'+e) self.printer.heaters[e].I = self.printer.config.getfloat('Heaters', 'pid_i_'+e) self.printer.heaters[e].D = self.printer.config.getfloat('Heaters', 'pid_d_'+e) # Init the three fans. Argument is PWM channel number self.printer.fans = [] if self.revision == "00A3": self.printer.fans.append(Fan(0)) self.printer.fans.append(Fan(1)) self.printer.fans.append(Fan(2)) elif self.revision == "0A4A": self.printer.fans.append(Fan(8)) self.printer.fans.append(Fan(9)) self.printer.fans.append(Fan(10)) elif self.revision == "00B1": self.printer.fans.append(Fan(7)) self.printer.fans.append(Fan(8)) self.printer.fans.append(Fan(9)) self.printer.fans.append(Fan(10)) for f in self.printer.fans: f.set_value(0) # Init the servos printer.servos = [] servo_nr = 0 while(printer.config.has_option("Servos", "servo_"+str(servo_nr)+"_enable")): if printer.config.getboolean("Servos", "servo_"+str(servo_nr)+"_enable"): channel = printer.config.getint("Servos", "servo_"+str(servo_nr)+"_channel") angle_off = printer.config.getint("Servos", "servo_"+str(servo_nr)+"_angle_off") s = Servo(channel, 500, 750, angle_off) s.angle_on = printer.config.getint("Servos", "servo_"+str(servo_nr)+"_angle_on") s.angle_off = angle_off printer.servos.append(s) logging.info("Added servo "+str(servo_nr)) servo_nr += 1 # Connect thermitors to fans for t, therm in self.printer.heaters.iteritems(): for f, fan in enumerate(self.printer.fans): if self.printer.config.getboolean('Cold-ends', "connect-therm-{}-fan-{}".format(t, f)): c = Cooler(therm, fan, "Cooler-{}-{}".format(t, f), False) c.ok_range = 4 c.set_target_temperature(60) c.enable() self.printer.coolers.append(c) logging.info("Cooler connects therm {} with fan {}".format(t, f)) # Connect fans to M106 printer.controlled_fans = [] for i, fan in enumerate(self.printer.fans): if self.printer.config.getboolean('Cold-ends', "add-fan-{}-to-M106".format(i)): printer.controlled_fans.append(self.printer.fans[i]) logging.info("Added fan {} to M106/M107".format(i)) # Connect the cold end 0 to fan 2 # This is very "Thing" specific, should be configurable somehow. if len(self.printer.cold_ends): self.printer.coolers.append( Cooler(self.printer.cold_ends[0], self.printer.fans[2], "Cooler0", False)) self.printer.coolers[0].ok_range = 4 self.printer.coolers[0].set_target_temperature(60) self.printer.coolers[0].enable() # Make a queue of commands self.printer.commands = JoinableQueue(10) # Make a queue of commands that should not be buffered self.printer.sync_commands = JoinableQueue() self.printer.unbuffered_commands = JoinableQueue(10) # Bed compensation matrix Path.matrix_bed_comp = printer.load_bed_compensation_matrix() Path.matrix_bed_comp_inv = np.linalg.inv(Path.matrix_bed_comp) logging.debug("Loaded bed compensation matrix: \n"+str(Path.matrix_bed_comp)) for axis in printer.steppers.keys(): i = Path.axis_to_index(axis) Path.max_speeds[i] = printer.config.getfloat('Planner', 'max_speed_'+axis.lower()) Path.home_speed[i] = printer.config.getfloat('Homing', 'home_speed_'+axis.lower()) Path.home_backoff_speed[i] = printer.config.getfloat('Homing', 'home_backoff_speed_'+axis.lower()) Path.home_backoff_offset[i] = printer.config.getfloat('Homing', 'home_backoff_offset_'+axis.lower()) Path.steps_pr_meter[i] = printer.steppers[axis].get_steps_pr_meter() Path.backlash_compensation[i] = printer.config.getfloat('Steppers', 'backlash_'+axis.lower()) dirname = os.path.dirname(os.path.realpath(__file__)) # Create the firmware compiler pru_firmware = PruFirmware( dirname + "/firmware/firmware_runtime.p", dirname + "/firmware/firmware_runtime.bin", dirname + "/firmware/firmware_endstops.p", dirname + "/firmware/firmware_endstops.bin", self.revision, self.printer.config, "/usr/bin/pasm") printer.maxJerkXY = printer.config.getfloat('Planner', 'maxJerk_xy') printer.maxJerkZ = printer.config.getfloat('Planner', 'maxJerk_z') printer.maxJerkEH = printer.config.getfloat('Planner', 'maxJerk_eh') printer.move_cache_size = printer.config.getfloat('Planner', 'move_cache_size') printer.print_move_buffer_wait = printer.config.getfloat('Planner', 'print_move_buffer_wait') printer.min_buffered_move_time = printer.config.getfloat('Planner', 'min_buffered_move_time') printer.max_buffered_move_time = printer.config.getfloat('Planner', 'max_buffered_move_time') self.printer.processor = GCodeProcessor(self.printer) self.printer.plugins = PluginsController(self.printer) # Path planner travel_default = False center_default = False home_default = False self.printer.path_planner = PathPlanner(self.printer, pru_firmware) for axis in printer.steppers.keys(): i = Path.axis_to_index(axis) printer.acceleration[Path.axis_to_index(axis)] = printer.config.getfloat( 'Planner', 'acceleration_' + axis.lower()) # Sometimes soft_end_stop aren't defined to be at the exact hardware boundary. # Adding 100mm for searching buffer. if printer.config.has_option('Geometry', 'travel_' + axis.lower()): printer.path_planner.travel_length[axis] = printer.config.getfloat('Geometry', 'travel_' + axis.lower()) else: printer.path_planner.travel_length[axis] = (Path.soft_max[i] - Path.soft_min[i]) + .1 if axis in ['X','Y','Z']: travel_default = True if printer.config.has_option('Geometry', 'offset_' + axis.lower()): printer.path_planner.center_offset[axis] = printer.config.getfloat('Geometry', 'offset_' + axis.lower()) else: printer.path_planner.center_offset[axis] =(Path.soft_min[i] if Path.home_speed[i] > 0 else Path.soft_max[i]) if axis in ['X','Y','Z']: center_default = True if printer.config.has_option('Homing', 'home_' + axis.lower()): printer.path_planner.home_pos[axis] = printer.config.getfloat('Homing', 'home_' + axis.lower()) else: printer.path_planner.home_pos[axis] = printer.path_planner.center_offset[axis] if axis in ['X','Y','Z']: home_default = True if Path.axis_config == Path.AXIS_CONFIG_DELTA: if travel_default: logging.warning("Axis travel (travel_*) set by soft limits, manual setup is recommended for a delta") if center_default: logging.warning("Axis offsets (offset_*) set by soft limits, manual setup is recommended for a delta") if home_default: logging.warning("Home position (home_*) set by soft limits or offset_*") logging.info("Home position will be recalculated...") # convert home_pos to effector space Az = printer.path_planner.home_pos['X'] Bz = printer.path_planner.home_pos['Y'] Cz = printer.path_planner.home_pos['Z'] z_offset = Delta.vertical_offset(Az,Bz,Cz) # vertical offset xyz = Delta.forward_kinematics2(Az, Bz, Cz) # effector position # The default home_pos, provided above, is based on effector space # coordinates for carriage positions. We need to transform these to # get where the effector actually is. xyz[2] += z_offset for i, a in enumerate(['X','Y','Z']): printer.path_planner.home_pos[a] = xyz[i] logging.info("Home position = %s"%str(printer.path_planner.home_pos)) # Enable PWM and steppers printer.enable = Enable("P9_41") printer.enable.set_enabled() # Set up communication channels printer.comms["USB"] = USB(self.printer) printer.comms["Eth"] = Ethernet(self.printer) if Pipe.check_tty0tty() or Pipe.check_socat(): printer.comms["octoprint"] = Pipe(printer, "octoprint") printer.comms["toggle"] = Pipe(printer, "toggle") printer.comms["testing"] = Pipe(printer, "testing") printer.comms["testing_noret"] = Pipe(printer, "testing_noret") # Does not send "ok" printer.comms["testing_noret"].send_response = False else: logging.warning("Neither tty0tty or socat is installed! No virtual tty pipes enabled")
def home(self, axis): """ Home the given axis using endstops (min) """ logging.debug("homing " + str(axis)) # Home axis for core X,Y and H-Belt independently to avoid hardware # damages. if Path.axis_config == Path.AXIS_CONFIG_CORE_XY or \ Path.axis_config == Path.AXIS_CONFIG_H_BELT: for a in axis: self._home_internal(a) # For delta, switch to cartesian when homing elif Path.axis_config == Path.AXIS_CONFIG_DELTA: if 0 < len({"X", "Y", "Z"}.intersection(set(axis))) < 3: axis = list(set(axis).union({"X", "Y", "Z" })) # Deltas must home all axes. Path.axis_config = Path.AXIS_CONFIG_XY path_center, speed = self._home_internal(axis) Path.axis_config = Path.AXIS_CONFIG_DELTA # homing was performed in cartesian mode # need to convert back to delta Az = path_center['X'] Bz = path_center['Y'] Cz = path_center['Z'] z_offset = Delta.vertical_offset(Az, Bz, Cz) # vertical offset xyz = Delta.forward_kinematics2(Az, Bz, Cz) # effector position xyz[2] += z_offset path = {'X': xyz[0], 'Y': xyz[1], 'Z': xyz[2]} p = G92Path(path, speed) self.add_path(p) self.wait_until_done() # For scar, switch also to cartesian when homing elif Path.axis_config == Path.AXIS_CONFIG_SCARA: # TODO: implement individual homing ( needs to take care of position after homing) if 0 < len({"X", "Y", "Z"}.intersection(set(axis))) < 3: axis = list(set(axis).union({ "X", "Y", "Z" })) # For now Scaras must home all axes. Than can changed Path.axis_config = Path.AXIS_CONFIG_XY path_center, speed = self._home_internal(axis) Path.axis_config = Path.AXIS_CONFIG_SCARA # homing was performed in cartesian mode # need to convert back to delta A = path_center['X'] B = path_center['Y'] C = path_center['Z'] #z_offset = Delta.vertical_offset(Az,Bz,Cz) # vertical offset # xyz = Scara.inverse_kinematics(A, B, C) # effector position # logging.debug("HomeXYZ: %s", xyz) #xyz[2] += z_offset # don't cpnvert home_pos to effector spac # home offset is defined in cartesian space # xyz = np.array([path_center['X'], path_center['Y'], path_center['Z']]) #path = {'X':xyz[0], 'Y':xyz[1], 'Z':xyz[2]} path = {A, B, C} p = G92Path(path, speed) self.add_path(p) self.wait_until_done() else: self._home_internal(axis) # go to the designated home position self._go_to_home(axis) # Reset backlash compensation Path.backlash_reset() logging.debug("homing done for " + str(axis)) return
import random from Delta import Delta from Active_Function import Sigmoid count_Training_Data = 4 count_Node = 1 X = [[0, 0, 1], [0, 1, 1], [1, 0, 1], [1, 1, 1]] D = [0, 0, 1, 1] Weight = list() for i in range(0, 3): Weight.append(random.uniform(-1, 1)) bias = [0] Learning_rate = 0.9 for epoch in range(0, 10000): Delta("SGD", Learning_rate, Sigmoid, bias, Weight, X, D, count_Training_Data, count_Node) for k in range(0, count_Training_Data): v = 0 for W_count in range(0, len(Weight)): x = X[k][W_count] v = v + (Weight[W_count] * x + 0) print(Sigmoid(v, False))
import random from Delta import Delta, Sigmoid #N = int(input("학습데이터의 수: ")) count_Training = 4 # 학습데이터의 수 count_Node = 1 # 1. 데이터 입력 X = [[0, 0, 1], [0, 1, 1], [1, 0, 1], [1, 1, 1]] D = [0, 0, 1, 1] Weight = list() for i in range(0, 3): # 노드의 입력값들의 가중치 count Weight.append(random.uniform(-1, 1)) # 가중치 랜덤값으로 초기화 bias = [0] Learning_rate = 0.9 #학습률(0<alpha<=1), 크면 수렴하지 못함, 작으면 정답에 근접속도가 느림 for epoch in range(0, 10000): # SGD 방식 Delta(Learning_rate, Sigmoid, bias, Weight, X, D, count_Training, count_Node) #활성함수(시그모이드)를 델타 규칙으로 학습 for k in range(0, count_Training): v = 0 for W_count in range(0, len(Weight)): x = X[k][W_count] #학습데이터의 입력데이터 #v = W*x+0 #노드의 가중합(가중행렬*입력데이터+bias) #의도가 담긴 방향성 v = v + (Weight[W_count] * x + 0) # 최종v = v + 0(행렬계산 + bias) print(Sigmoid(v, False))
def home(self, axis): """ Home the given axis using endstops (min) """ logging.debug("homing " + str(axis)) # Home axis for core X,Y and H-Belt independently to avoid hardware # damages. if Path.axis_config == Path.AXIS_CONFIG_CORE_XY or \ Path.axis_config == Path.AXIS_CONFIG_H_BELT: for a in axis: self._home_internal(a) # For delta, switch to cartesian when homing elif Path.axis_config == Path.AXIS_CONFIG_DELTA: if 0 < len({"X", "Y", "Z"}.intersection(set(axis))) < 3: axis = list(set(axis).union({"X", "Y", "Z"})) # Deltas must home all axes. Path.axis_config = Path.AXIS_CONFIG_XY path_center, speed = self._home_internal(axis) Path.axis_config = Path.AXIS_CONFIG_DELTA # homing was performed in cartesian mode # need to convert back to delta Az = path_center['X'] Bz = path_center['Y'] Cz = path_center['Z'] z_offset = Delta.vertical_offset(Az,Bz,Cz) # vertical offset xyz = Delta.forward_kinematics2(Az, Bz, Cz) # effector position xyz[2] += z_offset path = {'X':xyz[0], 'Y':xyz[1], 'Z':xyz[2]} p = G92Path(path, speed) self.add_path(p) self.wait_until_done() # For scar, switch also to cartesian when homing elif Path.axis_config == Path.AXIS_CONFIG_SCARA: # TODO: implement individual homing ( needs to take care of position after homing) if 0 < len({"X", "Y", "Z"}.intersection(set(axis))) < 3: axis = list(set(axis).union({"X", "Y", "Z"})) # For now Scaras must home all axes. Than can changed Path.axis_config = Path.AXIS_CONFIG_XY path_center, speed = self._home_internal(axis) Path.axis_config = Path.AXIS_CONFIG_SCARA # homing was performed in cartesian mode # need to convert back to delta A = path_center['X'] B = path_center['Y'] C = path_center['Z'] #z_offset = Delta.vertical_offset(Az,Bz,Cz) # vertical offset # xyz = Scara.inverse_kinematics(A, B, C) # effector position # logging.debug("HomeXYZ: %s", xyz) #xyz[2] += z_offset # don't cpnvert home_pos to effector spac # home offset is defined in cartesian space # xyz = np.array([path_center['X'], path_center['Y'], path_center['Z']]) #path = {'X':xyz[0], 'Y':xyz[1], 'Z':xyz[2]} path = {A, B, C} p = G92Path(path, speed) self.add_path(p) self.wait_until_done() else: self._home_internal(axis) # go to the designated home position self._go_to_home(axis) # Reset backlash compensation Path.backlash_reset() logging.debug("homing done for " + str(axis)) return
def __init__(self): firmware_version = "1.1.8~Raw Deal" logging.info("Redeem initializing "+firmware_version) printer = Printer() self.printer = printer Path.printer = printer printer.firmware_version = firmware_version # check for config files if not os.path.exists("/etc/redeem/default.cfg"): logging.error("/etc/redeem/default.cfg does not exist, this file is required for operation") sys.exit() # maybe use something more graceful? if not os.path.exists("/etc/redeem/local.cfg"): logging.info("/etc/redeem/local.cfg does not exist, Creating one") os.mknod("/etc/redeem/local.cfg") # Parse the config files. printer.config = CascadingConfigParser( ['/etc/redeem/default.cfg', '/etc/redeem/printer.cfg', '/etc/redeem/local.cfg']) # Get the revision and loglevel from the Config file level = self.printer.config.getint('System', 'loglevel') if level > 0: logging.getLogger().setLevel(level) # Set up additional logging, if present: if self.printer.config.getboolean('System', 'log_to_file'): logfile = self.printer.config.get('System', 'logfile') formatter = '%(asctime)s %(name)-12s %(levelname)-8s %(message)s' printer.redeem_logging_handler = logging.handlers.RotatingFileHandler(logfile, maxBytes=2*1024*1024) printer.redeem_logging_handler.setFormatter(logging.Formatter(formatter)) printer.redeem_logging_handler.setLevel(level) logging.getLogger().addHandler(printer.redeem_logging_handler) logging.info("-- Logfile configured --") # Find out which capes are connected self.printer.config.parse_capes() self.revision = self.printer.config.replicape_revision if self.revision: logging.info("Found Replicape rev. " + self.revision) else: logging.warning("Oh no! No Replicape present!") self.revision = "00B3" # We set it to 5 axis by default Path.NUM_AXES = 5 if self.printer.config.reach_revision: logging.info("Found Reach rev. "+self.printer.config.reach_revision) if self.printer.config.reach_revision == "00A0": Path.NUM_AXES = 8 elif self.printer.config.reach_revision == "00B0": Path.NUM_AXES = 7 if self.revision in ["00A4", "0A4A", "00A3"]: PWM.set_frequency(100) elif self.revision in ["00B1", "00B2", "00B3"]: PWM.set_frequency(1000) # Test the alarm framework Alarm.printer = self.printer Alarm.executor = AlarmExecutor() alarm = Alarm(Alarm.ALARM_TEST, "Alarm framework operational") # Init the Watchdog timer printer.watchdog = Watchdog() # Enable PWM and steppers printer.enable = Enable("P9_41") printer.enable.set_disabled() # Init the Paths Path.axis_config = printer.config.getint('Geometry', 'axis_config') # Init the end stops EndStop.inputdev = self.printer.config.get("Endstops", "inputdev") # Set up key listener Key_pin.listener = Key_pin_listener(EndStop.inputdev) for es in ["Z2", "Y2", "X2", "Z1", "Y1", "X1"]: # Order matches end stop inversion mask in Firmware pin = self.printer.config.get("Endstops", "pin_"+es) keycode = self.printer.config.getint("Endstops", "keycode_"+es) invert = self.printer.config.getboolean("Endstops", "invert_"+es) self.printer.end_stops[es] = EndStop(printer, pin, keycode, es, invert) self.printer.end_stops[es].stops = self.printer.config.get('Endstops', 'end_stop_'+es+'_stops') # Init the 5 Stepper motors (step, dir, fault, DAC channel, name) if self.revision == "00A3": printer.steppers["X"] = Stepper_00A3("GPIO0_27", "GPIO1_29", "GPIO2_4" , 0, "X") printer.steppers["Y"] = Stepper_00A3("GPIO1_12", "GPIO0_22", "GPIO2_5" , 1, "Y") printer.steppers["Z"] = Stepper_00A3("GPIO0_23", "GPIO0_26", "GPIO0_15", 2, "Z") printer.steppers["E"] = Stepper_00A3("GPIO1_28", "GPIO1_15", "GPIO2_1" , 3, "E") printer.steppers["H"] = Stepper_00A3("GPIO1_13", "GPIO1_14", "GPIO2_3" , 4, "H") elif self.revision == "00B1": printer.steppers["X"] = Stepper_00B1("GPIO0_27", "GPIO1_29", "GPIO2_4" , 11, 0, "X") printer.steppers["Y"] = Stepper_00B1("GPIO1_12", "GPIO0_22", "GPIO2_5" , 12, 1, "Y") printer.steppers["Z"] = Stepper_00B1("GPIO0_23", "GPIO0_26", "GPIO0_15", 13, 2, "Z") printer.steppers["E"] = Stepper_00B1("GPIO1_28", "GPIO1_15", "GPIO2_1" , 14, 3, "E") printer.steppers["H"] = Stepper_00B1("GPIO1_13", "GPIO1_14", "GPIO2_3" , 15, 4, "H") elif self.revision == "00B2": printer.steppers["X"] = Stepper_00B2("GPIO0_27", "GPIO1_29", "GPIO2_4" , 11, 0, "X") printer.steppers["Y"] = Stepper_00B2("GPIO1_12", "GPIO0_22", "GPIO2_5" , 12, 1, "Y") printer.steppers["Z"] = Stepper_00B2("GPIO0_23", "GPIO0_26", "GPIO0_15", 13, 2, "Z") printer.steppers["E"] = Stepper_00B2("GPIO1_28", "GPIO1_15", "GPIO2_1" , 14, 3, "E") printer.steppers["H"] = Stepper_00B2("GPIO1_13", "GPIO1_14", "GPIO2_3" , 15, 4, "H") elif self.revision == "00B3": printer.steppers["X"] = Stepper_00B3("GPIO0_27", "GPIO1_29", 90, 11, 0, "X") printer.steppers["Y"] = Stepper_00B3("GPIO1_12", "GPIO0_22", 91, 12, 1, "Y") printer.steppers["Z"] = Stepper_00B3("GPIO0_23", "GPIO0_26", 92, 13, 2, "Z") printer.steppers["E"] = Stepper_00B3("GPIO1_28", "GPIO1_15", 93, 14, 3, "E") printer.steppers["H"] = Stepper_00B3("GPIO1_13", "GPIO1_14", 94, 15, 4, "H") elif self.revision in ["00A4", "0A4A"]: printer.steppers["X"] = Stepper_00A4("GPIO0_27", "GPIO1_29", "GPIO2_4" , 0, 0, "X") printer.steppers["Y"] = Stepper_00A4("GPIO1_12", "GPIO0_22", "GPIO2_5" , 1, 1, "Y") printer.steppers["Z"] = Stepper_00A4("GPIO0_23", "GPIO0_26", "GPIO0_15", 2, 2, "Z") printer.steppers["E"] = Stepper_00A4("GPIO1_28", "GPIO1_15", "GPIO2_1" , 3, 3, "E") printer.steppers["H"] = Stepper_00A4("GPIO1_13", "GPIO1_14", "GPIO2_3" , 4, 4, "H") # Init Reach steppers, if present. if printer.config.reach_revision == "00A0": printer.steppers["A"] = Stepper_reach_00A4("GPIO2_2" , "GPIO1_18", "GPIO0_14", 5, 5, "A") printer.steppers["B"] = Stepper_reach_00A4("GPIO1_16", "GPIO0_5" , "GPIO0_14", 6, 6, "B") printer.steppers["C"] = Stepper_reach_00A4("GPIO0_3" , "GPIO3_19", "GPIO0_14", 7, 7, "C") elif printer.config.reach_revision == "00B0": printer.steppers["A"] = Stepper_reach_00B0("GPIO1_16", "GPIO0_5", "GPIO0_3", 5, 5, "A") printer.steppers["B"] = Stepper_reach_00B0("GPIO2_2" , "GPIO0_14", "GPIO0_3", 6, 6, "B") # Enable the steppers and set the current, steps pr mm and # microstepping for name, stepper in self.printer.steppers.iteritems(): stepper.in_use = printer.config.getboolean('Steppers', 'in_use_' + name) stepper.direction = printer.config.getint('Steppers', 'direction_' + name) stepper.has_endstop = printer.config.getboolean('Endstops', 'has_' + name) stepper.set_current_value(printer.config.getfloat('Steppers', 'current_' + name)) stepper.set_steps_pr_mm(printer.config.getfloat('Steppers', 'steps_pr_mm_' + name)) stepper.set_microstepping(printer.config.getint('Steppers', 'microstepping_' + name)) stepper.set_decay(printer.config.getint("Steppers", "slow_decay_" + name)) # Add soft end stops Path.soft_min[Path.axis_to_index(name)] = printer.config.getfloat('Endstops', 'soft_end_stop_min_' + name) Path.soft_max[Path.axis_to_index(name)] = printer.config.getfloat('Endstops', 'soft_end_stop_max_' + name) slave = printer.config.get('Steppers', 'slave_' + name) if slave: Path.add_slave(name, slave) logging.debug("Axis "+name+" has slave "+slave) # Commit changes for the Steppers #Stepper.commit() Stepper.printer = printer # Delta printer setup if Path.axis_config == Path.AXIS_CONFIG_DELTA: opts = ["Hez", "L", "r", "Ae", "Be", "Ce", "A_radial", "B_radial", "C_radial", "A_tangential", "B_tangential", "C_tangential" ] for opt in opts: Delta.__dict__[opt] = printer.config.getfloat('Delta', opt) Delta.recalculate() # Discover and add all DS18B20 cold ends. import glob paths = glob.glob("/sys/bus/w1/devices/28-*/w1_slave") logging.debug("Found cold ends: "+str(paths)) for i, path in enumerate(paths): self.printer.cold_ends.append(ColdEnd(path, "ds18b20-"+str(i))) logging.info("Found Cold end "+str(i)+" on " + path) # Make Mosfets, thermistors and extruders heaters = ["E", "H", "HBP"] if self.printer.config.reach_revision: heaters.extend(["A", "B", "C"]) for e in heaters: # Mosfets channel = self.printer.config.getint("Heaters", "mosfet_"+e) self.printer.mosfets[e] = Mosfet(channel) # Thermistors adc = self.printer.config.get("Heaters", "path_adc_"+e) chart = self.printer.config.get("Heaters", "temp_chart_"+e) resistance = self.printer.config.getfloat("Heaters", "resistance_"+e) self.printer.thermistors[e] = Thermistor(adc, "MOSFET "+e, chart, resistance) self.printer.thermistors[e].printer = printer # Extruders onoff = self.printer.config.getboolean('Heaters', 'onoff_'+e) prefix = self.printer.config.get('Heaters', 'prefix_'+e) if e != "HBP": self.printer.heaters[e] = Extruder( self.printer.steppers[e], self.printer.thermistors[e], self.printer.mosfets[e], e, onoff) else: self.printer.heaters[e] = HBP( self.printer.thermistors[e], self.printer.mosfets[e], onoff) self.printer.heaters[e].prefix = prefix self.printer.heaters[e].P = self.printer.config.getfloat('Heaters', 'pid_p_'+e) self.printer.heaters[e].I = self.printer.config.getfloat('Heaters', 'pid_i_'+e) self.printer.heaters[e].D = self.printer.config.getfloat('Heaters', 'pid_d_'+e) # Min/max settings self.printer.heaters[e].min_temp = self.printer.config.getfloat('Heaters', 'min_temp_'+e) self.printer.heaters[e].max_temp = self.printer.config.getfloat('Heaters', 'max_temp_'+e) self.printer.heaters[e].max_temp_rise = self.printer.config.getfloat('Heaters', 'max_rise_temp_'+e) self.printer.heaters[e].max_temp_fall = self.printer.config.getfloat('Heaters', 'max_fall_temp_'+e) # Init the three fans. Argument is PWM channel number self.printer.fans = [] if self.revision == "00A3": self.printer.fans.append(Fan(0)) self.printer.fans.append(Fan(1)) self.printer.fans.append(Fan(2)) elif self.revision == "0A4A": self.printer.fans.append(Fan(8)) self.printer.fans.append(Fan(9)) self.printer.fans.append(Fan(10)) elif self.revision in ["00B1", "00B2", "00B3"]: self.printer.fans.append(Fan(7)) self.printer.fans.append(Fan(8)) self.printer.fans.append(Fan(9)) self.printer.fans.append(Fan(10)) if printer.config.reach_revision == "00A0": self.printer.fans.append(Fan(14)) self.printer.fans.append(Fan(15)) self.printer.fans.append(Fan(7)) # Disable all fans for f in self.printer.fans: f.set_value(0) # Init the servos printer.servos = [] servo_nr = 0 while(printer.config.has_option("Servos", "servo_"+str(servo_nr)+"_enable")): if printer.config.getboolean("Servos", "servo_"+str(servo_nr)+"_enable"): channel = printer.config.get("Servos", "servo_"+str(servo_nr)+"_channel") pulse_min = printer.config.getfloat("Servos", "servo_"+str(servo_nr)+"_pulse_min") pulse_max = printer.config.getfloat("Servos", "servo_"+str(servo_nr)+"_pulse_max") angle_min = printer.config.getfloat("Servos", "servo_"+str(servo_nr)+"_angle_min") angle_max = printer.config.getfloat("Servos", "servo_"+str(servo_nr)+"_angle_max") angle_init = printer.config.getfloat("Servos", "servo_"+str(servo_nr)+"_angle_init") s = Servo(channel, pulse_min, pulse_max, angle_min, angle_max, angle_init) printer.servos.append(s) logging.info("Added servo "+str(servo_nr)) servo_nr += 1 # Connect thermitors to fans for t, therm in self.printer.heaters.iteritems(): for f, fan in enumerate(self.printer.fans): if not self.printer.config.has_option('Cold-ends', "connect-therm-{}-fan-{}".format(t, f)): continue if printer.config.getboolean('Cold-ends', "connect-therm-{}-fan-{}".format(t, f)): c = Cooler(therm, fan, "Cooler-{}-{}".format(t, f), True) # Use ON/OFF on these. c.ok_range = 4 opt_temp = "therm-{}-fan-{}-target_temp".format(t, f) if printer.config.has_option('Cold-ends', opt_temp): target_temp = printer.config.getfloat('Cold-ends', opt_temp) else: target_temp = 60 c.set_target_temperature(target_temp) c.enable() printer.coolers.append(c) logging.info("Cooler connects therm {} with fan {}".format(t, f)) # Connect fans to M106 printer.controlled_fans = [] for i, fan in enumerate(self.printer.fans): if not self.printer.config.has_option('Cold-ends', "add-fan-{}-to-M106".format(i)): continue if self.printer.config.getboolean('Cold-ends', "add-fan-{}-to-M106".format(i)): printer.controlled_fans.append(self.printer.fans[i]) logging.info("Added fan {} to M106/M107".format(i)) # Connect the colds to fans for ce, cold_end in enumerate(self.printer.cold_ends): for f, fan in enumerate(self.printer.fans): option = "connect-ds18b20-{}-fan-{}".format(ce, f) if self.printer.config.has_option('Cold-ends', option): if self.printer.config.getboolean('Cold-ends', option): c = Cooler(cold_end, fan, "Cooler-ds18b20-{}-{}".format(ce, f), False) c.ok_range = 4 opt_temp = "cooler_{}_target_temp".format(ce) if printer.config.has_option('Cold-ends', opt_temp): target_temp = printer.config.getfloat('Cold-ends', opt_temp) else: target_temp = 60 c.set_target_temperature(target_temp) c.enable() printer.coolers.append(c) logging.info("Cooler connects temp sensor ds18b20 {} with fan {}".format(ce, f)) # Init roatray encs. printer.filament_sensors = [] # Init rotary encoders printer.rotary_encoders = [] for ex in ["E", "H", "A", "B", "C"]: if not printer.config.has_option('Rotary-encoders', "enable-{}".format(ex)): continue if printer.config.getboolean("Rotary-encoders", "enable-{}".format(ex)): logging.debug("Rotary encoder {} enabled".format(ex)) event = printer.config.get("Rotary-encoders", "event-{}".format(ex)) cpr = printer.config.getint("Rotary-encoders", "cpr-{}".format(ex)) diameter = printer.config.getfloat("Rotary-encoders", "diameter-{}".format(ex)) r = RotaryEncoder(event, cpr, diameter) printer.rotary_encoders.append(r) # Append as Filament Sensor ext_nr = Path.axis_to_index(ex)-3 sensor = FilamentSensor(ex, r, ext_nr, printer) alarm_level = printer.config.getfloat("Filament-sensors", "alarm-level-{}".format(ex)) logging.debug("Alarm level"+str(alarm_level)) sensor.alarm_level = alarm_level printer.filament_sensors.append(sensor) # Make a queue of commands self.printer.commands = JoinableQueue(10) # Make a queue of commands that should not be buffered self.printer.sync_commands = JoinableQueue() self.printer.unbuffered_commands = JoinableQueue(10) # Bed compensation matrix Path.matrix_bed_comp = printer.load_bed_compensation_matrix() Path.matrix_bed_comp_inv = np.linalg.inv(Path.matrix_bed_comp) logging.debug("Loaded bed compensation matrix: \n"+str(Path.matrix_bed_comp)) for axis in printer.steppers.keys(): i = Path.axis_to_index(axis) Path.max_speeds[i] = printer.config.getfloat('Planner', 'max_speed_'+axis.lower()) Path.min_speeds[i] = printer.config.getfloat('Planner', 'min_speed_'+axis.lower()) Path.jerks[i] = printer.config.getfloat('Planner', 'max_jerk_'+axis.lower()) Path.home_speed[i] = printer.config.getfloat('Homing', 'home_speed_'+axis.lower()) Path.home_backoff_speed[i] = printer.config.getfloat('Homing', 'home_backoff_speed_'+axis.lower()) Path.home_backoff_offset[i] = printer.config.getfloat('Homing', 'home_backoff_offset_'+axis.lower()) Path.steps_pr_meter[i] = printer.steppers[axis].get_steps_pr_meter() Path.backlash_compensation[i] = printer.config.getfloat('Steppers', 'backlash_'+axis.lower()) dirname = os.path.dirname(os.path.realpath(__file__)) # Create the firmware compiler pru_firmware = PruFirmware( dirname + "/firmware/firmware_runtime.p", dirname + "/firmware/firmware_runtime.bin", dirname + "/firmware/firmware_endstops.p", dirname + "/firmware/firmware_endstops.bin", self.printer, "/usr/bin/pasm") printer.move_cache_size = printer.config.getfloat('Planner', 'move_cache_size') printer.print_move_buffer_wait = printer.config.getfloat('Planner', 'print_move_buffer_wait') printer.min_buffered_move_time = printer.config.getfloat('Planner', 'min_buffered_move_time') printer.max_buffered_move_time = printer.config.getfloat('Planner', 'max_buffered_move_time') self.printer.processor = GCodeProcessor(self.printer) self.printer.plugins = PluginsController(self.printer) # Path planner travel_default = False center_default = False home_default = False # Setting acceleration before PathPlanner init for axis in printer.steppers.keys(): Path.acceleration[Path.axis_to_index(axis)] = printer.config.getfloat( 'Planner', 'acceleration_' + axis.lower()) self.printer.path_planner = PathPlanner(self.printer, pru_firmware) for axis in printer.steppers.keys(): i = Path.axis_to_index(axis) # Sometimes soft_end_stop aren't defined to be at the exact hardware boundary. # Adding 100mm for searching buffer. if printer.config.has_option('Geometry', 'travel_' + axis.lower()): printer.path_planner.travel_length[axis] = printer.config.getfloat('Geometry', 'travel_' + axis.lower()) else: printer.path_planner.travel_length[axis] = (Path.soft_max[i] - Path.soft_min[i]) + .1 if axis in ['X','Y','Z']: travel_default = True if printer.config.has_option('Geometry', 'offset_' + axis.lower()): printer.path_planner.center_offset[axis] = printer.config.getfloat('Geometry', 'offset_' + axis.lower()) else: printer.path_planner.center_offset[axis] =(Path.soft_min[i] if Path.home_speed[i] > 0 else Path.soft_max[i]) if axis in ['X','Y','Z']: center_default = True if printer.config.has_option('Homing', 'home_' + axis.lower()): printer.path_planner.home_pos[axis] = printer.config.getfloat('Homing', 'home_' + axis.lower()) else: printer.path_planner.home_pos[axis] = printer.path_planner.center_offset[axis] if axis in ['X','Y','Z']: home_default = True if Path.axis_config == Path.AXIS_CONFIG_DELTA: if travel_default: logging.warning("Axis travel (travel_*) set by soft limits, manual setup is recommended for a delta") if center_default: logging.warning("Axis offsets (offset_*) set by soft limits, manual setup is recommended for a delta") if home_default: logging.warning("Home position (home_*) set by soft limits or offset_*") logging.info("Home position will be recalculated...") # convert home_pos to effector space Az = printer.path_planner.home_pos['X'] Bz = printer.path_planner.home_pos['Y'] Cz = printer.path_planner.home_pos['Z'] z_offset = Delta.vertical_offset(Az,Bz,Cz) # vertical offset xyz = Delta.forward_kinematics2(Az, Bz, Cz) # effector position # The default home_pos, provided above, is based on effector space # coordinates for carriage positions. We need to transform these to # get where the effector actually is. xyz[2] += z_offset for i, a in enumerate(['X','Y','Z']): printer.path_planner.home_pos[a] = xyz[i] logging.info("Home position = %s"%str(printer.path_planner.home_pos)) # Enable Stepper timeout timeout = printer.config.getint('Steppers', 'timeout_seconds') printer.swd = StepperWatchdog(printer, timeout) if printer.config.getboolean('Steppers', 'use_timeout'): printer.swd.start() # Set up communication channels printer.comms["USB"] = USB(self.printer) printer.comms["Eth"] = Ethernet(self.printer) if Pipe.check_tty0tty() or Pipe.check_socat(): printer.comms["octoprint"] = Pipe(printer, "octoprint") printer.comms["toggle"] = Pipe(printer, "toggle") printer.comms["testing"] = Pipe(printer, "testing") printer.comms["testing_noret"] = Pipe(printer, "testing_noret") # Does not send "ok" printer.comms["testing_noret"].send_response = False else: logging.warning("Neither tty0tty or socat is installed! No virtual tty pipes enabled")
class Runtime: def __init__(self, robot: str): # Thread-safe event flags self.program_stopped = Event() self.ignore_controller = Event() self._current_mode = 'off' self.controller = None self.already_connected = False self.controller_poll_rate = 5 self.mode_poll_rate = 0.1 self.mode_lock = RLock() self.lcd = LCD() # Preprocess string robot_str = robot.strip().lower() if robot_str == '6rus': self.robot = SixRUS(stepper_mode=1 / 32, step_delay=0.002) elif robot_str == 'quattro': self.robot = Quattro(stepper_mode=1 / 32, step_delay=0.002) elif robot_str == 'delta': self.robot = Delta(stepper_mode=1 / 32, step_delay=0.002) else: raise ValueError(f"Unknown robot type: {robot}") self.lcd.print_status(f'Started {robot}') @property def current_mode(self): with self.mode_lock: return self._current_mode @current_mode.setter def current_mode(self, val): with self.mode_lock: self._current_mode = val def eval_controller_response(self, response): """ evaluates the answer from the mode_from_input-function """ if isinstance(response, str): if response in ['stop', 'demo', 'manual', 'calibrate', 'off']: pass elif response == 'homing': self.ignore_controller.set() else: raise ValueError("Unknown answer from controller") if self.current_mode != response: # only print if the mode changes logging.debug( f'Switching from {self.current_mode} to {response}.') self.lcd.print_status(f'Status: {response}') self.current_mode = response # set robot mode to the response return True return False # no response given def poll_controller_status(self): if self.program_stopped.is_set(): return if not controller.still_connected(): self.already_connected = False logging.info("Please connect controller! Retrying in 5 seconds...") self.lcd.print_connection(False) else: if self.already_connected: # no new initialisation required here logging.info('Controller still connected.') else: # stop listening as the controller gets initalised self.ignore_controller.set() # init new joystick since the controller was reconnected or connected the first time self.controller = controller.init_controller() self.ignore_controller.clear() self.already_connected = True logging.info('Controller connected.') self.lcd.print_connection(True) # call program again after 5 seconds Timer(self.controller_poll_rate, self.poll_controller_status).start() def poll_program_mode(self): if self.program_stopped.is_set(): # Finish thread if program is terminated return # Handle controller inputs all the time to keep button states up to date try: controls = controller.get_controller_inputs(self.controller) if not self.ignore_controller.is_set(): # evaluate the answer from controller self.eval_controller_response( controller.mode_from_inputs(controls)) except AttributeError: pass except pygame.error as e: logging.exception(e) finally: # call program again after 0.1 seconds Timer(self.mode_poll_rate, self.poll_program_mode).start() def move(self, pose): try: self.robot.mov(pose) except WorkspaceViolation: logging.debug(f"Cannot move to pose:{pose}") else: self.lcd.print_pose(pose) def move_manual(self, dt=0.005): """ This is the manual controlling mode, where the robot can be driven with the controller. Exits only if the mode was changed or the program was interrupted """ # stop listening to controller (bc. we listen all the time in here) self.ignore_controller.set() time.sleep(dt) try: inputs = controller.get_controller_inputs(self.controller) except AttributeError: return new_pose = controller.get_movement_from_cont(inputs, self.robot.currPose) # check if mode was changed if self.eval_controller_response(controller.mode_from_inputs(inputs)): self.ignore_controller.clear() self.move(new_pose) def move_demo(self): """ Selects a random demo programm and executes it """ modules = [] for a in dir(demo): if isinstance(getattr(demo, a), types.FunctionType): modules.append(getattr(demo, a)) prog = random.choice(modules) # choose a random demo demo_pos_list = prog() # execute chosen demo programm for pos in demo_pos_list: try: if pos[6] == 'lin': coord = pos[:6] # extract only pose self.robot.mov_lin(coord) # move linear elif pos[6] == 'mov': coord = pos[:6] # extract only pose self.move(coord) # move with PTP-interplation except IndexError: self.move(pos) # if 'lin' or 'mov' wasent given, use mov/PTP if not self.current_mode == 'demo': # break if the mode was changed break def calibrate_process(self, dt=0.005): """ enters mode, where the user can calibrate each motor in microstep mode. A homing procedure has to be done afterwarts! `dt`: how fast the controller inputs get checked in [s] """ mot_num = 0 # motornumber from 0 to 5 # pose after calibration has to be given to move the motors but is not necessary here # since a homing procedure has to be done afterwards anyways pose_after_cali = [0, 0, 0, 0, 0, 0] allowed_to_change_again = True # if the next motor can be selected cali_step_increment = 1 while True: time.sleep(dt) try: controls = controller.get_controller_inputs(self.controller) except AttributeError: continue # check if mode was changed if self.eval_controller_response( controller.mode_from_inputs(controls)): break cali_mot = [0, 0, 0, 0, 0, 0] if allowed_to_change_again: # change motornumber with L1 and R1 if controls['L1']: mot_num -= 1 elif controls['R1']: mot_num += 1 # check if selected motor number exists if mot_num > self.robot.dof - 1: mot_num = 0 elif mot_num < 0: mot_num = self.robot.dof - 1 allowed_to_change_again = False if controls['L1'] == 0 and controls[ 'R1'] == 0: # both buttons have to be released to switch to next motor allowed_to_change_again = True if controls['UP']: cali_mot[ mot_num] = cali_step_increment # set 1 posivitve for selected motor elif controls['DOWN']: cali_mot[ mot_num] = -cali_step_increment # set -1 posivitve for selected motor elif controls['LEFT'] and self.robot.stepperMode != 0: # Decrement calibration step size but needs to be at least 1 cali_step_increment = max(1, cali_step_increment - 1) elif controls['RIGHT'] and self.robot.stepperMode != 0: # Increment calibration step size but needs to be <= 1/step-mode (e.g. 1/32 -> 32 inc = 1 full step) cali_step_increment = min(1 / self.robot.stepperMode, cali_step_increment + 1) self.robot.mov_steps(cali_mot, pose_after_cali) def loop(self): self.robot.homing('90') # home robot self.controller = controller.init_controller() if self.controller is None: self.already_connected = False # call subroutine every 5-seconds to check for controller self.poll_controller_status() # start listening to controller self.ignore_controller.clear() self.poll_program_mode() while not self.program_stopped.is_set(): # State Machine if self.current_mode == 'off': self.robot.disable_steppers() time.sleep(0.0001) # limit loop time else: self.robot.enable_steppers() if self.current_mode == 'demo': self.move_demo() time.sleep(2) elif self.current_mode == 'manual': # control the robot with the controller self.move_manual() elif self.current_mode == 'calibrate': # stop listening to controller (bc. we listen all the time in here) self.ignore_controller.set() time.sleep(0.5) self.calibrate_process() time.sleep(0.5) # home robot afterwards logging.info('Switching to homing') self.lcd.print_status(f'Status: homing') self.current_mode = 'homing' elif self.current_mode == 'homing': # stop listening to controller to prevent program change while homing self.ignore_controller.set() time.sleep( 1.5) # wait a bit to reduce multiple homing attempts self.robot.homing('90') # use homing method '90' # exit homing and switch to state that stopped calibration logging.info('Switching to stop') self.lcd.print_status(f'Status: stop') self.current_mode = 'stop' self.ignore_controller.clear() elif self.current_mode == 'stop': # stop robot after next movement and do nothing time.sleep(0.0001) # limit loop time
def __init__(self): firmware_version = "1.1.8~Raw Deal" logging.info("Redeem initializing " + firmware_version) printer = Printer() self.printer = printer Path.printer = printer printer.firmware_version = firmware_version # check for config files if not os.path.exists("/etc/redeem/default.cfg"): logging.error( "/etc/redeem/default.cfg does not exist, this file is required for operation" ) sys.exit() # maybe use something more graceful? if not os.path.exists("/etc/redeem/local.cfg"): logging.info("/etc/redeem/local.cfg does not exist, Creating one") os.mknod("/etc/redeem/local.cfg") # Parse the config files. printer.config = CascadingConfigParser([ '/etc/redeem/default.cfg', '/etc/redeem/printer.cfg', '/etc/redeem/local.cfg' ]) # Get the revision and loglevel from the Config file level = self.printer.config.getint('System', 'loglevel') if level > 0: logging.getLogger().setLevel(level) # Set up additional logging, if present: if self.printer.config.getboolean('System', 'log_to_file'): logfile = self.printer.config.get('System', 'logfile') formatter = '%(asctime)s %(name)-12s %(levelname)-8s %(message)s' printer.redeem_logging_handler = logging.handlers.RotatingFileHandler( logfile, maxBytes=2 * 1024 * 1024) printer.redeem_logging_handler.setFormatter( logging.Formatter(formatter)) printer.redeem_logging_handler.setLevel(level) logging.getLogger().addHandler(printer.redeem_logging_handler) logging.info("-- Logfile configured --") # Find out which capes are connected self.printer.config.parse_capes() self.revision = self.printer.config.replicape_revision if self.revision: logging.info("Found Replicape rev. " + self.revision) else: logging.warning("Oh no! No Replicape present!") self.revision = "00B3" # We set it to 5 axis by default Path.NUM_AXES = 5 if self.printer.config.reach_revision: logging.info("Found Reach rev. " + self.printer.config.reach_revision) if self.printer.config.reach_revision == "00A0": Path.NUM_AXES = 8 elif self.printer.config.reach_revision == "00B0": Path.NUM_AXES = 7 if self.revision in ["00A4", "0A4A", "00A3"]: PWM.set_frequency(100) elif self.revision in ["00B1", "00B2", "00B3"]: PWM.set_frequency(1000) # Test the alarm framework Alarm.printer = self.printer Alarm.executor = AlarmExecutor() alarm = Alarm(Alarm.ALARM_TEST, "Alarm framework operational") # Init the Watchdog timer printer.watchdog = Watchdog() # Enable PWM and steppers printer.enable = Enable("P9_41") printer.enable.set_disabled() # Init the Paths Path.axis_config = printer.config.getint('Geometry', 'axis_config') # Init the end stops EndStop.inputdev = self.printer.config.get("Endstops", "inputdev") # Set up key listener Key_pin.listener = Key_pin_listener(EndStop.inputdev) for es in ["Z2", "Y2", "X2", "Z1", "Y1", "X1"]: # Order matches end stop inversion mask in Firmware pin = self.printer.config.get("Endstops", "pin_" + es) keycode = self.printer.config.getint("Endstops", "keycode_" + es) invert = self.printer.config.getboolean("Endstops", "invert_" + es) self.printer.end_stops[es] = EndStop(printer, pin, keycode, es, invert) self.printer.end_stops[es].stops = self.printer.config.get( 'Endstops', 'end_stop_' + es + '_stops') # Init the 5 Stepper motors (step, dir, fault, DAC channel, name) if self.revision == "00A3": printer.steppers["X"] = Stepper_00A3("GPIO0_27", "GPIO1_29", "GPIO2_4", 0, "X") printer.steppers["Y"] = Stepper_00A3("GPIO1_12", "GPIO0_22", "GPIO2_5", 1, "Y") printer.steppers["Z"] = Stepper_00A3("GPIO0_23", "GPIO0_26", "GPIO0_15", 2, "Z") printer.steppers["E"] = Stepper_00A3("GPIO1_28", "GPIO1_15", "GPIO2_1", 3, "E") printer.steppers["H"] = Stepper_00A3("GPIO1_13", "GPIO1_14", "GPIO2_3", 4, "H") elif self.revision == "00B1": printer.steppers["X"] = Stepper_00B1("GPIO0_27", "GPIO1_29", "GPIO2_4", 11, 0, "X") printer.steppers["Y"] = Stepper_00B1("GPIO1_12", "GPIO0_22", "GPIO2_5", 12, 1, "Y") printer.steppers["Z"] = Stepper_00B1("GPIO0_23", "GPIO0_26", "GPIO0_15", 13, 2, "Z") printer.steppers["E"] = Stepper_00B1("GPIO1_28", "GPIO1_15", "GPIO2_1", 14, 3, "E") printer.steppers["H"] = Stepper_00B1("GPIO1_13", "GPIO1_14", "GPIO2_3", 15, 4, "H") elif self.revision == "00B2": printer.steppers["X"] = Stepper_00B2("GPIO0_27", "GPIO1_29", "GPIO2_4", 11, 0, "X") printer.steppers["Y"] = Stepper_00B2("GPIO1_12", "GPIO0_22", "GPIO2_5", 12, 1, "Y") printer.steppers["Z"] = Stepper_00B2("GPIO0_23", "GPIO0_26", "GPIO0_15", 13, 2, "Z") printer.steppers["E"] = Stepper_00B2("GPIO1_28", "GPIO1_15", "GPIO2_1", 14, 3, "E") printer.steppers["H"] = Stepper_00B2("GPIO1_13", "GPIO1_14", "GPIO2_3", 15, 4, "H") elif self.revision == "00B3": printer.steppers["X"] = Stepper_00B3("GPIO0_27", "GPIO1_29", 90, 11, 0, "X") printer.steppers["Y"] = Stepper_00B3("GPIO1_12", "GPIO0_22", 91, 12, 1, "Y") printer.steppers["Z"] = Stepper_00B3("GPIO0_23", "GPIO0_26", 92, 13, 2, "Z") printer.steppers["E"] = Stepper_00B3("GPIO1_28", "GPIO1_15", 93, 14, 3, "E") printer.steppers["H"] = Stepper_00B3("GPIO1_13", "GPIO1_14", 94, 15, 4, "H") elif self.revision in ["00A4", "0A4A"]: printer.steppers["X"] = Stepper_00A4("GPIO0_27", "GPIO1_29", "GPIO2_4", 0, 0, "X") printer.steppers["Y"] = Stepper_00A4("GPIO1_12", "GPIO0_22", "GPIO2_5", 1, 1, "Y") printer.steppers["Z"] = Stepper_00A4("GPIO0_23", "GPIO0_26", "GPIO0_15", 2, 2, "Z") printer.steppers["E"] = Stepper_00A4("GPIO1_28", "GPIO1_15", "GPIO2_1", 3, 3, "E") printer.steppers["H"] = Stepper_00A4("GPIO1_13", "GPIO1_14", "GPIO2_3", 4, 4, "H") # Init Reach steppers, if present. if printer.config.reach_revision == "00A0": printer.steppers["A"] = Stepper_reach_00A4("GPIO2_2", "GPIO1_18", "GPIO0_14", 5, 5, "A") printer.steppers["B"] = Stepper_reach_00A4("GPIO1_16", "GPIO0_5", "GPIO0_14", 6, 6, "B") printer.steppers["C"] = Stepper_reach_00A4("GPIO0_3", "GPIO3_19", "GPIO0_14", 7, 7, "C") elif printer.config.reach_revision == "00B0": printer.steppers["A"] = Stepper_reach_00B0("GPIO1_16", "GPIO0_5", "GPIO0_3", 5, 5, "A") printer.steppers["B"] = Stepper_reach_00B0("GPIO2_2", "GPIO0_14", "GPIO0_3", 6, 6, "B") # Enable the steppers and set the current, steps pr mm and # microstepping for name, stepper in self.printer.steppers.iteritems(): stepper.in_use = printer.config.getboolean('Steppers', 'in_use_' + name) stepper.direction = printer.config.getint('Steppers', 'direction_' + name) stepper.has_endstop = printer.config.getboolean( 'Endstops', 'has_' + name) stepper.set_current_value( printer.config.getfloat('Steppers', 'current_' + name)) stepper.set_steps_pr_mm( printer.config.getfloat('Steppers', 'steps_pr_mm_' + name)) stepper.set_microstepping( printer.config.getint('Steppers', 'microstepping_' + name)) stepper.set_decay( printer.config.getint("Steppers", "slow_decay_" + name)) # Add soft end stops Path.soft_min[Path.axis_to_index(name)] = printer.config.getfloat( 'Endstops', 'soft_end_stop_min_' + name) Path.soft_max[Path.axis_to_index(name)] = printer.config.getfloat( 'Endstops', 'soft_end_stop_max_' + name) slave = printer.config.get('Steppers', 'slave_' + name) if slave: Path.add_slave(name, slave) logging.debug("Axis " + name + " has slave " + slave) # Commit changes for the Steppers #Stepper.commit() Stepper.printer = printer # Delta printer setup if Path.axis_config == Path.AXIS_CONFIG_DELTA: opts = [ "Hez", "L", "r", "Ae", "Be", "Ce", "A_radial", "B_radial", "C_radial", "A_tangential", "B_tangential", "C_tangential" ] for opt in opts: Delta.__dict__[opt] = printer.config.getfloat('Delta', opt) Delta.recalculate() # Discover and add all DS18B20 cold ends. import glob paths = glob.glob("/sys/bus/w1/devices/28-*/w1_slave") logging.debug("Found cold ends: " + str(paths)) for i, path in enumerate(paths): self.printer.cold_ends.append(ColdEnd(path, "ds18b20-" + str(i))) logging.info("Found Cold end " + str(i) + " on " + path) # Make Mosfets, thermistors and extruders heaters = ["E", "H", "HBP"] if self.printer.config.reach_revision: heaters.extend(["A", "B", "C"]) for e in heaters: # Mosfets channel = self.printer.config.getint("Heaters", "mosfet_" + e) self.printer.mosfets[e] = Mosfet(channel) # Thermistors adc = self.printer.config.get("Heaters", "path_adc_" + e) chart = self.printer.config.get("Heaters", "temp_chart_" + e) resistance = self.printer.config.getfloat("Heaters", "resistance_" + e) self.printer.thermistors[e] = Thermistor(adc, "MOSFET " + e, chart, resistance) self.printer.thermistors[e].printer = printer # Extruders onoff = self.printer.config.getboolean('Heaters', 'onoff_' + e) prefix = self.printer.config.get('Heaters', 'prefix_' + e) if e != "HBP": self.printer.heaters[e] = Extruder(self.printer.steppers[e], self.printer.thermistors[e], self.printer.mosfets[e], e, onoff) else: self.printer.heaters[e] = HBP(self.printer.thermistors[e], self.printer.mosfets[e], onoff) self.printer.heaters[e].prefix = prefix self.printer.heaters[e].P = self.printer.config.getfloat( 'Heaters', 'pid_p_' + e) self.printer.heaters[e].I = self.printer.config.getfloat( 'Heaters', 'pid_i_' + e) self.printer.heaters[e].D = self.printer.config.getfloat( 'Heaters', 'pid_d_' + e) # Min/max settings self.printer.heaters[e].min_temp = self.printer.config.getfloat( 'Heaters', 'min_temp_' + e) self.printer.heaters[e].max_temp = self.printer.config.getfloat( 'Heaters', 'max_temp_' + e) self.printer.heaters[ e].max_temp_rise = self.printer.config.getfloat( 'Heaters', 'max_rise_temp_' + e) self.printer.heaters[ e].max_temp_fall = self.printer.config.getfloat( 'Heaters', 'max_fall_temp_' + e) # Init the three fans. Argument is PWM channel number self.printer.fans = [] if self.revision == "00A3": self.printer.fans.append(Fan(0)) self.printer.fans.append(Fan(1)) self.printer.fans.append(Fan(2)) elif self.revision == "0A4A": self.printer.fans.append(Fan(8)) self.printer.fans.append(Fan(9)) self.printer.fans.append(Fan(10)) elif self.revision in ["00B1", "00B2", "00B3"]: self.printer.fans.append(Fan(7)) self.printer.fans.append(Fan(8)) self.printer.fans.append(Fan(9)) self.printer.fans.append(Fan(10)) if printer.config.reach_revision == "00A0": self.printer.fans.append(Fan(14)) self.printer.fans.append(Fan(15)) self.printer.fans.append(Fan(7)) # Disable all fans for f in self.printer.fans: f.set_value(0) # Init the servos printer.servos = [] servo_nr = 0 while (printer.config.has_option("Servos", "servo_" + str(servo_nr) + "_enable")): if printer.config.getboolean("Servos", "servo_" + str(servo_nr) + "_enable"): channel = printer.config.get( "Servos", "servo_" + str(servo_nr) + "_channel") pulse_min = printer.config.getfloat( "Servos", "servo_" + str(servo_nr) + "_pulse_min") pulse_max = printer.config.getfloat( "Servos", "servo_" + str(servo_nr) + "_pulse_max") angle_min = printer.config.getfloat( "Servos", "servo_" + str(servo_nr) + "_angle_min") angle_max = printer.config.getfloat( "Servos", "servo_" + str(servo_nr) + "_angle_max") angle_init = printer.config.getfloat( "Servos", "servo_" + str(servo_nr) + "_angle_init") s = Servo(channel, pulse_min, pulse_max, angle_min, angle_max, angle_init) printer.servos.append(s) logging.info("Added servo " + str(servo_nr)) servo_nr += 1 # Connect thermitors to fans for t, therm in self.printer.heaters.iteritems(): for f, fan in enumerate(self.printer.fans): if not self.printer.config.has_option( 'Cold-ends', "connect-therm-{}-fan-{}".format(t, f)): continue if printer.config.getboolean( 'Cold-ends', "connect-therm-{}-fan-{}".format(t, f)): c = Cooler(therm, fan, "Cooler-{}-{}".format(t, f), True) # Use ON/OFF on these. c.ok_range = 4 opt_temp = "therm-{}-fan-{}-target_temp".format(t, f) if printer.config.has_option('Cold-ends', opt_temp): target_temp = printer.config.getfloat( 'Cold-ends', opt_temp) else: target_temp = 60 c.set_target_temperature(target_temp) c.enable() printer.coolers.append(c) logging.info("Cooler connects therm {} with fan {}".format( t, f)) # Connect fans to M106 printer.controlled_fans = [] for i, fan in enumerate(self.printer.fans): if not self.printer.config.has_option( 'Cold-ends', "add-fan-{}-to-M106".format(i)): continue if self.printer.config.getboolean('Cold-ends', "add-fan-{}-to-M106".format(i)): printer.controlled_fans.append(self.printer.fans[i]) logging.info("Added fan {} to M106/M107".format(i)) # Connect the colds to fans for ce, cold_end in enumerate(self.printer.cold_ends): for f, fan in enumerate(self.printer.fans): option = "connect-ds18b20-{}-fan-{}".format(ce, f) if self.printer.config.has_option('Cold-ends', option): if self.printer.config.getboolean('Cold-ends', option): c = Cooler(cold_end, fan, "Cooler-ds18b20-{}-{}".format(ce, f), False) c.ok_range = 4 opt_temp = "cooler_{}_target_temp".format(ce) if printer.config.has_option('Cold-ends', opt_temp): target_temp = printer.config.getfloat( 'Cold-ends', opt_temp) else: target_temp = 60 c.set_target_temperature(target_temp) c.enable() printer.coolers.append(c) logging.info( "Cooler connects temp sensor ds18b20 {} with fan {}" .format(ce, f)) # Init roatray encs. printer.filament_sensors = [] # Init rotary encoders printer.rotary_encoders = [] for ex in ["E", "H", "A", "B", "C"]: if not printer.config.has_option('Rotary-encoders', "enable-{}".format(ex)): continue if printer.config.getboolean("Rotary-encoders", "enable-{}".format(ex)): logging.debug("Rotary encoder {} enabled".format(ex)) event = printer.config.get("Rotary-encoders", "event-{}".format(ex)) cpr = printer.config.getint("Rotary-encoders", "cpr-{}".format(ex)) diameter = printer.config.getfloat("Rotary-encoders", "diameter-{}".format(ex)) r = RotaryEncoder(event, cpr, diameter) printer.rotary_encoders.append(r) # Append as Filament Sensor ext_nr = Path.axis_to_index(ex) - 3 sensor = FilamentSensor(ex, r, ext_nr, printer) alarm_level = printer.config.getfloat( "Filament-sensors", "alarm-level-{}".format(ex)) logging.debug("Alarm level" + str(alarm_level)) sensor.alarm_level = alarm_level printer.filament_sensors.append(sensor) # Make a queue of commands self.printer.commands = JoinableQueue(10) # Make a queue of commands that should not be buffered self.printer.sync_commands = JoinableQueue() self.printer.unbuffered_commands = JoinableQueue(10) # Bed compensation matrix Path.matrix_bed_comp = printer.load_bed_compensation_matrix() Path.matrix_bed_comp_inv = np.linalg.inv(Path.matrix_bed_comp) logging.debug("Loaded bed compensation matrix: \n" + str(Path.matrix_bed_comp)) for axis in printer.steppers.keys(): i = Path.axis_to_index(axis) Path.max_speeds[i] = printer.config.getfloat( 'Planner', 'max_speed_' + axis.lower()) Path.min_speeds[i] = printer.config.getfloat( 'Planner', 'min_speed_' + axis.lower()) Path.jerks[i] = printer.config.getfloat('Planner', 'max_jerk_' + axis.lower()) Path.home_speed[i] = printer.config.getfloat( 'Homing', 'home_speed_' + axis.lower()) Path.home_backoff_speed[i] = printer.config.getfloat( 'Homing', 'home_backoff_speed_' + axis.lower()) Path.home_backoff_offset[i] = printer.config.getfloat( 'Homing', 'home_backoff_offset_' + axis.lower()) Path.steps_pr_meter[i] = printer.steppers[axis].get_steps_pr_meter( ) Path.backlash_compensation[i] = printer.config.getfloat( 'Steppers', 'backlash_' + axis.lower()) dirname = os.path.dirname(os.path.realpath(__file__)) # Create the firmware compiler pru_firmware = PruFirmware(dirname + "/firmware/firmware_runtime.p", dirname + "/firmware/firmware_runtime.bin", dirname + "/firmware/firmware_endstops.p", dirname + "/firmware/firmware_endstops.bin", self.printer, "/usr/bin/pasm") printer.move_cache_size = printer.config.getfloat( 'Planner', 'move_cache_size') printer.print_move_buffer_wait = printer.config.getfloat( 'Planner', 'print_move_buffer_wait') printer.min_buffered_move_time = printer.config.getfloat( 'Planner', 'min_buffered_move_time') printer.max_buffered_move_time = printer.config.getfloat( 'Planner', 'max_buffered_move_time') self.printer.processor = GCodeProcessor(self.printer) self.printer.plugins = PluginsController(self.printer) # Path planner travel_default = False center_default = False home_default = False # Setting acceleration before PathPlanner init for axis in printer.steppers.keys(): Path.acceleration[Path.axis_to_index( axis)] = printer.config.getfloat( 'Planner', 'acceleration_' + axis.lower()) self.printer.path_planner = PathPlanner(self.printer, pru_firmware) for axis in printer.steppers.keys(): i = Path.axis_to_index(axis) # Sometimes soft_end_stop aren't defined to be at the exact hardware boundary. # Adding 100mm for searching buffer. if printer.config.has_option('Geometry', 'travel_' + axis.lower()): printer.path_planner.travel_length[ axis] = printer.config.getfloat('Geometry', 'travel_' + axis.lower()) else: printer.path_planner.travel_length[axis] = ( Path.soft_max[i] - Path.soft_min[i]) + .1 if axis in ['X', 'Y', 'Z']: travel_default = True if printer.config.has_option('Geometry', 'offset_' + axis.lower()): printer.path_planner.center_offset[ axis] = printer.config.getfloat('Geometry', 'offset_' + axis.lower()) else: printer.path_planner.center_offset[axis] = ( Path.soft_min[i] if Path.home_speed[i] > 0 else Path.soft_max[i]) if axis in ['X', 'Y', 'Z']: center_default = True if printer.config.has_option('Homing', 'home_' + axis.lower()): printer.path_planner.home_pos[axis] = printer.config.getfloat( 'Homing', 'home_' + axis.lower()) else: printer.path_planner.home_pos[ axis] = printer.path_planner.center_offset[axis] if axis in ['X', 'Y', 'Z']: home_default = True if Path.axis_config == Path.AXIS_CONFIG_DELTA: if travel_default: logging.warning( "Axis travel (travel_*) set by soft limits, manual setup is recommended for a delta" ) if center_default: logging.warning( "Axis offsets (offset_*) set by soft limits, manual setup is recommended for a delta" ) if home_default: logging.warning( "Home position (home_*) set by soft limits or offset_*") logging.info("Home position will be recalculated...") # convert home_pos to effector space Az = printer.path_planner.home_pos['X'] Bz = printer.path_planner.home_pos['Y'] Cz = printer.path_planner.home_pos['Z'] z_offset = Delta.vertical_offset(Az, Bz, Cz) # vertical offset xyz = Delta.forward_kinematics2(Az, Bz, Cz) # effector position # The default home_pos, provided above, is based on effector space # coordinates for carriage positions. We need to transform these to # get where the effector actually is. xyz[2] += z_offset for i, a in enumerate(['X', 'Y', 'Z']): printer.path_planner.home_pos[a] = xyz[i] logging.info("Home position = %s" % str(printer.path_planner.home_pos)) # Enable Stepper timeout timeout = printer.config.getint('Steppers', 'timeout_seconds') printer.swd = StepperWatchdog(printer, timeout) if printer.config.getboolean('Steppers', 'use_timeout'): printer.swd.start() # Set up communication channels printer.comms["USB"] = USB(self.printer) printer.comms["Eth"] = Ethernet(self.printer) if Pipe.check_tty0tty() or Pipe.check_socat(): printer.comms["octoprint"] = Pipe(printer, "octoprint") printer.comms["toggle"] = Pipe(printer, "toggle") printer.comms["testing"] = Pipe(printer, "testing") printer.comms["testing_noret"] = Pipe(printer, "testing_noret") # Does not send "ok" printer.comms["testing_noret"].send_response = False else: logging.warning( "Neither tty0tty or socat is installed! No virtual tty pipes enabled" )
def __init__(self): """ Init """ logging.info("Redeem initializing " + version) printer = Printer() self.printer = printer # check for config files if not os.path.exists("/etc/redeem/default.cfg"): logging.error("/etc/redeem/default.cfg does not exist, this file is required for operation") sys.exit() # maybe use something more graceful? # Parse the config files. printer.config = CascadingConfigParser( ['/etc/redeem/default.cfg', '/etc/redeem/printer.cfg', '/etc/redeem/local.cfg']) # Find out which capes are connected self.printer.config.parse_capes() self.revision = self.printer.config.replicape_revision if self.revision: logging.info("Found Replicape rev. " + self.revision) Path.set_axes(5) else: logging.warning("Oh no! No Replicape present!") self.revision = "0A4A" # We set it to 5 axis by default Path.set_axes(5) if self.printer.config.reach_revision: Path.set_axes(8) logging.info("Found Reach rev. "+self.printer.config.reach_revision) # Get the revision and loglevel from the Config file level = self.printer.config.getint('System', 'loglevel') if level > 0: logging.getLogger().setLevel(level) if self.revision in ["00A4", "0A4A", "00A3"]: PWM.set_frequency(100) elif self.revision in ["00B1", "00B2"]: PWM.set_frequency(1000) # Init the Paths Path.axis_config = printer.config.getint('Geometry', 'axis_config') # Init the end stops EndStop.callback = self.end_stop_hit EndStop.inputdev = self.printer.config.get("Endstops", "inputdev") for es in ["X1", "X2", "Y1", "Y2", "Z1", "Z2"]: pin = self.printer.config.get("Endstops", "pin_"+es) keycode = self.printer.config.getint("Endstops", "keycode_"+es) invert = self.printer.config.getboolean("Endstops", "invert_"+es) self.printer.end_stops[es] = EndStop(pin, keycode, es, invert) # Backwards compatibility with A3 if self.revision == "00A3": # Init the 5 Stepper motors (step, dir, fault, DAC channel, name) printer.steppers["X"] = Stepper_00A3("GPIO0_27", "GPIO1_29", "GPIO2_4" , 0, "X", 0, 0) printer.steppers["Y"] = Stepper_00A3("GPIO1_12", "GPIO0_22", "GPIO2_5" , 1, "Y", 1, 1) printer.steppers["Z"] = Stepper_00A3("GPIO0_23", "GPIO0_26", "GPIO0_15", 2, "Z", 2, 2) printer.steppers["E"] = Stepper_00A3("GPIO1_28", "GPIO1_15", "GPIO2_1" , 3, "E", 3, 3) printer.steppers["H"] = Stepper_00A3("GPIO1_13", "GPIO1_14", "GPIO2_3" , 4, "H", 4, 4) elif self.revision == "00B1": # Init the 5 Stepper motors (step, dir, fault, DAC channel, name) printer.steppers["X"] = Stepper_00B1("GPIO0_27", "GPIO1_29", "GPIO2_4" , 11, 0, "X", 0, 0) printer.steppers["Y"] = Stepper_00B1("GPIO1_12", "GPIO0_22", "GPIO2_5" , 12, 1, "Y", 1, 1) printer.steppers["Z"] = Stepper_00B1("GPIO0_23", "GPIO0_26", "GPIO0_15", 13, 2, "Z", 2, 2) printer.steppers["E"] = Stepper_00B1("GPIO1_28", "GPIO1_15", "GPIO2_1" , 14, 3, "E", 3, 3) printer.steppers["H"] = Stepper_00B1("GPIO1_13", "GPIO1_14", "GPIO2_3" , 15, 4, "H", 4, 4) elif self.revision == "00B2": # Init the 5 Stepper motors (step, dir, fault, DAC channel, name) printer.steppers["X"] = Stepper_00B2("GPIO0_27", "GPIO1_29", "GPIO2_4" , 11, 0, "X", 0, 0) printer.steppers["Y"] = Stepper_00B2("GPIO1_12", "GPIO0_22", "GPIO2_5" , 12, 1, "Y", 1, 1) printer.steppers["Z"] = Stepper_00B2("GPIO0_23", "GPIO0_26", "GPIO0_15", 13, 2, "Z", 2, 2) printer.steppers["E"] = Stepper_00B2("GPIO1_28", "GPIO1_15", "GPIO2_1" , 14, 3, "E", 3, 3) printer.steppers["H"] = Stepper_00B2("GPIO1_13", "GPIO1_14", "GPIO2_3" , 15, 4, "H", 4, 4) else: # Init the 5 Stepper motors (step, dir, fault, DAC channel, name) printer.steppers["X"] = Stepper_00A4("GPIO0_27", "GPIO1_29", "GPIO2_4" , 0, 0, "X", 0, 0) printer.steppers["Y"] = Stepper_00A4("GPIO1_12", "GPIO0_22", "GPIO2_5" , 1, 1, "Y", 1, 1) printer.steppers["Z"] = Stepper_00A4("GPIO0_23", "GPIO0_26", "GPIO0_15", 2, 2, "Z", 2, 2) printer.steppers["E"] = Stepper_00A4("GPIO1_28", "GPIO1_15", "GPIO2_1" , 3, 3, "E", 3, 3) printer.steppers["H"] = Stepper_00A4("GPIO1_13", "GPIO1_14", "GPIO2_3" , 4, 4, "H", 4, 4) if printer.config.reach_revision: printer.steppers["A"] = Stepper_00A4("GPIO2_2" , "GPIO1_18", "GPIO0_14", 5, 5, "A", 5, 5) printer.steppers["B"] = Stepper_00A4("GPIO1_14", "GPIO0_5" , "GPIO0_14", 6, 6, "B", 6, 6) printer.steppers["C"] = Stepper_00A4("GPIO0_3" , "GPIO3_19", "GPIO0_14", 7, 7, "C", 7, 7) # Enable the steppers and set the current, steps pr mm and # microstepping for name, stepper in self.printer.steppers.iteritems(): stepper.in_use = printer.config.getboolean('Steppers', 'in_use_' + name) stepper.direction = printer.config.getint('Steppers', 'direction_' + name) stepper.has_endstop = printer.config.getboolean('Endstops', 'has_' + name) stepper.set_current_value(printer.config.getfloat('Steppers', 'current_' + name)) stepper.set_steps_pr_mm(printer.config.getfloat('Steppers', 'steps_pr_mm_' + name)) stepper.set_microstepping(printer.config.getint('Steppers', 'microstepping_' + name)) stepper.set_decay(printer.config.getboolean("Steppers", "slow_decay_" + name)) # Add soft end stops Path.soft_min[Path.axis_to_index(name)] = printer.config.getfloat('Endstops', 'soft_end_stop_min_' + name) Path.soft_max[Path.axis_to_index(name)] = printer.config.getfloat('Endstops', 'soft_end_stop_max_' + name) # Commit changes for the Steppers #Stepper.commit() Stepper.printer = printer # Delta printer setup if Path.axis_config == Path.AXIS_CONFIG_DELTA: opts = ["Hez", "L", "r", "Ae", "Be", "Ce", "A_radial", "B_radial", "C_radial", "A_tangential", "B_tangential", "C_tangential" ] for opt in opts: Delta.__dict__[opt] = printer.config.getfloat('Delta', opt) Delta.recalculate() # Discover and add all DS18B20 cold ends. import glob paths = glob.glob("/sys/bus/w1/devices/28-*/w1_slave") logging.debug("Found cold ends: "+str(paths)) for i, path in enumerate(paths): self.printer.cold_ends.append(ColdEnd(path, "ds18b20-"+str(i))) logging.info("Found Cold end "+str(i)+" on " + path) # Make Mosfets, thermistors and extruders heaters = ["E", "H", "HBP"] if self.printer.config.reach_revision: heaters.extend(["A", "B", "C"]) for e in heaters: # Mosfets channel = self.printer.config.getint("Heaters", "mosfet_"+e) self.printer.mosfets[e] = Mosfet(channel) # Thermistors adc = self.printer.config.get("Heaters", "path_adc_"+e) chart = self.printer.config.get("Heaters", "temp_chart_"+e) resistance = self.printer.config.getfloat("Heaters", "resistance_"+e) self.printer.thermistors[e] = Thermistor(adc, "MOSFET "+e, chart, resistance) self.printer.thermistors[e].printer = printer # Extruders onoff = self.printer.config.getboolean('Heaters', 'onoff_'+e) prefix = self.printer.config.get('Heaters', 'prefix_'+e) if e != "HBP": self.printer.heaters[e] = Extruder( self.printer.steppers[e], self.printer.thermistors[e], self.printer.mosfets[e], e, onoff) else: self.printer.heaters[e] = HBP( self.printer.thermistors[e], self.printer.mosfets[e], onoff) self.printer.heaters[e].prefix = prefix self.printer.heaters[e].P = self.printer.config.getfloat('Heaters', 'pid_p_'+e) self.printer.heaters[e].I = self.printer.config.getfloat('Heaters', 'pid_i_'+e) self.printer.heaters[e].D = self.printer.config.getfloat('Heaters', 'pid_d_'+e) # Init the three fans. Argument is PWM channel number self.printer.fans = [] if self.revision == "00A3": self.printer.fans.append(Fan(0)) self.printer.fans.append(Fan(1)) self.printer.fans.append(Fan(2)) elif self.revision == "0A4A": self.printer.fans.append(Fan(8)) self.printer.fans.append(Fan(9)) self.printer.fans.append(Fan(10)) elif self.revision in ["00B1", "00B2"]: self.printer.fans.append(Fan(7)) self.printer.fans.append(Fan(8)) self.printer.fans.append(Fan(9)) self.printer.fans.append(Fan(10)) # Disable all fans for f in self.printer.fans: f.set_value(0) # Init the servos printer.servos = [] servo_nr = 0 while(printer.config.has_option("Servos", "servo_"+str(servo_nr)+"_enable")): if printer.config.getboolean("Servos", "servo_"+str(servo_nr)+"_enable"): channel = printer.config.get("Servos", "servo_"+str(servo_nr)+"_channel") angle_init = printer.config.getint("Servos", "servo_"+str(servo_nr)+"_angle_init") s = Servo(channel, 0.1, 0.2, angle_init) printer.servos.append(s) logging.info("Added servo "+str(servo_nr)) servo_nr += 1 # Connect thermitors to fans for t, therm in self.printer.heaters.iteritems(): for f, fan in enumerate(self.printer.fans): if self.printer.config.getboolean('Cold-ends', "connect-therm-{}-fan-{}".format(t, f)): c = Cooler(therm, fan, "Cooler-{}-{}".format(t, f), False) c.ok_range = 4 c.set_target_temperature(60) c.enable() self.printer.coolers.append(c) logging.info("Cooler connects therm {} with fan {}".format(t, f)) # Connect fans to M106 printer.controlled_fans = [] for i, fan in enumerate(self.printer.fans): if self.printer.config.getboolean('Cold-ends', "add-fan-{}-to-M106".format(i)): printer.controlled_fans.append(self.printer.fans[i]) logging.info("Added fan {} to M106/M107".format(i)) # Connect the colds to fans for ce, cold_end in enumerate(self.printer.cold_ends): for f, fan in enumerate(self.printer.fans): option = "connect-ds18b20-{}-fan-{}".format(ce, f) if self.printer.config.has_option('Cold-ends', option): if self.printer.config.getboolean('Cold-ends', option): c = Cooler(cold_end, fan, "Cooler-ds18b20-{}-{}".format(ce, f), False) c.ok_range = 4 c.set_target_temperature(60) c.enable() self.printer.coolers.append(c) logging.info("Cooler connects temp sensor ds18b20 {} with fan {}".format(ce, f)) # Make a queue of commands self.printer.commands = JoinableQueue(10) # Make a queue of commands that should not be buffered self.printer.sync_commands = JoinableQueue() self.printer.unbuffered_commands = JoinableQueue(10) # Bed compensation matrix Path.matrix_bed_comp = printer.load_bed_compensation_matrix() Path.matrix_bed_comp_inv = np.linalg.inv(Path.matrix_bed_comp) logging.debug("Loaded bed compensation matrix: \n"+str(Path.matrix_bed_comp)) for axis in printer.steppers.keys(): i = Path.axis_to_index(axis) Path.max_speeds[i] = printer.config.getfloat('Planner', 'max_speed_'+axis.lower()) Path.home_speed[i] = printer.config.getfloat('Homing', 'home_speed_'+axis.lower()) Path.home_backoff_speed[i] = printer.config.getfloat('Homing', 'home_backoff_speed_'+axis.lower()) Path.home_backoff_offset[i] = printer.config.getfloat('Homing', 'home_backoff_offset_'+axis.lower()) Path.steps_pr_meter[i] = printer.steppers[axis].get_steps_pr_meter() Path.backlash_compensation[i] = printer.config.getfloat('Steppers', 'backlash_'+axis.lower()) dirname = os.path.dirname(os.path.realpath(__file__)) # Create the firmware compiler pru_firmware = PruFirmware( dirname + "/firmware/firmware_runtime.p", dirname + "/firmware/firmware_runtime.bin", dirname + "/firmware/firmware_endstops.p", dirname + "/firmware/firmware_endstops.bin", self.revision, self.printer.config, "/usr/bin/pasm") printer.maxJerkXY = printer.config.getfloat('Planner', 'maxJerk_xy') printer.maxJerkZ = printer.config.getfloat('Planner', 'maxJerk_z') printer.maxJerkEH = printer.config.getfloat('Planner', 'maxJerk_eh') printer.move_cache_size = printer.config.getfloat('Planner', 'move_cache_size') printer.print_move_buffer_wait = printer.config.getfloat('Planner', 'print_move_buffer_wait') printer.min_buffered_move_time = printer.config.getfloat('Planner', 'min_buffered_move_time') printer.max_buffered_move_time = printer.config.getfloat('Planner', 'max_buffered_move_time') self.printer.processor = GCodeProcessor(self.printer) self.printer.plugins = PluginsController(self.printer) # Path planner travel_default = False center_default = False home_default = False # Setting acceleration before PathPlanner init for axis in printer.steppers.keys(): printer.acceleration[Path.axis_to_index(axis)] = printer.config.getfloat( 'Planner', 'acceleration_' + axis.lower()) self.printer.path_planner = PathPlanner(self.printer, pru_firmware) for axis in printer.steppers.keys(): i = Path.axis_to_index(axis) # Sometimes soft_end_stop aren't defined to be at the exact hardware boundary. # Adding 100mm for searching buffer. if printer.config.has_option('Geometry', 'travel_' + axis.lower()): printer.path_planner.travel_length[axis] = printer.config.getfloat('Geometry', 'travel_' + axis.lower()) else: printer.path_planner.travel_length[axis] = (Path.soft_max[i] - Path.soft_min[i]) + .1 if axis in ['X','Y','Z']: travel_default = True if printer.config.has_option('Geometry', 'offset_' + axis.lower()): printer.path_planner.center_offset[axis] = printer.config.getfloat('Geometry', 'offset_' + axis.lower()) else: printer.path_planner.center_offset[axis] =(Path.soft_min[i] if Path.home_speed[i] > 0 else Path.soft_max[i]) if axis in ['X','Y','Z']: center_default = True if printer.config.has_option('Homing', 'home_' + axis.lower()): printer.path_planner.home_pos[axis] = printer.config.getfloat('Homing', 'home_' + axis.lower()) else: printer.path_planner.home_pos[axis] = printer.path_planner.center_offset[axis] if axis in ['X','Y','Z']: home_default = True if Path.axis_config == Path.AXIS_CONFIG_DELTA: if travel_default: logging.warning("Axis travel (travel_*) set by soft limits, manual setup is recommended for a delta") if center_default: logging.warning("Axis offsets (offset_*) set by soft limits, manual setup is recommended for a delta") if home_default: logging.warning("Home position (home_*) set by soft limits or offset_*") logging.info("Home position will be recalculated...") # convert home_pos to effector space Az = printer.path_planner.home_pos['X'] Bz = printer.path_planner.home_pos['Y'] Cz = printer.path_planner.home_pos['Z'] z_offset = Delta.vertical_offset(Az,Bz,Cz) # vertical offset xyz = Delta.forward_kinematics2(Az, Bz, Cz) # effector position # The default home_pos, provided above, is based on effector space # coordinates for carriage positions. We need to transform these to # get where the effector actually is. xyz[2] += z_offset for i, a in enumerate(['X','Y','Z']): printer.path_planner.home_pos[a] = xyz[i] logging.info("Home position = %s"%str(printer.path_planner.home_pos)) if Path.axis_config == Path.AXIS_CONFIG_SCARA: if travel_default: logging.warning("Axis travel (travel_*) set by soft limits, manual setup is recommended for a scara") if center_default: logging.warning("Axis offsets (offset_*) set by soft limits, manual setup is recommended for a scara") if home_default: logging.warning("Home position (home_*) set by soft limits or offset_*") logging.info("Home position will be recalculated...") # convert home_pos to effector space #A = printer.path_planner.home_pos['X'] #B = printer.path_planner.home_pos['Y'] #C = printer.path_planner.home_pos['Z'] #z_offset = Delta.vertical_offset(Az,Bz,Cz) # vertical offset #xyz = Scara.forward_kinematics(A, B, C) # effector position # don't cpnvert home_pos to effector spac # home offset is defined in cartesian space xyz = np.array([printer.path_planner.home_pos['X'],printer.path_planner.home_pos['Y'],printer.path_planner.home_pos['Z']]) # The default home_pos, provided above, is based on effector space # coordinates for carriage positions. We need to transform these to # get where the effector actually is. #xyz[2] += z_offset for i, a in enumerate(['X','Y','Z']): printer.path_planner.home_pos[a] = xyz[i] logging.info("Home position = %s"%str(printer.path_planner.home_pos)) # Enable PWM and steppers printer.enable = Enable("P9_41") printer.enable.set_enabled() # Set up communication channels printer.comms["USB"] = USB(self.printer) printer.comms["Eth"] = Ethernet(self.printer) if Pipe.check_tty0tty() or Pipe.check_socat(): printer.comms["octoprint"] = Pipe(printer, "octoprint") printer.comms["toggle"] = Pipe(printer, "toggle") printer.comms["testing"] = Pipe(printer, "testing") printer.comms["testing_noret"] = Pipe(printer, "testing_noret") # Does not send "ok" printer.comms["testing_noret"].send_response = False else: logging.warning("Neither tty0tty or socat is installed! No virtual tty pipes enabled")