-
Notifications
You must be signed in to change notification settings - Fork 22
/
update_quadrotor_3D.m
72 lines (62 loc) · 2.85 KB
/
update_quadrotor_3D.m
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
function [ new_quad3D ] = update_quadrotor_3D( quad3D, state )
%UNTITLED4 Summary of this function goes here
% Detailed explanation goes here
% update attitude
R = rotation_mat_body2inertia(state.att.q);
[row col] = size(quad3D.Arm1.X);
for c = 1:col
P1 = [quad3D.Arm1.X(:,c)'; quad3D.Arm1.Y(:,c)'; quad3D.Arm1.Z(:,c)'];
P2 = R * P1;
quad3D.Arm1.PosX(:,c) = P2(1,:)';
quad3D.Arm1.PosY(:,c) = P2(2,:)';
quad3D.Arm1.PosZ(:,c) = P2(3,:)';
P1 = [quad3D.Arm2.X(:,c)'; quad3D.Arm2.Y(:,c)'; quad3D.Arm2.Z(:,c)'];
P2 = R * P1;
quad3D.Arm2.PosX(:,c) = P2(1,:)';
quad3D.Arm2.PosY(:,c) = P2(2,:)';
quad3D.Arm2.PosZ(:,c) = P2(3,:)';
end
[row col] = size(quad3D.Rotor1.X);
for c = 1:col
P1 = [quad3D.Rotor1.X(:,c)'; quad3D.Rotor1.Y(:,c)'; quad3D.Rotor1.Z(:,c)'];
P2 = R * P1;
quad3D.Rotor1.PosX(:,c) = P2(1,:)';
quad3D.Rotor1.PosY(:,c) = P2(2,:)';
quad3D.Rotor1.PosZ(:,c) = P2(3,:)';
P1 = [quad3D.Rotor2.X(:,c)'; quad3D.Rotor2.Y(:,c)'; quad3D.Rotor2.Z(:,c)'];
P2 = R * P1;
quad3D.Rotor2.PosX(:,c) = P2(1,:)';
quad3D.Rotor2.PosY(:,c) = P2(2,:)';
quad3D.Rotor2.PosZ(:,c) = P2(3,:)';
P1 = [quad3D.Rotor3.X(:,c)'; quad3D.Rotor3.Y(:,c)'; quad3D.Rotor3.Z(:,c)'];
P2 = R * P1;
quad3D.Rotor3.PosX(:,c) = P2(1,:)';
quad3D.Rotor3.PosY(:,c) = P2(2,:)';
quad3D.Rotor3.PosZ(:,c) = P2(3,:)';
P1 = [quad3D.Rotor4.X(:,c)'; quad3D.Rotor4.Y(:,c)'; quad3D.Rotor4.Z(:,c)'];
P2 = R * P1;
quad3D.Rotor4.PosX(:,c) = P2(1,:)';
quad3D.Rotor4.PosY(:,c) = P2(2,:)';
quad3D.Rotor4.PosZ(:,c) = P2(3,:)';
end
% update position
quad3D.Arm1.PosX = quad3D.Arm1.PosX + state.posI(1);
quad3D.Arm1.PosY = quad3D.Arm1.PosY + state.posI(2);
quad3D.Arm1.PosZ = quad3D.Arm1.PosZ + state.posI(3);
quad3D.Arm2.PosX = quad3D.Arm2.PosX + state.posI(1);
quad3D.Arm2.PosY = quad3D.Arm2.PosY + state.posI(2);
quad3D.Arm2.PosZ = quad3D.Arm2.PosZ + state.posI(3);
quad3D.Rotor1.PosX = quad3D.Rotor1.PosX + state.posI(1);
quad3D.Rotor1.PosY = quad3D.Rotor1.PosY + state.posI(2);
quad3D.Rotor1.PosZ = quad3D.Rotor1.PosZ + state.posI(3);
quad3D.Rotor2.PosX = quad3D.Rotor2.PosX + state.posI(1);
quad3D.Rotor2.PosY = quad3D.Rotor2.PosY + state.posI(2);
quad3D.Rotor2.PosZ = quad3D.Rotor2.PosZ + state.posI(3);
quad3D.Rotor3.PosX = quad3D.Rotor3.PosX + state.posI(1);
quad3D.Rotor3.PosY = quad3D.Rotor3.PosY + state.posI(2);
quad3D.Rotor3.PosZ = quad3D.Rotor3.PosZ + state.posI(3);
quad3D.Rotor4.PosX = quad3D.Rotor4.PosX + state.posI(1);
quad3D.Rotor4.PosY = quad3D.Rotor4.PosY + state.posI(2);
quad3D.Rotor4.PosZ = quad3D.Rotor4.PosZ + state.posI(3);
new_quad3D = quad3D;
end