本篇目录

    • 一、机械臂模型及参数
    • 二、路径生成
      • 2.1 RRT算法简介
      • 2.2 初始化
      • 2.3 Sample、Steer、Near
      • 2.5 碰撞检测
      • 2.6 退出循环条件
      • 2.7 RRT算法整体代码
    • 三、碰撞检测算法简介
      • 3.1 机械臂连杆圆柱体包围及障碍物球包围
      • 3.2 路径离散化
      • 3.3 机械臂当前位姿碰撞检测
      • 3.4 机械臂单个连杆碰撞检测
    • 四、轨迹规划
      • 4.1 关节空间多项式插值(闭式求解 minium jerk)
      • 4.2 关节空间多项式插值(QP求解器 minium snap)
      • 4.3 效果展示
  • 五、资料分享
    • 5.1 常用的算法
    • 5.2 比较好用的开源库
    • 5.3 数据结构

在本篇内容中,将使用MATLAB机器人工具箱,对机械臂进行避障仿真。主要内容包括使用图搜索算法生成路径,获取路径后,对生成的路径进行插值,从而获取轨迹。(水平有限,还请各位大佬指正)

关键词: RRT、关节空间插值、多项式、闭式求解、QP 求解器、minium jerk、minium snap、笛卡尔空间插值、B样条、四元数多点插值Squad

一、机械臂模型及参数

图1.1 puma560
此处采用的机械臂为puma560,puma560为6自由度的机械臂,本文使用 MDH方法建模,MDH模型如图1.2所示:

图1.2 MDH模型
DH参数表如图1.3所示,图中单位为rad和mm:
图1.3 DH参数表
代码如下:

%   @autor: fuqb
%   @data:  2022-09-17
%   @function:   PlotRobot.mfunction robot=PlotRobot()
%建立机器人模型
% theta d a alpha offset
L1=Link([0 0 0 0 0 ],'modified'); %连杆的D-H参数
L2=Link([0 149.09 0 -pi/2 0 ],'modified');
L3=Link([0 0 431.8 0 0 ],'modified');
L4=Link([0 433.07 20.32 -pi/2 0 ],'modified');
L5=Link([0 0 0 pi/2 0 ],'modified');
L6=Link([0 0 0 -pi/2 0 ],'modified');
robot=SerialLink([L1 L2 L3 L4 L5 L6],'name','puma560','base' , ...
transl(0, 0, 0.62)* trotz(0)); %连接连杆,机器人取名puma560
robot.display();
q=[10*pi/180 0*pi/180 0*pi/180 0*pi/180 0*pi/180 0*pi/180 ];
robot.plot(q);
robot.teach();
% robot.fkine(q)hold on
% T=TransformMatrix(10*pi/180 ,0, 0 ,0)*TransformMatrix(-10*pi/180 ,149.09, 0, -pi/2)*TransformMatrix(-10*pi/180, 0, 431.8, 0)*...
%     TransformMatrix(10*pi/180, 433.07, 20.32, -pi/2)*TransformMatrix(10*pi/180, 0, 0, pi/2)*TransformMatrix(10*pi/180, 0, 0 ,-pi/2);
% [T,T01,T02,T03,T04,T05,T06]=RobotFkine(q,false);
end

二、路径生成

本文路径生成算法采用RRT算法。

2.1 RRT算法简介

RRT算法全称为快速扩展随机树算法(Rapidly Exploring Random Tree),此处RRT算法参考B站IR艾若机器人的路径规划、轨迹优化等系列课程,算法流程如图2.1所示:

图2.1 RRT算法流程图
对于机械臂而言,其可以在笛卡尔空间或者关节空间搜索,相对笛卡尔空间而言,关节空间中搜索更为简单直接,因此本篇采用 关节空间中搜索的方法。

2.2 初始化

