上位机&下位机

import serial

import math

import time

from tkinter import *

from tkinter.filedialog import askopenfilename

from tkinter import messagebox

import cv2

import numpy as np

import threading

import inspect

import ctypes

import math

# opencv部分可以改进 简化轮廓

# 解决tkinter卡死问题

'''

通信格式说明:

    波特率 9600

        PC发送:

        第1字节 xDir

        第2字节 yDir

        第3字节 zState

        第4&5字节 xPS

        第6&7字节 yPS

    单片机发送: 0xff  表示打印完成

'''

# build serial

try:

    s = serial.Serial('com5', 9600, timeout=0.5)

except serial.serialutil.SerialException:

    print('串口未打开')

# 参数设置

m = 15  # 臂长1(cm)

n = 15  # 臂长2(cm)

MaxW = (2**0.5)*(m+n)  # weight底cm

MaxH = MaxW/2  # high 避开0 cm

print('MAXW:', MaxW, 'MAXH:', MaxH)

global Q

Q = 400

# globals

global w, new_thread, isb, osb, input, output, cv, menu, is_print_button, set_threshold, isCanny, CannyMin, CannyMax, iterations, fanse

global mpx, npx

fanse = False

# iterations迭代次数

isCanny = True

global contours

global lst  # list

global isfinish, pos

isfinish = False

cishu = -1  # 发送开始标志时 也会有接收

def readdata():

    global isfinish, cishu

    while True:

        inputdata = s.read(1)

        # if inputdata!=b'':

        #     print(inputdata)

        if inputdata == b'\xff':  # 打印完成

            isfinish = True  # 若发送0xff且坐标正确

            # 清空缓存 防止次数误加

            s.flushInput()

            cishu += 1

            print(cishu, "打印完成!")


 

def stop_thread(thread):

    tid = thread.ident

    exctype = SystemExit

    tid = ctypes.c_long(tid)

    if not inspect.isclass(exctype):

        exctype = type(exctype)

    res = ctypes.pythonapi.PyThreadState_SetAsyncExc(

        tid, ctypes.py_object(exctype))

    if res == 0:

        raise ValueError("invalid thread id")

    elif res != 1:

        ctypes.pythonapi.PyThreadState_SetAsyncExc(tid, None)

        raise SystemError("PyThreadState_SetAsyncExc failed")


 

# define image

img = []

# size setting

canvasw = 256

canvash = 256

listboxw = 150

listboxh = 300

scrollbarw = 10

scrollbarh = listboxh

# class pen


 

class pen:

    org = [0, 0]  # for show

    p1 = [0, 0]  # for show

    # p2 for computing

    x = 1

    y = 1

    alpha = 0  # rad

    beta = 0

    z = 0  # 状态 0:up 1:down

    def __init__(self):

        global cv

        self.id1 = cv.create_line(0, 0, 0, 0)

        self.id2 = cv.create_line(0, 0, 0, 0)

    def up(self):

        self.z = 0

    def down(self):

        self.z = 1

    def goto(self, pos):  # pos是经典坐标系下

        global MaxH, MaxW,mpx,npx, cv, MaxH_px

        coe=350/(mpx+npx)

        if self.z == 1:

            cv.create_line(int(self.x+MaxH_px)*coe, int(-self.y+MaxH_px)*coe,

                           int(pos[0]+MaxH_px)*coe, int(-pos[1]+MaxH_px)*coe)

        cv.delete(self.id1)

        cv.delete(self.id2)

        a, b = pos[0], pos[1]

        S = -((npx**2-a**2-b**2-mpx**2)/(2*b))

        x = (2*S*a/b+math.sqrt((2*S*a/b)**2-4*(1+a**2/b**2)

             * (S**2-mpx**2)))/(2*(1+a**2/b**2))

        y = S-a*x/b

        self.id1 = cv.create_line(MaxH_px*coe, MaxH_px*coe, (x+MaxH_px)*coe, (-y+MaxH_px)*coe)

        self.id2 = cv.create_line(

            (x+MaxH_px)*coe, (-y+MaxH_px)*coe, (pos[0]+MaxH_px)*coe, (-pos[1]+MaxH_px)*coe)

        drawpad.update()

        al = math.acos(x/mpx) if y >= 0 else -math.acos(x/mpx)

        # ((a-x)*(0-x)+(b-y)*(0-y))/( (a-x)**2+(b-y)**2 + (0-x)**2+(0-y)**2 )**0.5

        be = math.acos((-(a-x)*x-(b-y)*y) /

                       ((((a-x)**2+(b-y)**2) * (x**2+y**2))**0.5))

        da, db = al-self.alpha, be-self.beta  # delta差异

        self.alpha, self.beta, self.x, self.y = al, be, a, b

        return [0 if da < 0 else 1, 0 if db < 0 else 1, abs(da), abs(db)]


 

