Benutzer-Werkzeuge

Webseiten-Werkzeuge


Seitenleiste

mechatronik:sose24:remote-plotter:code

Inhaltsverzeichnis

Code

Falls Github spinnt :)

Backend

main.cpp
#include "DrawRobot.hpp"
 
#define cm
 
DrawRobot<Arm> robot;
 
void setup()
{
    Serial.begin(115200);
 
    Motor root(AccelStepper(8,4,6,5,7), 4076);
    Motor ext(AccelStepper(8,8,9,10,11), 4076);
 
    robot = {
    .axies = Arm(11 cm, 11.5 cm, root, ext),
        .gantry = Gantry(6, 7)
    };
 
    // robot.axies.moveTo({22.5,0});
    robot.axies.moveTo({11,11.5});
 
}
void loop()
{
    int cmd = Serial.parseInt();
    switch(cmd){
        case 0:{
            int x = Serial.parseInt();
            int y = Serial.parseInt();
            robot.axies.moveTo({x,y});
            break;
        }
        case 1: {
            int tool = Serial.parseInt();
            robot.gantry.setTool(tool); // ist tool
        }
 
    }
 
}

Axies

Axies.hpp
#pragma once
#include "AccelStepper.h"
#include "MultiStepper.h"
 
#ifndef PI
#define PI 3.14159265358979
#endif
 
struct Point {double x,y;};
struct Angles {double root, ext;};
 
class Axies
{
    public:
        virtual void moveTo(Point p)=0;
};
 
struct Motor
{
    AccelStepper stepper;
    int stepsPerRev=-1;
    Motor(AccelStepper stepper, int stepsPerRev, int speed=4000):
        stepper(stepper), stepsPerRev(stepsPerRev)
    {
        this->stepper.setAcceleration(1000);
        this->stepper.setMaxSpeed(speed);
        this->stepper.setSpeed(speed);
    }
 
    long getSteps(double deg)
    {
        return deg/360.0*stepsPerRev;
    }
};
 
class Arm
{
    double rootLen, extLen;
    Motor root, ext;
    MultiStepper ms;
    public:
        Arm(double rootLen, double extLen, Motor root, Motor ext);
        void moveTo(Point p);
    private:
        //calculates the angles of the two sections so the end of the second is at point p
        Angles pointToAngles(Point p);
};
Axies.cpp
#include "Axies.hpp"
 
Arm::Arm(double rootLen, double extLen, Motor root, Motor ext) :
    rootLen(rootLen), extLen(extLen), ms(), root(root), ext(ext)
{
    ms.addStepper(root.stepper);
    ms.addStepper(ext.stepper);
}
 
 
void Arm::moveTo(Point p)
{
    Angles angle = pointToAngles(p); // 0-360
    Serial.println("Root: " + String(angle.root) + "°->" + String(root.getSteps(angle.root)));
    Serial.println("Ext: " + String(angle.ext) + "°->" + String(ext.getSteps(angle.root)));
    long pos[2] = {root.getSteps(angle.root), ext.getSteps(angle.ext)};
    ms.moveTo(pos);
    ms.runSpeedToPosition();
}
 
Angles Arm::pointToAngles(Point p)
{
    double ph2= acos(
        (p.x*p.x+p.y*p.y-rootLen*rootLen-extLen*extLen)/
            (2*rootLen*extLen));
 
    double phi1 = atan2(p.y,p.x)
        -atan2(extLen*sin(ph2),
                (rootLen+extLen*cos(ph2)));
 
    return {phi1/PI*180, ph2/PI*180};
}

Gantry

Gantry.hpp
#pragma once
#include <Servo.h>
 
class Gantry
{
    Servo use, // servo for lowering tool
        select;// Servo to switch between tools
               // ^ currently unused
 
    public:
        Gantry(int usePin, int selectPin)
        {
            use.attach(usePin);
            select.attach(selectPin);
        }
        enum Tool {
            NONE,
            PEN
        };
        void setTool(Tool tool);
 
};
Gantry.cpp
#include "Gantry.hpp"
 
void Gantry::setTool(Tool tool)
{
    // maybe second servo for tool switch
 
    // dummy implementation
    use.write(180*(tool==PEN));
}

