In [1]:
%load_ext autoreload
%autoreload 2
%pylab inline
In [2]:
import px4tools.ulog
import pandas
import os
import pickle
import scipy.interpolate
import px4tools.version
rcParams['lines.linewidth'] = 2
In [3]:
pandas.__version__
Out[3]:
In [4]:
px4tools.version.git_revision
Out[4]:
In [5]:
d_gyro = px4tools.ulog.cached_log_processing(
log='/home/jgoppert/logs/01-18-17-gyro-bias.ulg',
msg_filter='sensor_gyro',
processing_func=lambda x: x['sensor_gyro_0'].resample('1 s').agg('mean'),
save_path='./logs/01-18-17-gyro-bias-sensor_gyro_0.pkl',
force_processing=False)
d_comb = px4tools.ulog.cached_log_processing(
log='/home/jgoppert/logs/01-18-17-gyro-bias.ulg',
msg_filter='',
processing_func=lambda x: x,
save_path='/home/jgoppert/logs/01-18-17-gyro-bias-comb.pkl',
force_processing=False)
d_gyro_bias = d_comb.concat(dt=1).ffill().bfill()['2 min': '40 m']
In [6]:
d_gyro2 = px4tools.ulog.cached_log_processing(
log='/home/jgoppert/logs/01-18-17-gyro-bias2.ulg',
msg_filter='sensor_gyro',
processing_func=lambda x: x['sensor_gyro_0'].resample('1 s').agg('mean'),
save_path='./logs/01-18-17-gyro-bias2-sensor_gyro_0.pkl',
force_processing=False)
d_comb2 = px4tools.ulog.cached_log_processing(
log='/home/jgoppert/logs/01-18-17-gyro-bias2.ulg',
msg_filter='',
processing_func=lambda x: x,
save_path='/home/jgoppert/logs/01-18-17-gyro-bias2-comb.pkl',
force_processing=False)
d_gyro2_bias = d_comb2.concat(dt=1).ffill().bfill()['2 min': '40 m']
In [7]:
def plot_gyro_bias(d):
for i, axis, color in zip([7, 8, 9], ['x', 'y', 'z'], ['r', 'g', 'b']):
est = getattr(d, 't_estimator_status_0__f_states_{:d}_'.format(i))
est.plot(label=axis + ' est', style=color + '--')
true = getattr(d, 't_sensor_gyro_0__f_{:s}'.format(axis))
true.plot(label=axis, style=color, alpha=0.5)
plt.gcf().autofmt_xdate()
legend(ncol=3, loc='best')
plt.ylabel('rad/s')
plt.title('gyro bias')
def plot_gyro_bias_error(d):
(d.t_estimator_status_0__f_states_7_ - d.t_sensor_gyro_0__f_x).plot(label='x', style='r')
(d.t_estimator_status_0__f_states_8_ - d.t_sensor_gyro_0__f_y).plot(label='y', style='g')
(d.t_estimator_status_0__f_states_9_ - d.t_sensor_gyro_0__f_z).plot(label='z', style='b')
plt.gcf().autofmt_xdate()
legend(ncol=3, loc='best')
plt.title('gyro bias error')
In [8]:
def plot_accel_bias(d):
for i, axis, color in zip([10, 11, 12], ['x', 'y', 'z'], ['r', 'g', 'b']):
est = getattr(d, 't_estimator_status_0__f_states_{:d}_'.format(i))
est.plot(label=axis + ' est', style=color + '--')
true = getattr(d, 't_sensor_accel_0__f_{:s}'.format(axis))
if axis == 'z':
true = pandas.Series(true + 9.8)
true.plot(label=axis, style=color, alpha=0.5)
plt.ylabel('m/s^2')
plt.gcf().autofmt_xdate()
legend(ncol=3, loc='best')
plt.title('accel bias')
def plot_accel_bias_error(d):
(d.t_estimator_status_0__f_states_10_ - d.t_sensor_accel_0__f_x).plot(label='x', style='r')
(d.t_estimator_status_0__f_states_11_ - d.t_sensor_accel_0__f_y).plot(label='y', style='g')
(d.t_estimator_status_0__f_states_12_ - d.t_sensor_accel_0__f_z - 9.8).plot(label='z', style='b')
In [9]:
figure()
plot_gyro_bias(d_gyro_bias)
gca().set_ylim(-0.01, 0.04)
figure()
plot_gyro_bias_error(d_gyro_bias)
gca().set_ylim(-0.02, 0.02)
In [10]:
figure()
plot_gyro_bias(d_gyro2_bias)
gca().set_ylim(-0.1, 0.1)
figure()
plot_gyro_bias_error(d_gyro2_bias)
gca().set_ylim(-0.1, 0.1)
In [11]:
plot_accel_bias(d_gyro2_bias)
#gca().set_ylim(-1, 0.4)
In [12]:
plot_accel_bias(d_gyro_bias)
#gca().set_ylim(-1, 0.4)
In [13]:
est_status = d_comb['estimator_status_0']
In [14]:
def plot_rotation_std_dev(d):
for i in range(3):
data = getattr(d, 't_estimator_status_0__f_covariances_{:d}_'.format(i))
np.rad2deg(sqrt(data)).plot()
plt.ylabel('deg')
plt.title('rotation std. dev.')
plt.grid()
plot_rotation_std_dev(est_status[:'2 m'])
In [15]:
def plot_velocity_std_dev(d):
for i in range(3, 6):
data = getattr(d, 't_estimator_status_0__f_covariances_{:d}_'.format(i))
sqrt(data).plot()
plt.ylabel('m/s')
plt.title('velocity std. dev.')
plt.grid()
plot_velocity_std_dev(est_status[:'2 m'])
In [16]:
px4tools.IEKF_STATES
Out[16]:
In [17]:
def plot_gyro_bias_std_dev(d):
for i in range(6, 9):
data = getattr(d, 't_estimator_status_0__f_covariances_{:d}_'.format(i))
np.rad2deg(sqrt(data)).plot()
plt.ylabel('deg')
plt.title('gyro bias std. dev.')
plt.grid()
plot_gyro_bias_std_dev(est_status[:'2 m'])
In [18]:
def plot_accel_bias_std_dev(d):
for i in range(9, 12):
data = getattr(d, 't_estimator_status_0__f_covariances_{:d}_'.format(i))
sqrt(data).plot()
plt.ylabel('m/s^2')
plt.title('accel bias std. dev.')
plt.grid()
plot_accel_bias_std_dev(est_status[:'2 m'])
In [19]:
def plot_pos_std_dev(d):
for i in range(12, 15):
data = getattr(d, 't_estimator_status_0__f_covariances_{:d}_'.format(i))
sqrt(data).plot()
plt.ylabel('m')
plt.title('pos std. dev.')
plt.grid()
plot_pos_std_dev(est_status[:'2 m'])
In [20]:
def plot_pos_std_dev(d):
for i in range(12, 15):
data = getattr(d, 't_estimator_status_0__f_covariances_{:d}_'.format(i))
sqrt(data).plot()
plt.ylabel('m')
plt.title('pos std. dev.')
plt.grid()
plot_pos_std_dev(est_status[:'2 m'])
In [21]:
px4tools.ulog.IEKF_ERROR_STATES
Out[21]:
In [22]:
est_status.t_estimator_status_0__f_covariances_6_[:'2 m'].plot()
est_status.t_estimator_status_0__f_covariances_7_[:'2 m'].plot()
est_status.t_estimator_status_0__f_covariances_8_[:'2 m'].plot()
In [23]:
est_status.t_estimator_status_0__f_covariances_9_[:'2 m'].plot()
est_status.t_estimator_status_0__f_covariances_10_[:'2 m'].plot()
est_status.t_estimator_status_0__f_covariances_11_[:'2 m'].plot()
In [24]:
est_status.t_estimator_status_0__f_covariances_12_[:'2 m'].plot()
est_status.t_estimator_status_0__f_covariances_13_[:'2 m'].plot()
est_status.t_estimator_status_0__f_covariances_14_[:'2 m'].plot()
In [25]:
est_status.t_estimator_status_0__f_covariances_15_[:'2 m'].plot()
est_status.t_estimator_status_0__f_covariances_16_[:'2 m'].plot()
est_status.t_estimator_status_0__f_covariances_17_[:'2 m'].plot()