# 参数

global threshold

threshold = 127


 

def change_threshold(a):

    global threshold

    threshold = set_threshold.get()


 

def change_CannyMin(a):

    global CannyMin

    CannyMin = set_CannyMin.get()


 

def change_CannyMax(a):

    global CannyMax

    CannyMax = set_CannyMax.get()


 

def change_iterations(a):

    global iterations

    iterations = set_iterations.get()


 

def cv_show():

    global img, gray, ret, thresh, contours, hierarchy, res, threshold, CannyMin, CannyMax, kernel, ersion, iterations, fanse

    # 获取轮廓

    # 按高的比例缩放

   # img=cv2.resize(img,[int(img.shape[1]*(MaxH/img.shape[0])),int(MaxH)])#先宽后高

    gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)

    ret, thresh = cv2.threshold(

        gray, threshold, 255, cv2. THRESH_BINARY)  # thresh 黑白图

    if isCanny:

        thresh = cv2.Canny(thresh, CannyMin, CannyMax)

        print(CannyMin, CannyMax)

        contours, hierarchy = cv2.findContours(

            thresh, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)  # 减少点数,提高效率  cv2.CHAIN_APPROX_SIMPLE

        # 显示

        draw_img = img.copy()

        res = cv2.drawContours(draw_img, contours, -1, (0, 0, 255), 3)

        print('轮廓展示')

        cv2.imshow('轮廓', res)

        cv2.waitKey(0)

        cv2.destroyAllWindows()

    else:

        # kernel=cv2.getStructuringElement(cv2.MORPH_RECT, (5, 5))

        # np.zeros((5,5),np.uint8)生成5x5填充0的卷积核(白) np.ones((5,5),np.uint8)5x5填充1(黑)

        kernel = np.ones((3, 3), np.uint8)

        if fanse:

            erosion = cv2.erode(thresh, kernel, iterations=iterations)

        else:

            erosion = cv2.dilate(thresh, kernel, iterations=iterations)

         # 显示

        cv2.imshow('腐蚀', erosion)

        print('腐蚀展示')

        cv2.waitKey(0)

        cv2.destroyAllWindows()


 

