Mikrokopter's Documentation
Mikrokopter's Documentation
Mikrokopter's Documentation
Cyphy Laboratory
Inkyu Sa
September 19, 2011
Contents
I. Introduction
A. Purpose
B. Coordinate systems
C. Position control
1. SI units
11
G. System latency
12
H. Velocity estimation
15
1. X axis acceleration
15
2. Y axis acceleration
16
3. Z axis acceleration
17
I. ROS implementation
22
J. Yaw control
23
K. Altitude control
25
26
26
28
28
O. Precision comparison
29
30
31
II. References
34
References
35
A. Matlab implementation
36
I.
INTRODUCTION
A.
Purpose
The objectives of this document are to create written history while implementing the
quadrotor using Mikrokopter (MK). In addition it will be a good opportunity to share this
knowledge with other researchers who are interested in using the MK platform.
B.
Coordinate systems
The MK doesnt specify a scientific coordinate system. It only has pitch, roll and yaw
angles. The red bar is the front and the opposite is the rear. Pitch (Nick) angle results
in forwards and backwards movements. In contrast, roll angle results in left and right
movements. When we push all the way up the pitch stick (right stick on mode2), StickNick
value (516) is transmitted to the FlightControl(FC). This implies moving forward with the
fastest speed. It is the maximum value of pitch angle. When we pull all the way down
the pitch stick, StickNick value (-592) is transmitted to the FC. This implies moving
backward with the fastest speed. On the other hand, when pushed all the way right, the
roll stick, StickRoll value (-516) is transmitted to the FC. When pushed all the way left, the
roll stick, StickRoll value (512) is transmitted to the FC. Commonly the forward direction
is the x-axis of robots and the right direction is the positive y-axis. Pitch angle implies
rotation around the y-axis and the roll angle implies rotation around x-axis according to the
right-hand rule. Positive pitch angle causes the vehicle to move backwards- the opposite of
MK notation. Positive roll angle causes it to move right-again the opposite of MK notation.
<
=
0
>
1
2
?
3
@
;4
5
6
/7
8
9
:.A
-B
+
,C
*#
D
$
%
)"E
(F
!&
G
'K
JH
L
M
IN
~
O
}P
|m
Q
u
w
v{zyxtR
sln
ko
p
q
rS
T
jU
g
h
V
ia
b
d
ce
W
f_
`^]X
\Y
Z
[
AccZ
yaw
MK frame
NickAngle
AccRoll
AccNick
RollAngle
Body frame
World frame
xis
x-a
yax
z-axis
x-axis
roll,
is
Note
All coordinate frames is
ruled by right hand.
y-axis
pitch,
yaw,
z-axis
C.
Position control
In order to control the quadrotor, a traditional PD controller is implemented. The inputs for the controller are desired position and velocity and the outputs are pitch and roll
commands. The laser range finder provides x,y positions and a yaw angle every 100ms and
these PD controllers generate outputs at the same rate. The unit of the position and angle
are represented in SI units, such as metres and radian.
d W W
( x x)
dt
d
W
= Kp (W y W y) + Kd (W y W y)
dt
= Kp (W x W x) + Kd
(1)
(2)
notes the pitch input in world frame and W x is the reference input which the quadrotor
should follow.
x is the current position of the quadrotor in the world frame and this data
is provided from the laser scan matcher. The desired output to the MK must be in the
range 128. Inputs are divided by the scale factor(120).
Then command angles are with respect to the world frame. The world and body frames
are related by the yaw angle transformation.
RW () =
cos
sin
sin
cos
where is the angle of the world frame with respect to the body frame.
B
W
= R()
B
W
(3)
(4)
= cos W sin W
(5)
(6)
= sin W + cos W
5
Pitch
90
60
50
45
15
15
45
50
60
90
1st
602
522
458
428
152
-122
-431
-457
-531
-617
2nd
602
525
468
432
154
-123
-433
-462
-532
-618
3rd
602
523
470
422
153
-122
-432
-463
-532
-617
Mean
602
523.3
465.3
427.3
153
-122.3
-432
-460.6
-531.6
-617.3
TABLE I: MK AccNick Acceleration versus pitch true angle measurement ruled by right
hand.
D.
MK doesnt provide either SI units or documents explaning MK units. These data are
unscaled measurements. Hence we try to figure out what the actual units are. This data is
measured by an external accelerometer and MikroKopter Tool V1.72.
a. Pitch acceleration The contents of TABLE I are the pitch acceleration data from
the MK. The unit of the measurement is unknown.
Fig. 3 shows the linear line fitting with the measured data. In the x-direction the equation
of motion is
x = k sin
(7)
Where x refers to the acceleration data provided from MK quadrotor, k is the scale factor
and is the pitch angle. Finally, k = 606.3 units/g can be calculated and the acceleration
value also can be obtained in units of 1g.
b.
Roll acceleration The contents of TABLE II are the roll acceleration data from
90
60
50
45
15
15
45
50
60
90
1st
612
522
458
436
162
-167
-430
-462
-522
-587
2nd
611
521
456
443
161
-162
-432
-463
-515
-588
3rd
613
523
457
439
160
-165
-431
-463
-517
-588
Mean
612
522
457
439.3
161
-164.6
-431
-462.6
-518
-587.6
TABLE II: MK roll acceleration versus true roll angle measurement ruled by right hand
c.
Z acceleration The drifting problem of raw ACCZ ADC measurement was found
when vibration came from four rotors and it was thought that error accumulated when
analog data was converted into digital. Hence the preprocessed MK default ACCZ value
is exploited to estimate the z-velocity. The MK provides vibration robust filtered data
but has an issue that it doesnt know what the unit is. In order to use this acceleration
7
ACCZmiko (t)
+ 9.8
15.5
(8)
FIG. 5:
E.
SI units
All units are used in the system following the SI units. All angle measurements are
represented in Radian and Metre as a unit of all distance and angle measurements and
Second is a unit of time. m/s2 is a unit of all acceleration.
2.
There are two log messages. One is logging attitude of the quadrotor such as pitch
angle and acceleration along x axis. Another measures data using the laser range finder like
position, velocity and estimation of velocity. The reason why we have two log messages is
because of different sampling rates of the laser range finder and the MK quadrotor. Position
data based on the laser range finder comes into every 100ms and attitude of the quadrotor
9
Order
Notation
Description
Unit
g W Vel.x
m/s
g B Vel.y
m/s
g B esti Vel.x
m/s
g W Vel.y
m/s
g B Vel.y
m/s
g B esti Vel.y
m/s
g CurrentPosition.x
current x position.
g CurrentPosition.y
current y position.
g CurrentPosition.theta
current angle.
radian
10
index
number
10
Order
Notation
Description
AnglePitch
Pitch angle
radian
AngleRoll
Roll angle
radian
AngleYaw
Yaw angle
radian
AccX
m/s2
AccY
m/s2
AccZ
m/s2
ControlPitch
unknown
ControlRoll
unknown
ControlYaw
unknown
10
StickPitch
unknown
11
StickRoll
unknown
12
StickYaw
unknown
13
StickThrust
unknown
14
index
Unit
number
50ms sampling time TABLE IV shows the 50ms sampling time log message
protocol.
F.
11
G.
System latency
In order to find out the system latency between the Gumstix and the ground station,
the network time protocol (NTP) server is exploited. NTP allows the setting up of two
systems with less than 1ms time error. Fig. 9 shows synchronised systems and delay.
After synchronisation, time duration was measured using ROS time stamp function. This
function provides s accuracy and it is sufficient to measure the time period.
Fig.
Fig.
delay of the ICP scan matcher. The WIFI latency can be determined by subtraction of
12
300
250
Number
200
150
100
50
0
30
20
10
10
20
30
40
pitch angle[degree]
x 10
4
3.95
3.9
3.85
3.8
3.75
3.7
3.65
3.6
20
15
10
10
15
20
As shown in
the Fig. 8, the MK has about 200ms natural response time and WIFI, laser range finder
and scan matcher have 167ms delay.
13
<
=
0
>
1
2
?
3
@
;4
5
6
/7
8
9
:.A
-B
+
,C
*#
D
$
%
)"E
(F
!&
G
'K
JH
L
M
IN
~
O
}P
|m
Q
u
w
v{zyxtR
sln
ko
p
q
rS
T
jU
g
h
V
ia
b
d
ce
W
f_
`^]X
\Y
Z
[
Desktop Time
100ms delay
Stop streaming
<
=
0
>
1
2
?
3
@
;4
5
6
/7
8
9
:.A
-B
+
,C
*#
D
$
%
)"E
(F
!&
G
'K
JH
L
M
IN
~
O
}P
|m
Q
u
w
v{zyxtR
sln
ko
p
q
rS
T
jU
g
h
V
ia
b
d
ce
W
f_
`^]X
\Y
Z
[
System latency
157ms 167ms
1
50ms
5ms 10ms
2 ms 7 ms
Laser scanner
inherited delay
Transfering Laser
data over WIFI
100ms
time (ms)
Parsing Data, 1s
2s
500s
get data from the
read buffer. 28s
Expand
50 ms
0 ms
ROS thread
20Hz
Velocity estimation
It is necessary to use a velocity estimator because of the complex dynamics and latency
of the system. A complementary filter is exploited and this requires accelerations of each
axis in order to estimate velocities.
1.
X axis acceleration
ax = B x cos g sin
B
x =
ax + g sin
cos
15
(9)
(10)
<
=
0
>
1
2
?
3
@
;4
5
6
/7
8
9
:.A
-B
+
,C
*#
D
$
%
)"E
(F
!&
G
'K
JH
L
M
IN
~
O
}P
|m
Q
u
w
v{zyxtR
sln
ko
p
q
rS
T
jU
g
h
V
ia
b
d
ce
W
f_
`^]X
\Y
Z
[
This is corrected
coordinate frame.
Q
ax
s
co
in
gs
Qf rame
Quadrotor
gs
in
Y axis acceleration
ay = B y cos + g sin
(11)
ay g sin
cos
(12)
y =
16
<
=
0
>
1
2
?
3
@
;4
5
6
/7
8
9
:.A
-B
+
,C
*#
D
$
%
)"E
(F
!&
G
'K
JH
L
M
IN
~
O
}P
|m
Q
u
w
v{zyxtR
sln
ko
p
q
rS
T
jU
g
h
V
ia
b
d
ce
W
f_
`^]X
\Y
Z
[
This is corrected
coordinate frame.
Qf rame
ay
Quadrotor
g sin
y
Q
y c
os
gs
in
Z axis acceleration
az = cos cos (g + Q z)
az
Q
z =
g
cos cos
17
(13)
(14)
<
=
0
>
1
2
?
3
@
;4
5
6
/7
8
9
:.A
-B
+
,C
*#
D
$
%
)"E
(F
!&
G
'K
JH
L
M
IN
~
O
}P
|m
Q
u
w
v{zyxtR
sln
ko
p
q
rS
T
jU
g
h
V
ia
b
d
ce
W
f_
`^]X
\Y
Z
[
This is corrected
coordinate frame.
Qf rame
Quadrotor
az = cos cos (g + Q z)
Q
18
a. A complementary filter
vx (t + 1) = vx (t) + T ( k ( B vx vx (t)) + Q x)
(15)
vy (t + 1) = vy (t) + T ( k ( B vy vy (t)) + Q y)
(16)
vz (t + 1) = vz (t) + T ( k ( B vz vz (t)) + Q z)
(17)
1.5
laser world position x
acc world position x
0.5
0.5
1.5
10
20
30
40
50
60
70
80
90
time [sec]
Fig. 16 is the one sample predicted position using Equation 18. We assume that the
quadrotor is hovering and the velocity of it is almost constant.
19
(18)
= x(t) +
(19)
x(t) x(t 1)
T
T
= 2x(t) x(t 1)
(20)
Fig. 17 shows the velocity in body frame calculated derivative of the x position and
Equation 4.
estimated velocity x
body velocity x
0.5
0.4
0.3
velocity x [m/s]
0.2
0.1
0.1
0.2
0.3
0.4
0.5
10
20
30
40
50
60
70
time [sec]
20
80
40
20
20
40
60
10
20
30
40
50
60
70
80
90
time [sec]
d W
( vx (t) W vx (t))
dt
d
W
(t) = Kp (W vy (t) W vy (t)) + Kd (W vy (t) W vy (t))
dt
d
W
(t) = Kp gas (W vz (t) W vz (t)) + Kdgas (W vz (t) W vz (t))
dt
W
W
vx (t)
and
21
W
vy (t)
(21)
(22)
(23)
FIG. 19: This plot shows estimated velocity along z axis. Green, Red and Blue lines stand
for ACCZ from MK, body velocity and estimated velocity. ACCZ is sampled at 20 Hzand
estimated velocity is computed at the same rate. The body velocity is calculated based on
laser range finder height data and has a sample rate of 10 Hz. Note that body velocity is
smoothed.
I.
ROS implementation
It is easily achieved to integrate systems with ROS. All messages come into the ROS
core and are redistributed to nodes through the TCP/IP protocol. This feature allows
implementation of the software packages as modules, ROS stacks or packages. Fig. 20 shows
simple implementation based on the ROS. In this figure, dark gray boxes denotes the ROS
nodes which act as an individual process. The canonical scan matcher receives laser range
data and produces 2D positions using the ICP algorithm. It publishes /pose2D topic every
100ms and the data structures are shown in TABLE V and TABLE VI. A Miko Serial
node functions are as obtaining IMU data from the flight control board while a quadrotor
is flying and publishing /mikoImu topic every 50ms. These two topics can be recorded to
create a log file and be played using rosbag package. Finally, a complementary Filter node
22
Name
geometry msgs/Pose2D
Description
Data type
definition
Unit
Description
float64
float64
float64
theta
radian
10
0m
s(
W
IFI
)
<
=
0
>
1
2
?
3
@
;4
5
6
/7
8
9
:.A
-B
+
,C
*#
D
$
%
)"E
(F
!&
G
'K
JH
L
M
IN
~
O
}P
|m
Q
u
w
v{zyxtR
sln
ko
p
q
rS
T
jU
g
h
V
ia
b
d
ce
W
f_
`^]X
\Y
Z
[
Canonical
scan matcher
Miko Serial
m
co
an
/po
se
ko
mi
2D
Im
rosbag
play
rosbag
record
Complementary
Filter
rosbag
IMU data
kC
/m
Quadrotor
Platform
tim
ate
loc
ity
md
Es
e
dv
Position
Velocity
P controller
PID controller
J.
Yaw control
Yaw control of the quadrotor is relatively easier than pitch, roll and height control. Gyro
data is drifting overtime which implies the vehicle is going to change its heading. Therefore
23
Name
sensor msgs/mikoImu
Description
Data type
definition
Unit
Description
float64
pitchAngle
radian
float64
rollAngle
radian
float64
yawAngle
radian
float64
AccX
m/s2
float64
AccY
m/s2
float64
AccZ
m/s2
sensor msgs/mikoCmd
Description
Data type
definition
Unit
Description
int32
pitch
int32
roll
int32
yaw
int32
throttle
24
u(t) = Kp e(t) + Ki
e( )d + Kd
0
d
e(t)
dt
(24)
where e(t) =
20
Yaw(Deg)
10
10
20
30
10
20
30
40
50
60
70
80
time(sec)
FIG. 21: Yaw angle and yaw command output using PID controller.
K.
Altitude control
1.
u(t) = Kp e(t) + Ki
e( )d + Kd
0
d
e(t)
dt
(25)
where e(t) = z z and z denotes the desired position along z axis and z is the current
position. In addition, the height measurement is coupled with and . The projected
estimation of the height can be determined as the following equation.
z = cos cos z
(26)
FIG. 22: Height measurement data using PID control with a goal at 0.6 metre. The input
for the PID controller is the height measurement from laser hat and output is throttle
control command. The MK uses unsigned char data type to control quadrotor range
from 127. Note that average height measurement is within 5cm. Rarely does maxim
error goes up up to 10cm owing to ground effect and aerodynamics, but the quadrotor
quickly converges into the goal.
L.
Flight time is essential to the MAV research area. Many research platforms can only fly
for up to 10 minutes or less. However, the MK platform is able to fly up to 41 minutes
unofficially. The video demonstration can be found on vimeo. Detailed information can be
26
found in the article of MikroKopter wiki page. In order to estimate the flight time given
payload, we need to know total weight of a vehicle. In our case, the quadrotor weight is
around 1,040g including frames, laser range finder, Gumstix, XBee, laser hat and battery.
Therefore 260g is the thrust per motor.
current respectively. A Lipo battery, 2.2Ah, 4 cells, was used and Figure 27 shows 0.323
hour = 19.4 minutes flight time. This flight time is an ideal value that specifies the absolute
limit. These factors should be taken account.
The thrust characteristic was measured with a 100% loaded LiPo. The thrust decreases
slightly when the voltage drops in flight.
27
Turbulence
Losses due to regulations
Other losses (e.g. in cables, etc.)
For these reasons, a scale factor, 0.9, was multiplied. This parameter is chosen empirically
and should be changed as the battery efficiency goes down.
In conclusion, the estimated total flight time is 17.4 minutes and this value also can be
found in Figure 24. This graph is validated by comparison of our previous work as described
in Figure 25
Moreover, extra power consumption electric pars are used such as a laser range finder,
a Gumstix, a XBee module and a USB HUB. These parts also consume energy and reduce
the total flight time. The power consumption of the Gumstix is order of 2.5W 5W and
the laser range finder spends 2.5W. Hence, the extra power consumption could be said to be
less than 0.5A. Finally, from the calculation our quadrotor can fly up to 16.28 minutes,
0.9
2.2
6.8+0.5
M.
We logged Lipo batteries, (3cell, 2200mAh), to compensate the trust offset. Interestingly,
each battery showed a different discharge curve. (see Figure 26).
N.
28
<
=
0
>
1
2
?
3
@
;4
5
6
/7
8
9
:.A
-B
+
,C
*#
D
$
%
)"E
(F
!&
G
'K
JH
L
M
IN
~
O
}P
|m
Q
u
w
v{zyxtR
sln
ko
p
q
rS
T
jU
g
h
V
ia
b
d
ce
W
f_
`^]X
\Y
Z
[
FIG. 24: Flight time Versus payload characteristic graph. Total weight of the vehicle is
1,040g and this graph shows the flight time with 640g+238g (battery) payload. Therefore,
the payload is 162g. In addition, the hovering graph is appropriate for the indoor
application.
O.
Precision comparison
In this section, a variety of accuracy and precisions of state estimations are presented
when a quadrotor performs hovering or following given trajectory. As MAVs have fast
dynamics, filtering techniques such as complementary filter and Kalman Filter are often
used to estimate the state of the vehicle. Table IX shows a summary of precision from 5
different research groups.[2][5][1][3][4]
29
FIG. 25: Payload Versus Flight time table. This table was measured by us.
Mikrokopter Price(USD) Asecnding Tech Price(USD)
platform
MK Basicset
987.46
Pelican
7435.09
Transmitter
6CH
169.99
7CH
499.49
Receiver
7 CH
79.99
Total
1237.44
Ratio
7934.58
6.41
TABLE VIII: This table shows prices comparison between the MK Quadrotor set and the
similar level platform of Ascending technology, Pelican. These prices come from
MikroKopter , HobbyKing and Ascending Tech.
P.
In this section, we compare ground truth from the VICON system to our dynamic state
estimation. We estimate position x, y, z and velocity Vx , Vy . in addition, The MK estimates
pitch(), roll() and yaw() angles.
30
170
battery new1
battery new2
battery old
160
150
140
130
120
110
100
90
80
0
100
200
300
400
500
time (sec)
600
700
800
900
FIG. 26: Lipo battery discharge curves. X axis denotes time and y axis is a battery ADC
reading value.
1.
Figure 28 shows VICON coordinate and experiment configuration. Since the maximum
range of the laser range finder attached to the quadrotor is 4m, we need to put structures
within the 4m range. VICON system tracks infrared beam reflected by each makers and
provides position and orientation of the makers. Figure 29 shows the place where makers
on the quadrotor are attached. By computing error of Euclidean distance between two
markers,Equation 28 VICON system shows 5mm position error. We could find the distance
error increased after taking off because of frame vibration.
e = einitial
(28)
FIG. 28: This photo shows the VICON system coordinate and setup. This system is
equipped with 14 cameras to track markers and provides position, normal and orthogonal.
A x mark on the ground is the initial position of VICON system. The coordinate
transformation is required from VICON coordinate to MK coordinate as described in 2.
32
FIG. 29: Two makers are attached in order to calculate position error of VICON system.
FIG. 30: Position error between two markers. Note that the quadrotor starts taking off and
increasing position error due to frame vibration around 22sec. Mean is 0.0002 metre.
33
TABLE IX:
University MIT(RANGE)[2]
GRASP Lab.[5]
ETHZ(ASL)[1]
Year
2010
2011
2011
Precision
Hovering
Hovering
Hovering
(metre)
RMS X= 0.06
Std X= 0.0849
RMS X=0.12
(metre)
RMS Y= 0.06
Std Y= 0.0911
RMS Y=0.12
(metre)
RMS Z= 0.02
Std Z= 0.0554
RMS Z=0.01
Trajectory following
Trajectory following
(metre)
RMS X=0.07
Std X=0.0247
(metre)
RMS Y=0.07
Std Y=0.0323
(metre)
Std Z=0.007
Platform
Pelican
Pelican
Pelican
Sensor
Laser 40Hz
Laser 40Hz
1000Hz IMU
10Hz mono Vision
Fusion
University
Freiburg[3]
QUT
Year
2009
2006
2011
Precision
Hovering
(metre)
Std X=0.075368
(metre)
Std Y=0.080849
(metre)
a.
Error Z=0.1
Error Z=0.1
Std Z=0.031913
Position estimation Figure 31 and Figure 32 show ground truth and position, ve-
locity estimation.
II.
REFERENCES
34
FIG. 31: Blue is the ground truth and red is the laser position estimation. The x-axis is
time in second, the y-axis is position in unit of metre.
[1] Markus Achtelik, Michael Achtelik, Stephan Weiss, and Roland Siegwar. Onboard imu and
monocular vision based control for mavs in unknown in- and outdoor environments.
In
ICRA2011, 2011.
[2] A. Bachrach, A. de Winter, Ruijie He, G. Hemann, S. Prentice, and N. Roy. RANGE - robust
autonomous navigation in GPS-denied environments. In Robotics and Automation (ICRA),
2010 IEEE International Conference on, pages 1096 1097. MIT, may 2010.
[3] S. Grzonka, G. Grisetti, and W. Burgard. Towards a navigation system for autonomous indoor
flying. In Robotics and Automation, 2009. ICRA 09. IEEE International Conference on, pages
2878 2883, may 2009.
[4] Christopher Kemp. Visual Control of a Miniature Quad-Rotor Helicopter. PhD thesis, Univer-
35
FIG. 32: Blue is the ground truth and red is the velocity estimation from complementary
filter. The x-axis is time in second, the y-axis is velocity in unit of m/s.
sity of Cambridge, 2006.
[5] Shaojie Shen, Nathan Michael, and Vijay Kumar. Autonomous multi-floor indoor navigation
with a computationally constrained mav. In 2011 IEEE International Conference on Robotics
and Automation, 2011.
clear
all ;
d a t a=i m p o r t d a t a ( d a t a M a n u a l C o o r d i n a t e , , , 1 ) ;
3
sa m p ti m e = 0 . 0 5 ; % s e c o n d /50ms s a m p l i n g t i m e
5 W x=d a t a . d a t a ( : , 1 0 ) / 1 0 0 0 ;
% u n i t=m e t r e X p o s i t i o n
W y=d a t a . d a t a ( : , 1 1 ) / 1 0 0 0 ;
% u n i t=m e t r e Y p o s i t i o n
36
FIG. 33: Blue is ground truth and red is angle estimation by accumulating angular rates of
gyro sensor. The x-axis is time in second, the y-axis is the angle in unit of degree. This
data comes from the MK.
7 t i m e=d a t a . d a t a ( : , 1 5 ) sa m p t im e ; % u n i t=s e c o n d
numData=max ( d a t a . d a t a ( : , 1 5 ) ) +1;
% +1 b e c a u s e i n d e x
starts
from 0
9 Yaw=d a t a . d a t a ( : , 1 2 ) p i / 1 8 0 ; % r a d i a n
ACC X=d a t a . d a t a ( : , 4 ) ; % u n i t =1g = 9 . 8m/ s 2
11 ACC Y=d a t a . d a t a ( : , 5 ) ; % u n i t =1g = 9 . 8m/ s 2
MK PITCH=d a t a . d a t a ( : , 1 ) /10 p i / 1 8 0 ; % r a d i a n
13 MK ROLL=d a t a . d a t a ( : , 2 ) /10 p i / 1 8 0 ; % r a d i a n
s t i c k p i t c h=d a t a . d a t a ( : , 1 3 ) ;
15
s t i c k r o l l =d a t a . d a t a ( : , 1 4 ) ;
g =9.81; % unit 1g
17 %k = 0 . 2 5 ; % f i l t e r
k =0.5; % f i l t e r
19
gain
gain
d e s i r e d v x =0; % d e s i r e d
velocity
along X axis
u n i t=m/ s
d e s i r e d v y =0; % d e s i r e d
velocity
along X axis
u n i t=m/ s
21 Kp=30;
Kd=30;
23
25
27 %Down s a m p l i n g t h e x p o s i t i o n
%The s a m p l i n g
rate
of
the
data because
laser
it
s c a n matcher
oversampled .
is
100ms and t h e
37
log
data
is
29 %sampled a t 50ms r a t e .
31
h a l f s i z = numData / 2 ;
W x 100ms= z e r o s ( h a l f s i z , 1 ) ;
33 W y 100ms= z e r o s ( h a l f s i z , 1 ) ;
for
i =1 :
half siz
W x 100ms ( i ) = W x( i 2 1) ;
35
W y 100ms ( i ) = W y( i 2 1) ;
37 end
39 %Do i n t e r p o l a t i o n
to
c r e a t e smooth g r a p h .
W x =i n t e r p ( W x 100ms , 2 ) ;
41 W y =i n t e r p ( W y 100ms , 2 ) ;
43 %Array
size
align
w i t h numData !
%I t s n o t f a n c y but works .
45 W x mine= z e r o s ( numData , 1 ) ;
W y mine= z e r o s ( numData , 1 ) ;
47
for
i =1 : numData1
W x mine ( i ) = W x ( i ) ;
49
W y mine ( i ) = W y ( i ) ;
end
51
53 %W x mine ( 1 6 5 9 )=W x ( 1 6 5 8 ) ;
%W y mine ( 1 6 5 9 )=W y ( 1 6 5 8 ) ;
55
57 %W v x= d i f f (W x) . / d i f f ( t i m e )
59
%=================================================
61 % S t e p 1 .
Calculate
world frame
velocity
using
laser
position
data
%=================================================
63 W x v = z e r o s ( numData ,
1) ;
W y v = z e r o s ( numData ,
1) ;
65 %f o r n =2:numData
W x v= d i f f ( W x mine ) / sa mp ti m e ;
67
W y v= d i f f ( W y mine ) / sa mp ti m e ;
%
69
71 %end
73 %=================================================
% Step2 .
velocity
t o t h e body f r a m e u s n i g
75 % m a t r i x
%%=================================================
77
b x v = z e r o s ( numData ,
1) ;
79 b y v = z e r o s ( numData ,
1) ;
f o r n =1:numData1
b x v ( n )=c o s (Yaw( n ) ) W x v ( n )s i n (Yaw( n ) ) W y v ( n ) ;
81
85 %=================================================
% Step3 .
velocity
complementary
filter
87 %%=================================================
38
rotation
89 b v h a t x = z e r o s ( numData ,
1) ;
b v h a t y = z e r o s ( numData ,
1) ;
91 ddotX = z e r o s ( numData ,
1) ;
ddotY = z e r o s ( numData ,
1) ;
93 b v h a t x ( 1 ) =0;
b v h a t y ( 1 ) =0;
95
f o r n =1:numData1
ddotX ( n ) = (ACC X( n ) g s i n (MK PITCH( n ) ) ) / c o s (MK PITCH( n ) ) ;
97
99
b v h a t y ( n+1) = b v h a t y ( n ) + sa m p ti m e ( k ( b y v ( n )b v h a t y ( n ) )+ddotY ( n ) ) ;
101 end
103
%=================================================
105 % S t e p 5 .
Velocity P controller
%%=================================================
107 p i t c h c m d = z e r o s ( numData ,
r o l l c m d = z e r o s ( numData ,
109
1) ;
1) ;
e r r o r p i t c h = z e r o s ( numData ,
e r r o r r o l l = z e r o s ( numData ,
111
1) ;
1) ;
p o s t e r r o r p i t c h = z e r o s ( numData ,
p o s t e r r o r r o l l = z e r o s ( numData ,
1) ;
1) ;
113
e r r o r p i t c h ( 1 ) =0;
115
e r r o r r o l l ( 1 ) =0;
117
f o r n =2:numData
e r r o r p i t c h ( n )=d e s i r e d v x b v h a t x ( n ) ;
e r r o r r o l l ( n )=d e s i r e d v y b v h a t y ( n ) ;
119
121
%p i t c h c m d ( n ) = Kp e r r o r p i t c h ( n )+Kd ( e r r o r p i t c h ( n ) e r r o r p i t c h ( n1) ) ;
123
%r o l l c m d ( n ) = Kp e r r o r r o l l ( n )+Kd ( ( e r r o r r o l l ( n ) e r r o r r o l l ( n1) ) / sa mp ti m e ) ;
p i t c h c m d ( n ) = Kp e r r o r p i t c h ( n ) ;
r o l l c m d ( n ) = Kp e r r o r r o l l ( n ) ;
125 end
127 %=================================================
% Step6 .
Acceleration
integration
129 %%================================================
131 %f o r n =1:numData1
%
133 %end
135
v e l i n t x = cumsum ( d e t r e n d ( ddotX ) sa m p ti m e ) ;
137
p o s i n t x = cumsum ( d e t r e n d ( v e l i n t x ) s am p ti m e ) ;
139
141
143
%=================================================
145 % S t e p 4 .
Plotting
%%=================================================
39
147
%C r e a t e a m u l t i l i n e
149 %x l a b e l ( { f i r s t
%C r e a t e a b o l d
label
for
l i n e ; second
label
for
t h e xa x i s
using a multiline
cell
array :
contains a single
quote :
l i n e })
t h e ya x i s
that
151 %
%y l a b e l ( George s
153
155 %=================================================
% Fig1 .
laser
world
position
vs acc world
position
157 %%=================================================
figure (1) ;
159 p l o t ( time , W x mine , r ) ;
x l a b e l ( time
[ sec ] ,
f o n t s i z e , 1 2 ) , y l a b e l ( world
p o s i t i o n x [m] ,
f o n t s i z e ,12) ;
161 h o l d on ;
163 p l o t ( time , p o s i n t x , b ) ;
x l a b e l ( time
[ sec ] ,
f o n t s i z e , 1 2 ) , y l a b e l ( world
p o s i t i o n x from a c c x ,
f o n t s i z e ,12) ;
165
legend ( l a s e r
world
p o s i t i o n x , acc world
position x ) ;
167 %f i g u r e ( 2 ) ;
%p l o t ( time , W x v , b ) ;
169
171 %f i g u r e ( 2 ) ;
%p l o t ( time , b x v , m ) ;
173 %x l a b e l ( t i m e
[ sec ] ,
f o n t s i z e , 1 2 ) , y l a b e l ( body v e l o c i t y x [m/ s ] ,
f o n t s i z e ,12) ;
175 %f i g u r e ( 4 ) ;
%p l o t ( time , b y v ) ;
177
%=================================================
179 % F i g 2 . body v e l o c i t y
v s CF e s t i m a t e d
velocity
%%=================================================
181
figure (2) ;
183 p l o t ( time , b v h a t x , r ) ;
x l a b e l ( time
[ sec ] ,
f o n t s i z e , 1 2 ) , y l a b e l ( v e l o c i t y x [m/ s ] ,
f o n t s i z e ,12) ;
185
h o l d on ;
187 p l o t ( time , b x v , b ) ;
189 l e g e n d ( e s t i m a t e d
191
axis ([0
v e l o c i t y x , body v e l o c i t y x ) ;
t i m e ( end ) 0.6
0.6]) ;
%h o l d on ;
193 %p l o t ( time , v e l i n t x , g ) ;
195 %=================================================
% Fig3 .
pitch
input vs
stick
pitch
197 %%=================================================
199
figure (3) ;
p l o t ( time , p i t c h c m d , r ) ;
201
x l a b e l ( time
[ sec ] ,
f o n t s i z e , 1 2 ) , y l a b e l ( p i t c h cmd v s
h o l d on ;
203 p l o t ( time , s t i c k p i t c h , b ) ;
205 l e g e n d ( p i t c h cmd , s t i c k
pitch ) ;
40
stick
pitch ,
f o n t s i z e ,12) ;
207 %f i g u r e ( 7 ) ;
%p l o t ( time , r o l l c m d , r ) ;
209 %x l a b e l ( t i m e
[ sec ] ,
f o n t s i z e , 1 2 ) , y l a b e l ( r o l l cmd v s
stick
roll ,
f o n t s i z e ,12) ;
%h o l d on ;
211 %p l o t ( time , s t i c k r o l l , b ) ;
213 %f i g u r e ( 8 ) ;
%p l o t ( time , b v h a t y , r ) ;
215 %x l a b e l ( t i m e
[ sec ] ,
f o n t s i z e , 1 2 ) , y l a b e l ( v e l o c i t y y [m/ s ] ,
217 %h o l d on ;
%p l o t ( time , b y v , b ) ;
219
%l e g e n d ( e s t i m a t e d
v e l o c i t y y , body v e l o c i t y y ) ;
41
f o n t s i z e ,12) ;