Functions | |
def | quaternion_to_eulerypr |
def | uniform_resample |
Variables | |
int | N = 10 |
tuple | quats = (np.empty(N), np.empty(N), np.empty(N), np.empty(N)) |
tuple | t1 = np.linspace(0, 10, 10) |
tuple | t2 = np.linspace(0.1,12.5,20) |
tuple | x1 = np.sin(t1) |
tuple | x2 = np.cos(t2) |
def starmac_tools.timeseries.quaternion_to_eulerypr | ( | quat_series | ) |
Convert a series of quaternions to the equivalent Euler angle (yaw-pitch-roll) representation. Input: tuple of 1-d vectors (w, x, y, z) Output: tuple of 1-d vectors (yaw, pitch, roll) in radians
Definition at line 77 of file timeseries.py.
def starmac_tools.timeseries.uniform_resample | ( | inputs, | |
dt | |||
) |
In general time series data t, x will have non-uniform sampling interval and further in a large system there may be several sources of data with different sampling times. This function takes a tuple of tuples as input. Each of the inner tuples must contain as its first element a 'kind' argument (per the kind argument of scipy.interpolate.interp1d; you probably want to use either 'linear' or 'zero'). The second element of the tuple is a numpy array of input sample times, and as its remaining elements, 1-D arrays of the data to be resampled. The second argument, dt, is the desired output sample period. The output will first a vector of the new sample times, and second, a tuple of tuples, the outer tuple of which is the same length as the input one. Each inner tuple will have the data, resampled as requested.
Definition at line 44 of file timeseries.py.
int starmac_tools::timeseries::N = 10 |
Definition at line 101 of file timeseries.py.
tuple starmac_tools::timeseries::quats = (np.empty(N), np.empty(N), np.empty(N), np.empty(N)) |
Definition at line 102 of file timeseries.py.
tuple starmac_tools::timeseries::t1 = np.linspace(0, 10, 10) |
Definition at line 95 of file timeseries.py.
tuple starmac_tools::timeseries::t2 = np.linspace(0.1,12.5,20) |
Definition at line 97 of file timeseries.py.
tuple starmac_tools::timeseries::x1 = np.sin(t1) |
Definition at line 96 of file timeseries.py.
tuple starmac_tools::timeseries::x2 = np.cos(t2) |
Definition at line 98 of file timeseries.py.