def draw():

    global isfinish, cishu, mpx, npx, cv, drawpad

    global img, gray, ret, thresh, contours, hierarchy, res, threshold, CannyMin, CannyMax, kernel, ersion, iterations, fanse, Q

    # 实例化对象

    p = pen()

    drawpad.deiconify()

    # drawpad.geometry(str(int(2*(mpx+npx)))+'x'+str(int(mpx+npx)))#宽x高

    # cv.place(x=0, y=0, width=int(2*(mpx+npx)),

    #          height=int(mpx+npx))

    # cv.pack()

    cv.delete(ALL)  # 清屏

    cishu = 0

    output.delete(0, output.size())

    gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)

    ret, thresh = cv2.threshold(

        gray, threshold, 255, cv2. THRESH_BINARY)  # thresh 黑白图

    if isCanny:

        thresh = cv2.Canny(thresh, CannyMin, CannyMax)

        print(CannyMin, CannyMax)

        contours, hierarchy = cv2.findContours(

            thresh, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)  # 减少点数,提高效率  cv2.CHAIN_APPROX_SIMPLE

        keyPoints = contours[1:]  # 不包括轮廓

        for a in keyPoints:

            p.down()

            for b in a:

                for c in b:

                    if list(c) == list(a[0][0]):  # 是线段开始处

                        p.up()

                        # 每一段线是连续的

                        # define

                        x1, y1 = p.x, p.y  # 经典坐标系

                        x2, y2 = list(c)[0] - int(MaxH_px), - \

                            list(c)[1] + int(MaxH_px)  # 转为经典坐标系

                        # 修改尺寸时已经保证了图像高度小于最大高度(sqrt2)/2*(m+n),所以平移后不会有0

                        dx = abs(x2 - x1)

                        dy = abs(y2 - y1)

                        # 根据直线的走势方向,设置变化的单位是正是负

                        s1 = 1 if ((x2 - x1) > 0) else -1

                        s2 = 1 if ((y2 - y1) > 0) else -1

                        # 根据斜率的大小,交换dx和dy,可以理解为变化x轴和y轴使得斜率的绝对值为(0,1)

                        boolInterChange = False

                        if dy > dx:   # np.swapaxes(dx, dy)

                            dx, dy = dy, dx

                            boolInterChange = True

                        # 初始误差

                        ee = 2 * dy - dx

                        x = x1

                        y = y1

                        for i in range(0, int(dx + 1)):

                            # 入口(重点)

                            # print('经典',x,y)

                            xd, yd, a1, a2 = p.goto([x, y])

                            #发送数据

                            s.write(bytes([xd]))#xDIR

                            time.sleep(0.01)

                            s.write(bytes([yd]))#yDIR

                            time.sleep(0.01)

                            s.write(bytes([p.z]))#zState

                            time.sleep(0.01)

                            #0&n=0 1&n=n 0b0000000011111111=0b11111111=255

                            print( int(a1/(2*math.pi)*Q), int(a2/(2*math.pi)*Q),

                            bytes([xd]),bytes([yd]),bytes([p.z]),

                                bytes([int(a1/(2*math.pi)*Q)>>8]),

                                bytes([int(a1/(2*math.pi)*Q)&255]),

                                bytes([int(a2/(2*math.pi)*Q)>>8]),

                                bytes([int(a2/(2*math.pi)*Q)&255]))

                            s.write(bytes([int(a1/(2*math.pi)*Q)>>8]))#xPS1

                            time.sleep(0.01)

                            s.write(bytes([int(a1/(2*math.pi)*Q)&255]))#xPS2

                            time.sleep(0.01)

                            s.write(bytes([int(a2/(2*math.pi)*Q)>>8]))#xPS1

                            time.sleep(0.01)

                            s.write(bytes([int(a2/(2*math.pi)*Q)&255]))#xPS2

                            while not isfinish:  # 等待mcu发送完成

                                w.update()  # 更新 解决卡死问题

                                # pass

                            isfinish = False

                            if ee >= 0:  # 此时要选择横纵坐标都不同的点,根据斜率的不同,让变化小的一边变化一个单位

                                ee -= 2 * dx

                                if (boolInterChange):

                                    x += s1

                                else:

                                    y += s2

                        # 根据斜率的不同,让变化大的方向改变一单位,保证两边的变化小于等于1单位,让直线更加均匀

                            if boolInterChange:

                                y += s2

                            else:

                                x += s1

                            ee += 2 * dy

                    else:

                        p.down()

                        xd, yd, a1, a2 = p.goto(

                            [list(c)[0]-MaxH_px, -list(c)[1]+MaxH_px])

                        # 发送数据

                        s.write(bytes([xd]))#xDIR

                        time.sleep(0.01)

                        s.write(bytes([yd]))#yDIR

                        time.sleep(0.01)

                        s.write(bytes([p.z]))#zState

                        time.sleep(0.01)

                        #0&n=0 1&n=n 0b0000000011111111=0b11111111=255

                        s.write(bytes([int(a1/(2*math.pi)*Q)>>8]))#xPS1

                        time.sleep(0.01)

                        s.write(bytes([int(a1/(2*math.pi)*Q)&255]))#xPS2

                        time.sleep(0.01)

                        s.write(bytes([int(a2/(2*math.pi)*Q)>>8]))#xPS1

                        time.sleep(0.01)

                        s.write(bytes([int(a2/(2*math.pi)*Q)&255]))#xPS2

                        while not isfinish:  # 等待mcu发送完成

                            w.update()  # 更新 解决卡死问题

                            # pass

                        isfinish = False

            p.up()

    else:

        kernel = np.ones((3, 3), np.uint8)

        if fanse:

            erosion = cv2.erode(thresh, kernel, iterations=iterations)

        else:

            erosion = cv2.dilate(thresh, kernel, iterations=iterations)

        for i in range(len(erosion)):

            for j in range(0 if i % 2 == 0 else len(erosion[i])-1,

                           len(erosion[i]) if i % 2 == 0 else -1,

                           1 if i % 2 == 0 else -1):

                print(i, j)

                if erosion[i][j] == 0:  # 黑

                    p.down()

                else:

                    p.up()

                xd, yd, a1, a2 = p.goto([i-MaxH_px, -j+MaxH_px])

                s.write(bytes([xd]))#xDIR

                time.sleep(0.01)

                s.write(bytes([yd]))#yDIR

                time.sleep(0.01)

                s.write(bytes([p.z]))#zState

                time.sleep(0.01)

                #0&n=0 1&n=n 0b0000000011111111=0b11111111=255

                s.write(bytes([int(a1/(2*math.pi)*Q)>>8]))#xPS1

                time.sleep(0.01)

                s.write(bytes([int(a1/(2*math.pi)*Q)&255]))#xPS2

                time.sleep(0.01)

                s.write(bytes([int(a2/(2*math.pi)*Q)>>8]))#xPS1

                time.sleep(0.01)

                s.write(bytes([int(a2/(2*math.pi)*Q)&255]))#xPS2

                while not isfinish:  # 等待mcu发送完成

                    w.update()  # 更新 解决卡死问题

                    # pass

                isfinish = False

    # # 发送开始

    # output.insert('end', '----------------')

    # output.insert('end', '0,0,0')

    # # 归位!!!

    # output.insert('end', '----------------')

    # while not isfinish:  # 等待mcu发送完成

    #     pass

    # isfinish = False

    osb.config(command=output.yview('moveto', 1))


 

