matlab自带优化工具和casadi对相同参考轨迹进行优化的结果

废话不多说,直接上图,规划时间0.5s 分16步计算,期望终点位置[1,0,0.2]' 由于时间较短,且给定的参考轨迹为简单的线性插值,规划出的轨迹并没有到期望的终点;

参考论文为[Online Trajectory Optimization for Dynamic Aerial Motions of a Quadruped Robot],[Implementing Regularized Predictive Control for Simultaneous Real-Time Footstep and Ground Reaction Force Optimization]

图为优化问题设置部分参考,引子第二篇文献,两篇文献优化问题非常类似

图一为matlab自带的fmincon函数求解,速度奇慢,这个过程大概算了3分钟

图二为casadi求解器求解,过程大概只需要半秒

三维动画为慢放后效果

casadi代码可以参考se-hwan/landing-controller: Trajectory optimization in MATLAB for MIT Cheetah (github.com)

#使用matlab自带求解器 运算奇慢无比
clc;
clear;
warning off
%%
%物理参数
Body.m = 9;%机器人质量
%机身惯量
Body.Ib = [0.07 0     0;0    0.26   0;0    0     0.242];%转动惯量矩阵
Body.length_body=0.38;
Body.width_body=0.22;
Body.hipPos=[0.2,0.2,-0.2,-0.2;0.1,-0.1,0.1,-0.1;0,  0,   0, 0];
g = 9.8;%重力加速度
mu=0.4;%摩擦系数
%%
foot_pos=[0.2,0.2,-0.2,-0.2;0.1,-0.1,0.1,-0.1;0,      0,   0,      0];%状态的权重
weight.QX = [10 10 10, 10 10 10, 10 10 10, 10 10 10 0]';
weight.QN = [50 50 100, 10 10 100, 10 10 10, 10 10 10 0]';
weight.Qc = [0.001 0.001 0.001]';
weight.Qf = [0.0001 0.0001 0.001]';
%%N = 16; % N = 11
T = 0.5; % T = 0.22
dt_val = repmat(T/(N-1),1,N-1)';
cs_val = [repmat([1 1 1 1]', 1, 2) repmat([1 1 1 1]', 1, 2) repmat([0 0 0 0]', 1, 8) repmat([1 1 1 1]', 1, 3)]';
cs_TD_val = zeros(4,N-1)';q_init_val = [0 0 0 0 0 0.2]';
qd_init_val = [0 0 0 0 0 0]';q_term_ref = [0 0 0 1 0 0.6]';
qd_term_ref = [0 0 0, 0 0 0]';c_init_val = repmat(q_init_val(4:6),4,1)+...diag([1 1 1, 1 -1 1, -1 1 1, -1 -1 1])*repmat([0.2 0.1 -q_init_val(6)],1,4)';c_ref = diag([1 1 1, 1 -1 1, -1 1 1, -1 -1 1])*repmat([0.2 0.1 -0.2],1,4)';
f_ref = zeros(12,1);%% set parameter values
for i = 1:6Xref_val(i,:)   = linspace(q_init_val(i),q_term_ref(i),N);Xref_val(6+i,:) = linspace(qd_init_val(i),qd_term_ref(i),N);
end
Xref_val(13,:)=ones(1,N)*-9.8;
% Z向抛物线
a=[Xref_val(4,1),Xref_val(4,N/2),Xref_val(4,N)];%x
b=[q_init_val(6),q_term_ref(6),q_init_val(6)+0.0];%z
Xref_val(6,:) =interp1(a,b,Xref_val(4,:),'spline');
Uref_val=zeros(24,N-1);
for leg = 1:4for xyz = 1:3Uref_val(3*(leg-1)+xyz,:)= Xref_val(xyz+3,1:end-1) + c_ref(3*(leg-1)+xyz);%FUref_val(12+3*(leg-1)+xyz,:) = f_ref(xyz).*ones(1,N-1);%Pend
endX_initial=Packge(Xref_val,Uref_val(13:24,:),Uref_val(1:12,:),N);
[aa,bb,vv]=unPackge(X_initial,N);
for i=1:N-1cube_animate(aa(:,i),i,vv(:,i),~cs_val(i,:),[0;0;0;0],...bb(:,i),3,[],[],[],[],[],[]);
pause(0.1);
endtemplb=[-Body.m*g*mu*6;-Body.m*g*mu*6;0];
tempub=[Body.m*g*mu*6;Body.m*g*mu*6;1000];UB=[pi*3*ones(3,1);10*ones(2,1);1;...pi*3*ones(3,1);40*ones(3,1);-9.8;...tempub;10*ones(3,1);tempub;10*ones(3,1);tempub;10*ones(3,1);tempub;10*ones(3,1)];LB=[-pi*3*ones(3,1);-10*ones(2,1);0;...-pi*3*ones(3,1);-40*ones(3,1);-9.8;...templb;-10*ones(3,1);templb;-10*ones(3,1);templb;-10*ones(3,1);templb;-10*ones(3,1)];UB=repmat(UB,N,1);
LB=repmat(LB,N,1);
%%Data.body=Body;
Data.dt=dt_val;
Data.mu=mu;
% constraints(X0,N,Data,table);
% cost(X0,X_Ref,weight,N);
Aa=[];Bb=[];Aeq=[];Beq=[];
%%
FUN=@(x)cost(x,X_initial,weight,N,Body,Data);NONLCON=@(x)constraints(x,N,Data,cs_val,X_initial);OPTIONS=optimoptions('fmincon','Display','iter','Algorithm','sqp');%,'OptimalityTolerance',1e-6,'MaxIterations',500X=fmincon(FUN,X_initial,Aa,Bb,Aeq,Beq,LB,UB,NONLCON,OPTIONS);
%
[Xstate,Ffoot,Pfoot]=unPackge(X,N);
%%
pic_num = 1;%保存gif用
for i=1:N-1cube_animate(Xstate(:,i),i,Pfoot(:,i),~cs_val(i,:),[0;0;0;0],...Ffoot(:,i),3,[],[],[],[],[],[-30,60]);frame = getframe(figure(3));[A,map]=rgb2ind(frame2im(frame),256);if pic_num==1imwrite(A,map,'testAnimated.gif','gif','LoopCount',Inf,'DelayTime',dt_val(i));elseimwrite(A,map,'testAnimated.gif','gif','WriteMode','append','DelayTime',dt_val(i));endpic_num=pic_num+1;
pause(0.1);
end%% 可视化函数
function cube_animate(X,time,foot_pos,swingstate,pre_contact,feetforce_used,fig,X_ref_mpc,path,mpcTra,Xtra,Polygon,View)
%可视化函数 参考系为世界系 接触脚为绿色,摆动为红色
%输入
%   X:需要绘制的状态向量
%   time:显示在图上的时间
%   foot_pos:落足点位置
%   swingstate:摆动状态
%   pre_contact:提前接触状态
%   feetforce_used:控制力
%   fig:窗口序号
%   X_ref_mpc:参考轨迹
%   path:跟踪路径
%输出
%   无
figure(fig);
clf; hold on; grid on; axis equal;
if ~isempty(View)view(View(1), View(2))
elseview(-0, 0);%视角控制,目前为跟随机器人后方,从 45 方向看机器人 X(3)*180/pi
end
%绘制参考轨迹
if ~isempty(X_ref_mpc)plot_temp=[];for i=1:length(X_ref_mpc)/13plot_temp=[plot_temp,X_ref_mpc((i-1)*13+4:(i-1)*13+6)];endplot3(plot_temp(1,:),plot_temp(2,:),plot_temp(3,:),'*');%绘制参考轨迹,'linewidth',6
end
%%绘制跟踪路径
if ~isempty(path)plot3(path(:,1),path(:,2),ones(length(path(:,2)),1)*0.28);
end
if ~isempty(Polygon)plot3(Polygon(1),Polygon(2),0,'o');
end%绘制mpc预测的轨迹
if ~isempty(mpcTra)plot_temp2=[];for i=1:length(mpcTra)/13plot_temp2=[plot_temp2,mpcTra((i-1)*13+4:(i-1)*13+6)];endplot3(plot_temp2(1,:),plot_temp2(2,:),plot_temp2(3,:),'o');
endif ~isempty(Xtra)plot3(Xtra(4,:),Xtra(5,:),Xtra(6,:));
endR = rotz(X(3))*roty(X(2))*rotx(X(1));%旋转矩阵plot3([X(4),X(4)+0.1*X(7)],[X(5),X(5)+0.1*X(8)],[X(6),X(6)+0.1*X(9)]);%当前角速度向量
plot3([X(4),X(4)+0.1*X(10)],[X(5),X(5)+0.1*X(11)],[X(6),X(6)+0.1*X(12)]);%当前速度向量plot_cube(R,0.38,0.22,0.10,[X(4),X(5),X(6)]');%绘制机身str=['pos: ',num2str(X(4:6)')];
str1=['rad: ',num2str(X(1:3)')];
text(X(4)+0.25,X(5)+0.25,X(6)-0.25,str);%标注POS/m
text(X(4)-0.25,X(5)-0.25,X(6)+0.25,str1);%标注rpy/rad
text(X(4),X(5)+0.5,X(6),num2str(time*0.002));%标注时间/s%绘制落脚点位置、r向量、力向量
for i=1:4x_indx=3*(i-1)+1;y_indx=3*(i-1)+2;z_indx=3*(i-1)+3;if  swingstate(i)>0 && pre_contact(i)~=1text(foot_pos(x_indx),foot_pos(y_indx),foot_pos(z_indx),num2str(i),'Color','red');%在落点标注脚序号 摆动用红色plot3([foot_pos(x_indx),foot_pos(x_indx)+0.01*feetforce_used(x_indx)],...[foot_pos(y_indx),foot_pos(y_indx)+0.01*feetforce_used(y_indx)],...[foot_pos(z_indx),foot_pos(z_indx)+0.01*feetforce_used(z_indx)]);elsetext(foot_pos(x_indx),foot_pos(y_indx),foot_pos(z_indx),num2str(i),'Color','green');%在落点标注脚序号 接触用绿色plot3([foot_pos(x_indx),foot_pos(x_indx)+0.01*feetforce_used(x_indx)],...[foot_pos(y_indx),foot_pos(y_indx)+0.01*feetforce_used(y_indx)],...[foot_pos(z_indx),foot_pos(z_indx)+0.01*feetforce_used(z_indx)]);plot3([X(4),foot_pos(x_indx)],[X(5),foot_pos(y_indx)],[X(6),foot_pos(z_indx)]);%riend
endaxis([X(4)-1,X(4)+1,X(5)-1,X(5)+1,0,0.8]);%坐标系范围 以当前机身为中心
xlabel('x');ylabel('y');zlabel('z');%规范x,y,z坐标轴刻度范围,及在各自坐标轴上标注字母x,y,z
drawnow;
endfunction plot_cube(R, a, b, c,pos)
x = [-1,  1,  1, -1, -1,  1,  1, -1] * a/2;
y = [-1, -1,  1,  1, -1, -1,  1,  1] * b/2;
z = [-1, -1, -1, -1,  1,  1,  1,  1] * c/2;
P = R * [x; y; z]+pos;
order = [1, 2, 3, 4, 1, 5, 6, 7, 8, 5, 6, 2, 3, 7, 8, 4];
plot3(P(1, order), P(2, order), P(3, order), 'b');
end
%% 工具函数
function rotxm=rotx(theta)
s=sin(theta);
c=cos(theta);
% rotxm=[1,0,0;
%     0,c,s
%     0,-s c]';
rotxm=[1,0,0;0,c,-s0,s c];
endfunction rotym=roty(theta)
s=sin(theta);
c=cos(theta);
% rotym =[c,0,-s;
%     0,1,0;
%     s,0,c]';
rotym =[c,0,s;0,1,0;-s,0,c];
endfunction rotzm=rotz(theta)
s=sin(theta);
c=cos(theta);% rotzm=[c,s,0;
%     -s,c,0;
%     0,0,1]';
rotzm=[c,-s,0;s,c,0;0,0,1];
end
%Rsb
function R=rotsb(theta)
% R=rotx(theta(1))*roty(theta(2))*rotz(theta(3));
R=rotz(theta(3))*roty(theta(2))*rotx(theta(1));endfunction s=Skew(in)
s=zeros(3,3);
s(1,2)=-in(3);
s(1,3)=in(2);
s(2,3)=-in(1);
s(2,1)=in(3);
s(3,1)=-in(2);
s(3,2)=in(1);
% s = [0 -in(3) in(2);
%     in(3) 0 -in(1);
%     -in(2) in(1) 0];
end%% 代价
function t=cost(X_,X_ref,weight,N,Body,Data)
%   代价函数
%   输入:
%       x 状态 [r p y x y z wx wy wz vx vy vz -g]'
%       u 输入 [f1 p1 f2 p2 f3 p3 f4 p4]'
%       整合变量 x =[x;u](N+1个) [x1;u1;x2;u2....];
%       x_ref:参考轨迹 [x;u](N+1个) [x1;u1;x2;u2....];
%       weigth 权重
%    输出:
%       代价:sum1~N{[(x(i)-xref(i))'*Qk*(x(i)-xref(i))+(u(i)-uref(i))'*Rk*(u(i)-uref(i))]}
%               +x(N+1)'*Qn*x(N+1)
t=0;
[X,U,P]=unPackge(X_,N);
[Xref,Uref,~]=unPackge(X_ref,N);
Body.hipPos(3,:)=ones(1,4)*-0.2;
Phip=reshape(Body.hipPos,[],1);
for k = 1:(N-1)                  % costX_err = X(:,k) - Xref(:,k);                                         % 基座状态误差pf_err = repmat(X(4:6,k),4,1) + Phip - P(:,k);                      %  悬空时约束foot位置U_err = U(:,k) - Uref(:,k);                                         % GRF 误差t = t + (X_err'*diag(weight.QX)*X_err+...                     % 误差求和pf_err'*diag(repmat(weight.Qc,4,1))*pf_err+...U_err'*diag(repmat(weight.Qf,4,1))*U_err)*Data.dt(k);
endX_err = X(:,end)-Xref(:,end);    % 终端 cost
t = t + X_err'*diag(weight.QN)*X_err;
end
%% 约束
function [c,ceq]=constraints(X_,N,D,table,X_ref)
%   输入:
%       x 状态 [r p y x y z wx wy wz vx vy vz -g]'
%       u 输入 [f1 p1 f2 p2 f3 p3 f4 p4]'
%       整合变量 X =[x;u](N+1个) [x1;u1;x2;u2....];
%       N:分段数
%       D:Data结构体 D.param.dt;D.body.m;D.body.hipPos;D.mu;D.body.Ib;
%       table: 未来分段中的接触状态
%   输出:
%       ceq=0:非线性等式约束
%       c<0;非线性不等式约束dt=D.dt;%时间间隔
m=D.body.m;%刚体质量
D.body.hipPos;%hip位置
mu_inv = 1.0/D.mu;
%摩擦约束
f_block =[ mu_inv, 0,  -1.0;-mu_inv, 0,  -1.0;0,  mu_inv, -1.0;0, -mu_inv, -1.0;];kin_box_x = 0.05;
kin_box_y = 0.05;
kin_box_z = 0.3;Kin_block =[ 1, 0,  0,-kin_box_x;-1, 0,  0,-kin_box_x;0, 1, 0,-kin_box_y;0, -1, 0,-kin_box_y;0, 0, 1,0.06;0, 0, -1,-kin_box_z];%将状态解包
% [Xstate,Ffoot,Pfoot]=unPackge(x,N);
[X,U,P]=unPackge(X_,N);
[Xref,~,~]=unPackge(X_ref,N);
%各种约束定义 之后优化速度时预分配内存
%初态约束
defect_init=Xref(:,1)-X(:,1);defect_state=zeros(13*N,1);%13N*1
defect_FootOnGround=zeros(4*(N-1),1);%4(N-1)*1
defect_legLimits=zeros(24*(N-1),1);%(4*6)(N-1)*1
defect_footStance=zeros(12*(N-1),1);%(3*4)(N-1)*1
defect_footforce=zeros(16*(N-1),1);%(4*4)(N-1)*1 xy摩擦约束4个
defect_ForceNormal=zeros(N-1,1);% (N-1)*1
defect_footswing=zeros(4*(N-1),1);%4(N-1)*1
%计算约束
A=zeros(13);
B=zeros(13,12);
I3=eye(3);
for i=1:N-1Xk=X(:,i);Fk=U(:,i);Pk=P(:,i);ContactStatek=table(i,:);dtk=dt(i);Rbody=rotsb(Xk(1:3));%计算角速度转换矩阵cy = cos(Xk(3));sy = sin(Xk(3));cp = cos(Xk(2));sp = sin(Xk(2));R_w=[cy/cp,sy/cp,0;-sy,cy,0;cy*sp/cp,sy*sp/cp,1];Ig = Rbody*D.body.Ib*Rbody';Ig_inv=Ig\I3;%hip在世界系Phip=Rbody*D.body.hipPos+Xk(4:6);r1=Pk(1:3)-Xk(4:6);r2=Pk(4:6)-Xk(4:6);r3=Pk(7:9)-Xk(4:6);r4=Pk(10:12)-Xk(4:6);%%A = [zeros(3) zeros(3) R_w zeros(3) zeros(3,1) ;zeros(3) zeros(3) zeros(3) I3 zeros(3,1);zeros(3) zeros(3) zeros(3) zeros(3) zeros(3,1);zeros(3) zeros(3) zeros(3) zeros(3) zeros(3,1);zeros(1,3) zeros(1,3) zeros(1,3) zeros(1,3) 0];%状态矩阵%%%     A(1:3,7:9)=R_w;%     A(4:6,10:12)=I3;A (12,13)=1;%%B=[zeros(3)           zeros(3)           zeros(3)            zeros(3);zeros(3)           zeros(3)           zeros(3)            zeros(3);Ig_inv*Skew(r1) Ig_inv*Skew(r2) Ig_inv*Skew(r3)  Ig_inv*Skew(r4);I3/m   I3/m   I3/m    I3/m;zeros(1,3) zeros(1,3) zeros(1,3) zeros(1,3)];%控制矩阵%%%     B(7:12,1:12)=[Ig_inv*Skew(r1) Ig_inv*Skew(r2) Ig_inv*Skew(r3)  Ig_inv*Skew(r4);%         I3/m   I3/m   I3/m    I3/m;];%动力学约束 Xk+1-f(Xk,Uk)=0defect_state((i-1)*13+1:(i-1)*13+13)=X(:,i+1)-(Xk+(A*Xk+B*Fk)*dtk);%法向力大于0 不等式defect_ForceNormal(i)=-dot(Fk,repmat([0;0;1],4,1));%结合法向力大于0,摩擦约束来约束摆动中力为0 和最大力 不等式defect_footswing((i-1)*4+1:(i-1)*4+4)=Fk([3,6,9,12])-ContactStatek'.*repmat(1000,4,1);for leg=1:4xyz_idx = 3*(leg-1)+1:3*(leg-1)+3;%脚在地上约束 0是此时地面高度等式defect_FootOnGround((i-1)*4+leg)=ContactStatek(leg)*Pk(3*(leg-1)+3);%限制腿长 限制范围不等式p_rel = (Pk(xyz_idx) - Phip(:,leg));%hip->足端defect_legLimits((i-1)*24+(leg-1)*6+1:(i-1)*24+(leg-1)*6+6)= Kin_block*[p_rel;1];%接触中脚不滑动if (i+1 < N)defect_footStance((i-1)*12+(leg-1)*3+1:(i-1)*12+(leg-1)*3+3)=ContactStatek(leg)*(P(xyz_idx,i+1)-Pk(xyz_idx));end%摩擦约束 不等式defect_footforce((i-1)*16+(leg-1)*4+1:(i-1)*16+(leg-1)*4+4)=f_block*Fk(xyz_idx);endend
%defect_legLimits;
c=[defect_legLimits;defect_footforce;defect_ForceNormal;defect_footswing];
%动力学约束 脚在地上约束 接触中脚不滑动 %%起点约束x(0)=0 终端约束 x(N)-des=0; 不需要起止约束
ceq=[defect_init;defect_state;defect_FootOnGround;defect_footStance];
% figure(6);
% plot(c);
% axis([-inf,inf,-inf,1]);
% drawnow;
end
%% 解包
function [Xstate,Ffoot,Pfoot]=unPackge(x,N)
Xstate=zeros(13,(N));%13*(N+1)
Ffoot=zeros(3*4,(N-1));%3*4(N+1)
Pfoot=zeros(3*4,(N-1));%3*4(N+1)
%将状态解包
for i=1:NXstate(:,i)=x((i-1)*37+1:(i-1)*37+13);if i>N-1continue;endfor leg=1:4Ffoot((leg-1)*3+1:(leg-1)*3+3,(i-1)+1)=x((i-1)*37+13+(leg-1)*6+1:(i-1)*37+13+(leg-1)*6+3);Pfoot((leg-1)*3+1:(leg-1)*3+3,(i-1)+1)=x((i-1)*37+16+(leg-1)*6+1:(i-1)*37+16+(leg-1)*6+3);end
end
end
%% 打包
function x=Packge(Xstate,Ffoot,Pfoot,N)
x=zeros(37*(N),1);%37*N+1
%将状态解包
for i=1:Nx((i-1)*37+1:(i-1)*37+13)=Xstate(:,i);if i>N-1continue;endfor leg=1:4x((i-1)*37+13+(leg-1)*6+1:(i-1)*37+13+(leg-1)*6+3)=Ffoot((leg-1)*3+1:(leg-1)*3+3,(i-1)+1);x((i-1)*37+16+(leg-1)*6+1:(i-1)*37+16+(leg-1)*6+3)=Pfoot((leg-1)*3+1:(leg-1)*3+3,(i-1)+1);end
end
end

四足机器人跳跃轨迹优化相关推荐

  1. 【转载】MIT四足机器人Cheetah 3控制方案笔记

    转载:知乎 Wenboxing https://zhuanlan.zhihu.com/p/190028074 这里写自定义目录标题 MIT四足机器人Cheetah 3控制方案理解笔记(1)--摆动腿控 ...

  2. 四足机器人 2.建模和步态规划

    1.建模 四足机器人建模: 运动学建模和动力学建模 四足机器人在运动过程中,与所处环境进行交互作用,为提高机器人运动的稳定性和适应性,需要整体考虑四足机器人的动力学模型.足-地接触模型和步态生成与变换 ...

  3. 【灯哥开源四足机器人】推荐一个开源四足机器狗项目,8自有度,两个舵机控制一个腿,apache开源协议的,已经迭代了好多个版本了,设计的非常好。有官方淘宝店,没有3D打印机的可以购买散装零件自己组装

    目录 前言 1,关于[灯哥开源四足机器人] 2,使用py-apple 3,总结 前言 本文的原文连接是: https://blog.csdn.net/freewebsys/article/detail ...

  4. MIT四足机器人Cheetah 3控制方案理解笔记(1)——摆动腿控制、单刚体模型平衡控制器

    之前一段时间在阅读MIT四足机器人Cheetah 3以及Mini Cheetah控制方案的相关论文,在此处做一些笔记.Cheetah 3与Mini Cheetah的控制方案大同小异,此处先以Cheet ...

  5. 四足论文《面对未知地形的四足机器人足端轨迹优化》解读

    在笔者的关于足端轨迹规划的文章中,曾经提到了类正弦轨迹,该规划是根据斯坦福的四足机器人Doggo的开源代码中得出的.而该轨迹的缺点是对于地形的适应差,无法自适应的调节自身足端的轨迹规划. 基于该种问题 ...

  6. 四足机器人足端轨迹规划--摆线

    古月居课程四足机器人控制与仿真入门笔记,视频链接:link 四足机器人足端轨迹规划--摆线 摆线定义 模型表示 matlab程序 摆线定义 摆线,又称旋轮线.圆滚线,在数学中,摆线(Cycloid)被 ...

  7. 四足机器人并联腿足端轨迹Matlab仿真

    四足机器人并联腿足端轨迹Matlab仿真 轨迹计算 轨迹是分成两部分:摆线方程+水平线段 首先,设置大腿关节轴心坐标为(0,0),根据机械设计的大腿小腿长度设置参数.此处设置大腿 l1=100mm,小 ...

  8. eigen库安装_四足机器人优化方法:Webots下Eigen与qpOASES非线性优化库环境搭建

    在最小二乘法一章节中我给出了基于matlab仿真下的手推最小二乘解方法,最终采用广义法能将任意多组数据求最小二乘解转换为求取固定矩阵元素平均值的形式从而避免数据增长带来的计算量增大: https:// ...

  9. 【四足机器人】学习笔记 足端轨迹规划和步态规划

    [四足机器人]学习笔记 足端轨迹规划和步态规划 一.足端轨迹规划(摆线) 二.步态规划 1.Walk步态 2.Trot步态 近期,博主在古月居学习关于四足机器人的相关部分知识,从阳炼老师的四足机器人控 ...

最新文章

  1. 使用微软提供的Office Online实现Office文档的在线查看,编辑等功能
  2. 在线作图|如何实现染色体标记
  3. 谷歌翻译大型翻车现场:请服用“反坦克导弹”来缓解疼痛,UCLA:医生们要注意了...
  4. matlab用lism求零输入响应,信号与系统matlab课后作业_北京交通大学讲解.docx
  5. vue-router的hash模式和history模式,
  6. [js] 写一个 document.querySelector 的逆方法
  7. 《啊哈 C语言》读书笔记
  8. python基础实例 韦玮 pdf_Python程序设计基础实战教程
  9. 上海市新能源汽车分时租赁规划策略研究
  10. C语言逻辑运算符: 和 ||
  11. plsql打开sql窗口快捷键_PL/SQL 快捷键设置
  12. Python3-爬虫登录开心网的账号,并且爬取个人主页内容
  13. PPT总结篇之字体,图片
  14. nacos运行报jar的错Failed to get nested archive for entry BOOT-INF/lib/XXX.jar
  15. 从零学习Belief Propagation算法(一)
  16. c语言曲率计算,曲率及其曲率半径及计算.ppt
  17. OpenState安装及 Port Knocking 实验
  18. 我们是如何改进YOLOv3进行红外小目标检测的?
  19. -01-OV7251摄像头与设计规划【Xilinx-LVDS读写功能实现】
  20. 利用卡口数据绘制断面基本图——Python交通数据分析

热门文章

  1. Vmware 15 新建虚拟机黑屏
  2. 区块链6-以太坊入门
  3. [SpringBoot系列]SSMP整合小项目
  4. Chapter 1 First Sight——35
  5. 动态规划模板题Day5
  6. ultraiso制作u盘系统linux,ultraiso制作Linux USB启动盘的操作步骤
  7. 算法设计——数学运算:数的整除问题
  8. vue 渲染对象object
  9. sql server中较大的sql脚本如何执行,sqlcmd
  10. 彭明清《完全求生手册》