Frontend

Dieses Programm ist mithilfe des Tkinter-Moduls geschrieben. Hiermt hat man eine Zeichenoberfläche, welche die aktuelle Zeichnung speichern kann als auch die Koordinaten der Zeichnung während Laufzeit ausgibt und an den Arduino schicken kann.(?)

draw_mtrobo.py
from tkinter import *
 
class Point:
    def __init__(self, x, y, color="black"):
        self.x = x
        self.y = y
        self.color = color
 
 
 
class GUI:
    def __init__(self):
        #gneral attributes
        self.last = None
        self.points = []
 
        #tkinter stuff
        self.widget_bgc = "black"
        self.widget_fgc = "lawn green"
        self.draw_color = "back"
        self.window = Tk()
        self.window.geometry("500x550")
        self.window.title("Frontend")
        self.window.config(bg=self.widget_bgc)
        self.canvas = Canvas(self.window, height=475, width=465)
        self.canvas.place(x=15, y=15)
        # self.canvas.bind("<B1-Motion>", self.draw)
        self.canvas.bind("<Button-1>", self.draw_dot)
        self.canvas.bind("<ButtonRelease-1>", self.reset_last)
        self.clear_btn = Button(self.window, text="clear", command=self.clear_canvas, bg=self.widget_bgc, fg=self.widget_fgc)
        self.clear_btn.place(x=15, y=510)
        self.export_btn = Button(self.window, text="export", command=self.export, bg=self.widget_bgc, fg=self.widget_fgc)
        self.export_btn.place(x=55, y=510)
        self.import_btn = Button(self.window, text="import", command=self.import_, bg=self.widget_bgc, fg=self.widget_fgc)
        self.import_btn.place(x=105, y=510)
        self.size = IntVar()
        self.size.set(7)
        self.slider = Scale(self.window, from_=1, to=20, tickinterval=0, orient=HORIZONTAL, variable=self.size, bg=self.widget_bgc, fg=self.widget_fgc, highlightbackground=self.widget_fgc)
        self.slider.place(x=375, y=505)
        self.window.mainloop()
 
 
    def clear_canvas(self):
        self.canvas.delete("all")
        self.points.clear()
 
    def export(self):
        f = open("export.txt", "w")
        result = ""
        for point in self.points:
            if point == "DONE":
                result += "DONE\n"
            else:
                result += str(point[0]) + "|" + str(point[1]) + "\n"
        f.write(result)
        f.close()
 
    def import_(self):
        self.canvas.delete("all")
        f = open("export.txt", "r")
        content = f.readlines()
        f.close()
        last = None
        for i, line in enumerate(content):
            line = line.replace("\n", "")
            if line == "DONE":
                last = None
            else:
                coords = line.split("|")
                x = int(coords[0])
                y = int(coords[1])
                if last:
                    self.canvas.create_line(x, y, last[0] , last[1], width=self.size.get(), fill = "black", capstyle=ROUND, joinstyle=BEVEL)
                if i == len(content) or content[i+1] == "DONE\n":
                    self.canvas.create_line(x, y, x, y, width=self.size.get(), fill = "black", capstyle=ROUND, joinstyle=BEVEL)
                last = (x, y)
 
 
 
 
    def reset_last(self, event):
        if self.last:
            self.canvas.create_line(self.last.x, self.last.y, event.x , event.y, width=self.size.get(), fill = "black", capstyle=ROUND, joinstyle=BEVEL)
        self.last = None
        self.points.append("DONE")
        print("PEN UP")
 
    def draw_dot(self, event):
        print("LINE START", event.x, event.y)
        print("PEN DOWN")
        if self.last == None:
            self.points.append((event.x, event.y))
            self.last = Point(event.x, event.y)
 
    def draw(self, event):
        print(event.x, event.y)
        if self.last:
            self.points.append((event.x, event.y))
            self.canvas.create_line(self.last.x, self.last.y, event.x, event.y, width= self.size.get(), fill = self.last.color, capstyle=ROUND, joinstyle=BEVEL)
        self.last = Point(event.x, event.y)
 
g = GUI()
mechatronik/sose24/remote-plotter/code.txt · Zuletzt geändert: 2024/07/31 10:29 von TPfoch