# menu

def callback():  # 打印按钮

    if messagebox.askquestion("提示", "开始打印?") == 'yes':

        draw()


 

def load():

    global img

    filename = askopenfilename(defaultextension='jpg')

    if filename:

        w.title(filename)

        img = cv2.imread(filename)


 

def set_size():

    global px, mpx, npx, MaxH_px

    while True:

       

        print("请输入图片长度(cm,小数float)(约束比例)")

        a = input()

        try:

            wcm = float(a)

            px = wcm/img.shape[1]  # cm/px

            hcm = img.shape[0]*px

            # cm/px print(img.shape)#图片的 高,底,查看格式,查看格式3是RGB

            print('img.shape:', img.shape)

            print("Size(cm):", wcm, hcm)

            print("px:", px)

            if wcm > MaxW or hcm >= MaxH:

                print('超出范围,请重新输入')

            else:

                print("Size(cm):", wcm, hcm)

                print("px:", px)

                mpx, npx = m/px, n/px

                MaxH_px = MaxH/px

                print('mpx&npx:', mpx, npx)

                print('设置成功')

                break

        except ValueError:

            print('类型错误,请重新输入')


 

def set_Q():

    global Q

    while True:

        try:

            q = input('请输入圈拍数:')

            Q = int(q)

            print('设置成功')

            break

        except ValueError:

            print('类型错误,请重新输入')

# checkbutton


 

def CBfunc():

    global isCanny

    isCanny = not cb_var.get()


 

def set_fanse():

    global fanse

    fanse = cb_var2.get()


 

