-
Notifications
You must be signed in to change notification settings - Fork 2
/
readData.m
147 lines (117 loc) · 4.37 KB
/
readData.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
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
%read in ROS bag data to workspace
%bagID = "combined/combined3";
bag = rosbag('./bagFile_data/criticValueTest.bag');
position = select(bag,'Topic','/mocap/rigid_bodies/RigidBody_01/pose');
opti_msgs = readMessages(position,'DataFormat','struct');
x = cellfun(@(m) double(m.Pose.Position.X),opti_msgs);
y = cellfun(@(m) double(m.Pose.Position.Y),opti_msgs);
z = cellfun(@(m) double(m.Pose.Position.Z),opti_msgs);
time_sec = cellfun(@(m) double(m.Header.Stamp.Sec),opti_msgs);
time_nsec = cellfun(@(m) double(m.Header.Stamp.Nsec),opti_msgs);
pose_time = time_sec + time_nsec*10^(-9);
pose_bias = pose_time(1);
pose_time = pose_time - pose_bias; %extra .01 for optitrack delay
odom = select(bag,'Topic','/qcar/odometry');
msgs = readMessages(odom,'DataFormat','struct');
raw_odom = cellfun(@(m) double(m.Vector.X),msgs);
time_sec = cellfun(@(m) double(m.Header.Stamp.Sec),msgs);
time_nsec = cellfun(@(m) double(m.Header.Stamp.Nsec),msgs);
odom_time = time_sec + time_nsec*10^(-9);
odom_time = odom_time - pose_bias;
accel = select(bag,'Topic','/qcar/accelerometer');
msgs = readMessages(accel,'DataFormat','struct');
raw_accel = cellfun(@(m) double(m.Vector.X),msgs);
y_acc_r = cellfun(@(m) double(m.Vector.Y),msgs);
z_acc_r = cellfun(@(m) double(m.Vector.Z),msgs);
time_sec = cellfun(@(m) double(m.Header.Stamp.Sec),msgs);
time_nsec = cellfun(@(m) double(m.Header.Stamp.Nsec),msgs);
accel_time = time_sec + time_nsec*10^(-9);
accel_time = accel_time - pose_bias;
command = select(bag,'Topic','/qcar/user_command');
msgs = readMessages(command,'DataFormat','struct');
long_command= cellfun(@(m) double(m.Vector.X),msgs);
time_sec = cellfun(@(m) double(m.Header.Stamp.Sec),msgs);
time_nsec = cellfun(@(m) double(m.Header.Stamp.Nsec),msgs);
command_time = time_sec + time_nsec*10^(-9);
command_time = command_time - pose_bias;
critic_topic = select(bag,'Topic','/critic_value');
msgs = readMessages(critic_topic,'DataFormat','struct');
long_act= cellfun(@(m) double(m.Vector.X),msgs);
steer_act= cellfun(@(m) double(m.Vector.Y),msgs);
critic_value= cellfun(@(m) double(m.Vector.Z),msgs);
time_sec = cellfun(@(m) double(m.Header.Stamp.Sec),msgs);
time_nsec = cellfun(@(m) double(m.Header.Stamp.Nsec),msgs);
crit_time = time_sec + time_nsec*10^(-9);
crit_time = crit_time - pose_bias;
%how far behind the velocity is behind accelerometer
opti_lag = .01
pose_time = pose_time -opti_lag
%% calculate velocity
x_vel = zeros(length(x)-1,1);
y_vel = zeros(length(y)-1,1);
z_vel = zeros(length(z)-1,1);
speed_time = zeros(length(pose_time)-1,1);
Ts = 1/100;
for i=1:length(x)-1
dT = pose_time(i+1)-pose_time(i);
x_vel(i) = (x(i+1)-x(i))/dT;
y_vel(i) = (y(i+1)-y(i))/dT;
z_vel(i) = (z(i+1)-z(i))/dT;
speed_time(i) = pose_time(i) + dT/2;
end
speed = (x_vel.^2 + y_vel.^2 + z_vel.^2).^(1/2);
x_vel_samp = zeros(length(x)-1,1);
y_vel_samp = zeros(length(y)-1,1);
z_vel_samp = zeros(length(z)-1,1);
speed_time_samp = zeros(length(pose_time)-1,1);
period = .2;
disc_time = .2;
prev_index = 1;
arr_index = 1
for i=1:length(x)-1
if(pose_time(i+1) > disc_time)
disc_time = disc_time + period;
x_vel_samp(arr_index) = (x(i+1)-x(prev_index))/.2;
y_vel_samp(arr_index) = (y(i+1)-y(prev_index))/.2;
z_vel_samp(arr_index) = (z(i+1)-z(prev_index))/.2;
speed_time_samp(arr_index) = pose_time(i+1);
prev_index = i;
arr_index = arr_index + 1;
end
end
speed_samp = (x_vel_samp.^2 + y_vel_samp.^2 + z_vel_samp.^2).^(1/2);
speed_samp = speed_samp(1:find(speed_samp,1,'last'))
speed_time_samp = speed_time_samp(1:find(speed_time_samp,1,'last'))
close all
figure(1)
yyaxis left
plot(speed_time_samp,speed_samp)
ylabel('5Hz Sampled Speed State [m/s]');
ylim([-.5 2])
yyaxis right
plot(command_time,long_command)
ylabel('Throttle Command []');
%ylim([-40 40])
xlabel('Time [s]')
title("Throttle Command and Sampled State vs. Time")
figure(2)
yyaxis left
plot(speed_time_samp,abs(speed_samp))
yline(.7)
ylabel('5Hz Sampled Speed State [m/s]');
ylim([0 2.5])
yyaxis right
plot(crit_time,critic_value,"--")
ylabel('Critic Value');
ylim([-40 40])
xlabel('Time [s]')
title("Critic Model Value Output at 5Hz Sampled State")
figure(3)
%plot(speed_time,lowpass(speed,5,100))
plot(speed_time,speed)
hold on
plot(speed_time_samp,speed_samp)
title("Differing Sampling Time Speed vs. Time")
xlabel("Time [s]")
ylabel("Speed [m/s]")
legend(["Velocity Sampled at 100Hz", "Velocity Sampled at 5 Hz"])