1、使用运动学逆解计算目标关节角度;
2、初始化随机生成树,随机数的1-6列存放关节角度,第7列存放cost,第8列存放节点parent;
3、设置关节空间搜索步长;
4、设置机械臂各连杆距离障碍物最近阈值;
5、设置最大迭代步数;
如代码所示:

targetPos=[0         0         1;0        -1         0;1         0         0];                                            %targetPos is the posture when manipulator touch balls
targetPos = [targetPos,[ballsOrigin(index,:)]';[0 0 0 1]];
targetJointPos = robot.ikine(targetPos)                                     %target joint pos
%%
nodeList=[initJointPos,0,0];                                                %nodeList:col 1-6 is jointpos,col 7 is cost,col 8 is node parent
%%
angleStepSize=0.2*pi/180;                                                   %joint space search step length is 1°
threhold=10;                                                                %distance between robot and  obstacle threhold is 10mm
%%
maxLoopCount=15000;

2.3 Sample、Steer、Near

图2.2 产生新节点

产生新节点的方法如图2.2所示,x_new为新节点关节角度,x_rand为随机采样点,x_near为最近的节点,x_init为初始节点关节角度,x_target为目标节点关节角度,kp为权重。引入kp后括号内项目的是为了加快搜索速度,提高效率,有点像人工势场法中的引力。具体做法如代码所示:

function newNode=SampleNearAndSteer(nodeList,angleStepSize,initJointPos,targetJointPos)Kp = 1.5;randNode = rand(1,6).*2*pi - pi;[row,~]=size(nodeList);len = zeros(row,1);for i=1:rowlen(i) = sqrt((nodeList(i,1:6)-randNode)*(nodeList(i,1:6)-randNode)');end[~,index]=min(len,[],1);nearNode = nodeList(index,1:6);randOrientation = (randNode-nearNode)/ sqrt((randNode-nearNode)*(randNode-nearNode)');searchOrientation=(targetJointPos-initJointPos)/ sqrt((targetJointPos-initJointPos)*(targetJointPos-initJointPos)');newNode = nearNode+angleStepSize*(randOrientation+Kp*searchOrientation);cost = sqrt((randOrientation+Kp*searchOrientation)*(randOrientation+Kp*searchOrientation)');newNode = [newNode,cost,index];
end

2.5 碰撞检测

碰撞检测算法将在第三部分详细介绍。

2.6 退出循环条件

退出循环条件有两个,第一个是超出循环次数,第二是搜索到终点附近,且与终点连接无碰撞,具体做法如代码所示:

isJointsPosNear = abs((targetJointPos-nearNode(1:6)))<...angleStepSize*10*[2 2 2 20 15 15];isNear = sum(isJointsPosNear);noCollision1=CheckPathCollision(newNode,targetJointPos,threhold,...ballsOrigin,ballsRadius,cylindersInfo,index);                       %check path collisionif (isNear==6)&&noCollision1disp('find path successfully.')[n,~]=size(nodeList);nodeList=[nodeList;[targetJointPos,0,n]];isFind = true;return;end

2.7 RRT算法整体代码

整体代码如下:

%   @autor: fuqb
%   @function:   RRT
%   @param: robot,initJointPos,origin,radius,index
%   @robot:  puma560
%   @initJointPos: robot current joint pos
%   @origin: balls origin (obstacle)
%   @radius: obstacle radius
%   @index: target ball indexfunction [nodeList,isFind]=RRT(robot,initJointPos,ballsOrigin,ballsRadius,cylindersInfo,index)
isFind = false;
targetPos=[0         0         1;0        -1         0;1         0         0];                                            %targetPos is the posture when manipulator touch balls
targetPos = [targetPos,[ballsOrigin(index,:)]';[0 0 0 1]];
targetJointPos = robot.ikine(targetPos)                                     %target joint pos
%%
nodeList=[initJointPos,0,0];                                                %nodeList:col 1-6 is jointpos,col 7 is cost,col 8 is node parent
%%
angleStepSize=0.2*pi/180;                                                   %joint space search step length is 1°
threhold=10;                                                                %distance between robot and  obstacle threhold is 10mm
%%
maxLoopCount=15000;
%%
% loop to grow RRTsfor i=1:maxLoopCountnewNode=SampleNearAndSteer(nodeList,angleStepSize,...initJointPos,targetJointPos);                                       %generate new nodenearNode = nodeList(newNode(8),:);                                  %get nearest nodenoCollision=CheckPathCollision(newNode,nearNode,threhold,ballsOrigin,...ballsRadius,cylindersInfo,index);           %check path collision             if noCollisionnodeList=[nodeList;newNode];elsecontinue;endisJointsPosNear = abs((targetJointPos-nearNode(1:6)))<...angleStepSize*10*[2 2 2 20 15 15];isNear = sum(isJointsPosNear);noCollision1=CheckPathCollision(newNode,targetJointPos,threhold,...ballsOrigin,ballsRadius,cylindersInfo,index);                       %check path collisionif (isNear==6)&&noCollision1disp('find path successfully.')[n,~]=size(nodeList);nodeList=[nodeList;[targetJointPos,0,n]];isFind = true;return;endendisFind = false;disp('failed to find path.')[row1,~]=size(nodeList);len = zeros(row1,1);for i=1:row1len(i) = 100*(nodeList(i,1:3)-targetJointPos(1:3))*...(nodeList(i,1:3)-targetJointPos(1:3))'+...(nodeList(i,4:6)-targetJointPos(4:6))*(nodeList(i,4:6)-targetJointPos(4:6))';end[~,index]=min(len,[],1)nearestNode = nodeList(index,1:6)abs(targetJointPos - nearestNode)*180/piend

三、碰撞检测算法简介

本文采用的碰撞检测流程如图3.1所示,本文机械臂各个连杆采用圆柱进行包围,障碍物采用球包围。

图3.1 碰撞检测流程图

3.1 机械臂连杆圆柱体包围及障碍物球包围

机械臂共使用8个圆柱体进行包围,具体做法如代码所示,障碍物如图3.2所示:

cylindersInfo=[150   120   100   90   70   70   60   60;                    %cylinder radius  100   90    435   90   435  90   90   90;                    %cylinder axis end-100  -120   0     -90  0    -90  -90  -90;                  %cylinder axis start  1     2     2     3    3    4    5    6;                     %cylinder subordinate to frame i3     3     1     3    2    3    3    3];                    %cylinder axis orientation,1 means axis x,2 means axis y,3 means axis z

图3.2 障碍物信息

3.2 路径离散化

将路径分为n份,再分别对每个点进行碰撞检测;

%   @autor: fuqb
%   @function:   CheckCollision
%   @param: newNode,nearNode,threhold,robot,origin,radius
%   @index: target ball index
%   @notes:this function is designed to check path collison between newNode
%   and nearNode.function noCollision=CheckPathCollision(newNode,nearNode,threhold,ballsOrigin,ballsRadius,cylindersInfo,index)
n=10;                                                                       %path interpolation count
initPos=newNode(1:6);
targetPos=nearNode(1:6);
%     tic
for i=0:npos = (targetPos-initPos)*i/n+initPos;noCollision=CheckLinksCollision(pos,threhold,ballsOrigin,ballsRadius,cylindersInfo,index);
end
%     toc
end

3.3 机械臂当前位姿碰撞检测

如3.1中所示,已经对路径进行了离散,对机械臂当前位姿进行碰撞检测。为方便各个连杆与球进行碰撞检测,将各个球球心坐标臂变换至各个连杆坐标系。

%   @autor: fuqb
%   @function:   CheckLinksCollision
%   @param: q,threhold,robot,origin,radius
%   @q:current joints pos
%   @notes:this function is designed to check manipulator links collision with
%   balls,manipulator joints pos is given.
function noCollision=CheckLinksCollision(q,threhold,ballsOrigin,ballsRadius,cylindersInfo,index)
% using SAT algorithm to check collision.
% The manipulator link is surrounded by cylinders
% obstacle is surrounded by balls
%   links and balls project on the planenoCollision=true;[~,T01,T02,T03,T04,T05,T06]=RobotFkine(q,false);o=zeros(6,4);[row,~]=size(ballsOrigin);for i=1:rowif(i~=index)o(1,:)=T01\[ballsOrigin(i,:),1]';                                                %ball origin in Coordinate 1o(2,:)=T02\[ballsOrigin(i,:),1]';                                                %ball origin in Coordinate 2o(3,:)=T03\[ballsOrigin(i,:),1]';                                                %ball origin in Coordinate 3o(4,:)=T04\[ballsOrigin(i,:),1]';                                                %ball origin in Coordinate 4o(5,:)=T05\[ballsOrigin(i,:),1]';                                                %ball origin in Coordinate 5o(6,:)=T06\[ballsOrigin(i,:),1]';                                                %ball origin in Coordinate 6o1=o(:,1:3);for j=1:8temp=CheckSingleLinkCollision(j,cylindersInfo,threhold,o1,ballsRadius(i));noCollision = noCollision&temp;endendend
end

3.4 机械臂单个连杆碰撞检测

在机械臂参数已知及姿态已知的情况下,将障碍物球心变换到各个关节坐标系中,分别在各个坐标系中计算点到线段的距离(此线段为圆柱的中心线,其必定与关节坐标系的x,y或者z轴重合),如果距离大于圆柱与球半径之和,那么不发生碰撞,此种方法可以大大减少计算量。机械臂单个连杆碰撞检测方法如代码所示。

%   @autor: fuqb
%   @function: CheckSingleLinkCollision
%   @param: idx,cylinderInfo,threhold,origin,ballRadius
%   @idx:cylinder index
%   @origin:ball origin in frame  cylinderInfo(4,idx)
%   @notes:this function is designed to check single cylinder collision
%   with single ball function noCollision=CheckSingleLinkCollision(idx,cylinderInfo,threhold,origin,ballRadius)cylinderRadius = cylinderInfo(1,idx);
cylinderAxisStart = cylinderInfo(3,idx);
cylinderAxisEnd = cylinderInfo(2,idx);
cylinderCoordinate = cylinderInfo(4,idx);
cylinderAxisOrientation = cylinderInfo(5,idx);
o=origin(cylinderCoordinate,:);axiss=1:3;
axiss(cylinderAxisOrientation) =[];if o(cylinderAxisOrientation)<cylinderAxisStartdistance = sqrt((o(cylinderAxisOrientation)-cylinderAxisStart)^2+(sqrt(o(axiss(1))^2+o(axiss(2))^2)-cylinderRadius)^2);
elseif o(cylinderAxisOrientation)>cylinderAxisEnddistance = sqrt((o(cylinderAxisOrientation)-cylinderAxisEnd)^2+(sqrt(o(axiss(1))^2+o(axiss(2))^2)-cylinderRadius)^2);
elsedistance = sqrt(o(axiss(1))^2+o(axiss(2))^2)-cylinderRadius;
endif distance>ballRadius+threholdnoCollision = true;
elsenoCollision = false;
endend

四、轨迹规划

RRT算法返回了一系列离散点,需要对这些离散点进行插值。可以在关节空间中进行插值,也可以在笛卡尔空间中分别对位置和姿态进行插值。本文首先在关节空间中使用多项式进行插值。

4.1 关节空间多项式插值(闭式求解 minium jerk)

%   @autor: fuqb
%   @function:   miniumJerkTrajectoryGeneration,closed form solution
%   @param: pieceNum,initialPVA,terminalPVA,intermediatePositions,timeAllocatorVector
%   @initialPVA:initial pos,vel,acc
%   @terminalPVA:terminal pos,vel,acc
%   @intermediatePositions:intermediate pos
%   @timeAllocatorVector:traj segments durationfunction traj=miniumJerkTrajectoryGeneration(pieceNum,initialPVA,...
terminalPVA,intermediatePositions,timeAllocatorVector,controlPeriod)
%   M*c=bb = zeros(6*pieceNum,6);b(1:3,:) = initialPVA;b(4:6,:) = terminalPVA;b(7:6+pieceNum-1,:) = intermediatePositions(1:end,:);M = zeros(6*pieceNum,6*pieceNum);%%%The starting point conditionM(1,1:6) = CalculateMiniumJerkPolynomialCoefficients(0,timeAllocatorVector(1),true);M(2,1:6) = CalculateMiniumJerkPolynomialCoefficients(1,timeAllocatorVector(1),true);M(3,1:6) = CalculateMiniumJerkPolynomialCoefficients(2,timeAllocatorVector(1),true);%%%%The terminal point conditionM(4,end-5:end) = CalculateMiniumJerkPolynomialCoefficients(0,timeAllocatorVector(end),false);M(5,end-5:end) = CalculateMiniumJerkPolynomialCoefficients(1,timeAllocatorVector(end),false);M(6,end-5:end) = CalculateMiniumJerkPolynomialCoefficients(2,timeAllocatorVector(end),false);for i = 1:pieceNum-1
%%% Midpoint conditionM(6+i,(6*(i-1)+1):6*i) = CalculateMiniumJerkPolynomialCoefficients(0,timeAllocatorVector(i),false);%%% Continuity conditions%pos continuous conditionsM(6+pieceNum+(i-1)*5,(6*(i-1)+1):6*i) = ...CalculateMiniumJerkPolynomialCoefficients(0,timeAllocatorVector(i),false);M(6+pieceNum+(i-1)*5,(6*i+1):6*(i+1)) = ...-CalculateMiniumJerkPolynomialCoefficients(0,timeAllocatorVector(i+1),true);%vel continuous conditionsM(6+pieceNum+(i-1)*5+1,(6*(i-1)+1):6*i) = ...CalculateMiniumJerkPolynomialCoefficients(1,timeAllocatorVector(i),false);M(6+pieceNum+(i-1)*5+1,(6*i+1):6*(i+1)) = ...-CalculateMiniumJerkPolynomialCoefficients(1,timeAllocatorVector(i+1),true);%acc continuous conditionsM(6+pieceNum+(i-1)*5+2,(6*(i-1)+1):6*i) = ...CalculateMiniumJerkPolynomialCoefficients(2,timeAllocatorVector(i),false);M(6+pieceNum+(i-1)*5+2,(6*i+1):6*(i+1)) = ...-CalculateMiniumJerkPolynomialCoefficients(2,timeAllocatorVector(i+1),true);%jerk continuous conditionsM(6+pieceNum+(i-1)*5+3,(6*(i-1)+1):6*i) = ...CalculateMiniumJerkPolynomialCoefficients(3,timeAllocatorVector(i),false);M(6+pieceNum+(i-1)*5+3,(6*i+1):6*(i+1)) = ...-CalculateMiniumJerkPolynomialCoefficients(3,timeAllocatorVector(i+1),true);%snap continuous conditionsM(6+pieceNum+(i-1)*5+4,(6*(i-1)+1):6*i) = ...CalculateMiniumJerkPolynomialCoefficients(4,timeAllocatorVector(i),false);M(6+pieceNum+(i-1)*5+4,(6*i+1):6*(i+1)) = ...-CalculateMiniumJerkPolynomialCoefficients(4,timeAllocatorVector(i+1),true);endcoefficientMatrix =pinv(M)*b;traj=GetTrajInJointSpace(controlPeriod,coefficientMatrix,timeAllocatorVector);end
function traj=GetTrajInJointSpace(controlPeriod,coefficientMatrix,timeAllocatorVector)trajDuration = sum(timeAllocatorVector);t = 0:controlPeriod:trajDuration;n = length(t);traj = zeros(n,6);currentTime = 0;k = 1;for i = 1:nfor j = 1:6traj(i,j) = CalculatePolynomialValue(coefficientMatrix((k-1)*6+1:k*6,j)',currentTime,5);endcurrentTime = currentTime + controlPeriod;if currentTime >=timeAllocatorVector(k)currentTime = currentTime - timeAllocatorVector(k);k = k + 1;endend
end

4.2 关节空间多项式插值(QP求解器 minium snap)

%   @autor: fuqb
%   @function:   TrajectoryGenerationUsingQPSolver,solution that using QP solver.
%   @param: pieceNum,initialPVA,terminalPVA,intermediatePositions,timeAllocatorVector
%   @initialPVA:initial pos,vel,acc
%   @terminalPVA:terminal pos,vel,acc
%   @intermediatePositions:intermediate pos
%   @timeAllocatorVector:traj segments durationfunction traj = TrajectoryGenerationUsingQPSolver(pieceNum,initialPVA,...
terminalPVA,intermediatePositions,timeAllocatorVector,controlPeriod)r = 4;
n = 2*r-1;[row,~] = size(timeAllocatorVector);
time = zeros(row+1,1);
sum =0;
for i = 1:rowsum = sum + timeAllocatorVector(i);time(i+1) = sum;
endH=[];
for i=1:pieceNumQi=GetPartQ(n,r,time(i),time(i+1));H=blkdiag(H,Qi);
endf = zeros(pieceNum*(n+1),1);
p = zeros(pieceNum*(n+1),6);[Aeq,beq]=GenerateEquationCoefficients(pieceNum,initialPVA,...
terminalPVA,intermediatePositions,timeAllocatorVector,n);for i = 1:6
be = beq(:,i);
p(:,i) = quadprog(H,f,[],[],Aeq,be);
endtraj=GetTrajInJointSpace1(controlPeriod,p,timeAllocatorVector);end

4.3 效果展示

在这里插入图片描述

(待续。。。。)

五、资料分享

各位,最近实在太忙,代码没来得及整理,加上自己写的也比较烂,这里先给各位推荐机械臂避障约束下的轨迹规划一些资料:

5.1 常用的算法

1、GJK 算法
2、SAT算法(分离轴)
3、EPA算法
以下是上面三个算法原理详细介绍文章的截图以及链接:

5.2 比较好用的开源库

1、FCL,著名的碰撞检测库,但不包括轨迹生成;
2、伯克利的traj-opt;

链接包括了源码,paper,还有guide。
主要思想是将碰撞设置为约束(可以用fcl库),然后求解凸优化问题,这个库主要可以用来生成轨迹。

5.3 数据结构

1、Octree,八叉树;
2、SDF,signed distance field;

机械臂避障与轨迹规划仿真相关推荐

  1. 【强化学习与机器人控制论文 1】基于深度强化学习的机械臂避障

    基于深度强化学习的机械臂避障 1. 引言 2. 论文解读 2.1 背景 2.2 将NAF算法用在机器人避障中 3. 总结 1. 引言 本文介绍一篇2018年发表在 European Control C ...

  2. ROS moveit 机械臂避障运动规划

    机械臂moveit编程(python) moveit默认使用的运动规划库OMPL支持臂章规划,这里选用RRT算法,使用move group中的PlanningSceneInterface()添加障碍物 ...

  3. 在ROS上实现Seed robotics R8HD机械手与Ur5机械臂的连接与轨迹规划(上)模型连接

    本部分讲解R8HD的模型与ur5机械臂的连接并在rviz中正常显示 前言:本文运行环境: Ubuntu 20.04 ROS noetic 工作空间ur_ws fmauch_universal_robo ...

  4. 基于MATLAB的关节型六轴机械臂轨迹规划仿真(2021实测完整代码)

    我是一个目录 基于MATLAB的关节型六轴机械臂轨迹规划仿真 1 实验目的 2 实验内容 2.1标准D-H参数法 2.2实验中使用的Matlab函数 3实验结果 4 全部代码 基于MATLAB的关节型 ...

  5. 【联合仿真】Adams六关节机械臂与Matlab/Simulink的联合仿真(下)

    Adams六关节机械臂与Matlab/Simulink的联合仿真(下) 接上文,上文讲到了建立好变量与测量单元之间的关联了,下面完成matlab/simulink的对接接口以及模型搭建 第一步. ad ...

  6. 空间机械臂Matlab/Simulink仿真程序自由漂浮空间机械臂(双臂)轨迹跟踪控制matlab仿真程序

    空间机械臂Matlab/Simulink仿真程序自由漂浮空间机械臂(双臂)轨迹跟踪控制matlab仿真程序,含空间机器人动力学模型,PD控制程序,带仿真结果,可供二次开发学习 ID:672006146 ...

  7. 【联合仿真】Adams六关节机械臂与Matlab/Simulink的联合仿真(上)

    Adams六关节机械臂与Matlab/Simulink的联合仿真(上) 前言:一直对于六关节机械臂与simulink的联合仿真很感兴趣,但网上关于实际模型的机械臂联合仿真的资料很少,更别说六关节的联合 ...

  8. ur10e机械臂与夹爪在gazebo下仿真

    上一篇博客为ur10e添加了DH-AG95夹爪,通过moveit助手能在Rviz界面下做运动规划,接着就是进行gazebo仿真了,首先当然是把ur10e与夹爪的模型加载到Gazebo仿真环境下,笔者这 ...

  9. 【机器人学习】分拣机器人运动学分析及轨迹规划仿真

    下载链接:包括matlab程序+word报告+视频动画,具体如下图 下载链接:版本二 下载链接:版本三 下载链接:版本三 一. 目的 1.设计一个六自由度机器人,至少包含一个伸缩关节,要求机器人工作空 ...

最新文章

  1. mysql left join的深入探讨
  2. 计算机电子琴弹奏怎么打开,怎么打开电脑键盘电子琴软件
  3. android lable标签,android:label说明
  4. 论文浅尝 | 基于神经网络的推理(DeepMind Relational Reasoning)
  5. 整合apache和JBoss,配置虚拟主机
  6. 软考网络工程师--知识产权与标准化
  7. python set_Python Set联合
  8. php遍历指定目录下的文件,PHP遍历指定目录下所有文件和目录
  9. 关于坑爹的编解码问题
  10. 自己做量化交易软件(42)小白量化实战15--自编股票软件公式历史与聚宽量化平台仿大智慧指标回测设计
  11. Notepad++删除空白行
  12. 比较有理数大小C语言pta,有理数比较PTA
  13. background详解
  14. 一、EulerOS 操作系统入门
  15. 使用 Pytorch 训练 AlexNet 识别5种花朵
  16. 火爆的人工智能项目都在这里了|Gitee项目推荐
  17. 如何测试WizFi210的”串口转无线”功能?
  18. 小白用ESP8266NodeMcu机智云SOC方案开发经验分享
  19. ddraw 的blt 方法
  20. 搞ACM,以后能干什么

热门文章

  1. python用七巧板图片画个图_画一个太大而不能放进一个七巧板的图像
  2. HTML设置文字和图片居中
  3. java电商平台_Java开源生鲜电商平台
  4. Ubuntu Kylin系统中配置Apache服务器
  5. Web全栈开发1+x(中级)PHPMySQL知识
  6. 初学Java常用设计模式之——原型模式
  7. [1609.04802] SRGAN中的那些loss
  8. 指针和地址之间的关系是什么?
  9. matlab中a2=poly(p2),插值与拟合matlab实现
  10. 对坐标的曲线积分求做功_曲线积分与曲面积分(前篇 曲线积分-坐标曲线积分-格林公式)...