if __name__ == '__main__':

    # 开启读取线程

    new_thread = threading.Thread(target=readdata, name="T1")

    new_thread.start()

    # 创建tk窗口及组件-----------------------------------------------------------

    w = Tk()

    drawpad = Tk()

    drawpad.title('drawing...')

    drawpad.geometry('350x700')

    drawpad.withdraw()  # 隐藏

    w.title('Printer_Helper')

    w.geometry('500x700')  # srceen_size

    # 滚动条-----------------------------------------

    isb = Scrollbar(w)

    isb.pack(side="right", fill="y")

    isb.place(x=canvasw+listboxw, y=0, width=scrollbarw, height=scrollbarh)

    osb = Scrollbar(w)

    osb.pack(side="right", fill="y")

    osb.place(x=canvasw+2*listboxw+scrollbarw, y=0,

              width=scrollbarw, height=scrollbarh)

    # listbox-------------------------------------------

    inputt = Listbox(w, yscrollcommand=isb.set)

    inputt.pack(side="left", fill="both")

    inputt.place(x=canvasw, y=0, width=listboxw, height=listboxh)

    output = Listbox(w, yscrollcommand=osb.set)

    output.pack(side="left", fill="both")

    output.place(x=canvasw+listboxw+scrollbarw, y=0,

                 width=listboxw, height=listboxh)

    # update_scrollbar :input.yview('moveto',1), command是回调函数参数

    # isb.config(command=input.yview('moveto',1))#滑动条滑到最下

    # osb.config(command=output.yview('moveto',1))

    # draw_pad-----------------------------------------

    global cv

    cv = Canvas(drawpad, bg="white", highlightthickness=0,

                width=2000, height=960)

    cv.place(x=0, y=0)  # pack和place不可同时用

    menu = Menu(w)

    w.config(menu=menu)  # 把菜单绑定root

    menu.add_command(label='file', command=load)

    menu.add_command(label='size', command=set_size)

    menu.add_command(label='1圈拍数', command=set_Q)

    # 参数

    set_threshold = Scale(w, from_=0, to=255, label="二值化阈值 threshold",

                          orient="horizontal", command=change_threshold)  # 阈值

    set_threshold.pack(side="left")

    set_threshold.set(127)

    set_threshold.place(x=0, y=listboxh+50)

    threshold = 127

    set_CannyMin = Scale(w, from_=0, to=255, label="CannyMin",

                         orient="horizontal", command=change_CannyMin)

    set_CannyMin.place(x=100, y=350)

    set_CannyMax = Scale(w, from_=0, to=255, label="CannyMax",

                         orient="horizontal", command=change_CannyMax)

    set_CannyMax.place(x=200, y=350)

    CannyMin, CannyMax = 100, 127

    set_iterations = Scale(w, from_=0, to=255, label="迭代次数 iterations",

                           orient="horizontal", command=change_iterations)

    set_iterations.place(x=0, y=410)

    # 勾选按钮 在canny与腐蚀选择

    cb_var = BooleanVar()

    cb = Checkbutton(w, text="腐蚀", command=CBfunc, variable=cb_var)

    cb.place(x=0, y=470)

    # 反色按钮

    cb_var2 = BooleanVar()

    cb = Checkbutton(w, text="反色", command=set_fanse, variable=cb_var2)

    cb.place(x=50, y=470)

    # button-----------------

    show_image = Button(w, text="show image", command=cv_show)

    show_image.place(x=127, y=listboxh)

    # 询问是否要开始打印

    is_print_button = Button(w, text="打印", command=callback)

    is_print_button.place(x=220, y=listboxh)

    # 创建tk窗口及组件-----------------------------------------------------------

    mainloop()

    stop_thread(new_thread)

/*

通信格式说明:

    波特率 9600

    PC发送:

        第1字节 xDir

        第2字节 yDir

        第3字节 zState

        第4&5字节 xPS

        第6&7字节 yPS

    单片机发送: 0xff  表示打印完成

28byj48_step-motor规定一拍用时5500us,509脉冲=1/8圈

42step-motor 400脉冲=1圈

*/

// direction-方向 lock-锁定 lock -> fixed

#include <Arduino.h>

#define u8 unsigned char

#define z 16

#define coe 5//sleepTime(ms) 5ms=5000us

// variable

hw_timer_t *timer;

u8 zs, k;

void timer_interrupt()

{

    k %= 50; // 20ms/0.5ms=50

    if (k <= zs)

    {

        digitalWrite(z, HIGH);

    }

    else

    {

        digitalWrite(z, LOW);

    }

}

// u8 movelist[8] = {8, 0x0a, 2, 6, 4, 5, 1, 9};//L298n&42stepmotor

u8 movelist[8] = {0x0e, 0x0c,0x0d,9,0x0b,3,7,6};//uln2003&28byj48

int sd[7]; // serialData

u8 si;     // serialDataIndex

int sleeptime, i, fi, ui;

bool isZero;

class motor

{

public:

    u8 a, b, c, d, dir;

    int ps;

    motor(u8 ia, u8 ib, u8 ic, u8 id)

    {

        this->a = ia;

        this->b = ib;

        this->c = ic;

        this->d = id;

        pinMode(this->a, OUTPUT);

        pinMode(this->b, OUTPUT);

        pinMode(this->c, OUTPUT);

        pinMode(this->d, OUTPUT);

    }

    void stop()

    {

        digitalWrite(this->a, LOW);

        digitalWrite(this->b, LOW);

        digitalWrite(this->c, LOW);

        digitalWrite(this->d, LOW);

    }

    void move(u8 step, u8 dir)

    {

        u8 temp = step;

        if (dir == 0)

        {

            temp = 7 - step;

        }

            //#num >> (i-1) & 1

        digitalWrite(this->a, movelist[temp % 8] &1);//已经做了temp % 8工作,可以直接输入大于8数字

        digitalWrite(this->b, movelist[temp % 8] >>1&1);

        digitalWrite(this->c,movelist[temp % 8] >>2&1);

        digitalWrite(this->d, movelist[temp % 8] >>3&1);

    }

};

// create objects & set pin

motor x = motor(5,18,19,21);

motor y = motor(12,13,14,15);

motor *f, *u; // Fixed&Unfixed

void setup()

{

    Serial.begin(9600);

    pinMode(z, OUTPUT);

    //{8, 0x0a, 2, 6, 4, 5, 1, 9};

    si = 0;

    timer = timerBegin(0, 80, true);

    // config func

    timerAttachInterrupt(timer, timer_interrupt, true);

    // set Mode

    timerAlarmWrite(timer, 500, true); // 1s=1000ms=1000*1000us => 0.5ms=500us

    // start

    timerAlarmEnable(timer);

    x.stop();

    y.stop();

}

//delayMicrosecond us

void loop()

{

    if (Serial.available())

    {

        sd[si] = Serial.read();

        si++;

        if (si == 7)

        {

            zs = sd[2];

            x.dir = sd[0];

            y.dir = sd[1];

            x.ps = (sd[3] << 8) + sd[4];

            y.ps = (sd[5] << 8 )+ sd[6];//左右移操作顺序不一致,要用括号

            // Serial.println(x.ps);

            // Serial.println(y.ps);

           

            if (x.ps >= y.ps)

            {

                f = &x;

                u = &y;

            }

            else

            {

                f = &y;

                u = &x;

            }

            if (u->ps == 0)

            {

                isZero = 0;

            }

            else

            {

                isZero = 1;

                sleeptime = coe* f->ps / u->ps;

            }

            fi = 0;

            ui = 0;

            u->stop();

            f->stop();

            for (i = 0; i < f->ps * coe + 1; i++)

            {

                delay(1);

                if (i % coe == 0)

                {

                    f->move(fi, f->dir);

                    fi++;

                }

                if (isZero)

                {              

                    if (i % sleeptime == 0)

                    {

                        u->move(ui, u->dir);

                        ui++;

                    }

                }

            }

            // setup si

            si = 0;

            u->stop();

            f->stop();

            Serial.write(0xff);//不是printf(0xff)(输出'255'),输出255(num)

        }

    }

}

// sth about motor

/*

#define LOW               0x0

#define HIGH              0x1

8a264519

step

1-1_0_0_0 :8

2-1_0_1_0 :a

3-0_0_1_0 :2

4-0_1_1_0 :6

5-0_1_0_0 :4

6-0_1_0_1 :5

7-0_0_0_1 :1

8-1_0_0_1 :9

*/

//ULN2003 28byj-48

//      case 0: IN1_A=1; IN1_B=1; IN1_C=1; IN1_D=0; break; //e

//      case 1: IN1_A=1; IN1_B=1; IN1_C=0; IN1_D=0; break;//c

//      case 2: IN1_A=1; IN1_B=1; IN1_C=0; IN1_D=1; break;//d

//      case 3: IN1_A=1; IN1_B=0; IN1_C=0; IN1_D=1; break;//9

//      case 4: IN1_A=1; IN1_B=0; IN1_C=1; IN1_D=1; break;//b

//      case 5: IN1_A=0; IN1_B=0; IN1_C=1; IN1_D=1; break;//3

//      case 6: IN1_A=0; IN1_B=1; IN1_C=1; IN1_D=1; break;//7

//      case 7: IN1_A=0; IN1_B=1; IN1_C=1; IN1_D=0; break;//6


 

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值