Skyward boardcore
Loading...
Searching...
No Matches
StateInitializer.h
Go to the documentation of this file.
1/* Copyright (c) 2022 Skyward Experimental Rocketry
2 * Authors: Marco Cella, Alberto Nidasio
3 *
4 * Permission is hereby granted, free of charge, to any person obtaining a copy
5 * of this software and associated documentation files (the "Software"), to deal
6 * in the Software without restriction, including without limitation the rights
7 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
8 * copies of the Software, and to permit persons to whom the Software is
9 * furnished to do so, subject to the following conditions:
10 *
11 * The above copyright notice and this permission notice shall be included in
12 * all copies or substantial portions of the Software.
13 *
14 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
15 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
16 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
17 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
18 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
19 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
20 * THE SOFTWARE.
21 */
22
23#pragma once
24
28
29#include <Eigen/Dense>
30
31#include "NAS.h"
32
33namespace Boardcore
34{
35
45{
46public:
55
66 void eCompass(const Eigen::Vector3f& acc, const Eigen::Vector3f& mag);
67
79 void triad(const Eigen::Vector3f& acc, const Eigen::Vector3f& mag,
80 const Eigen::Vector3f& nedMag);
81
82 Eigen::Matrix<float, 13, 1> getInitX();
83
84private:
85 Eigen::Matrix<float, 13, 1> x_init;
86
87 PrintLogger log = Logging::getLogger("stateinitializer");
88};
89} // namespace Boardcore
static PrintLogger getLogger(const string &name)
Utility used to initialize the extended kalman filter's state.
void triad(const Eigen::Vector3f &acc, const Eigen::Vector3f &mag, const Eigen::Vector3f &nedMag)
Triad algorithm to estimate the attitude before the liftoff.
void eCompass(const Eigen::Vector3f &acc, const Eigen::Vector3f &mag)
Ecompass algorithm to estimate the attitude before the liftoff.
Eigen::Matrix< float, 13, 1 > getInitX()
StateInitializer()
Initialize the state of the Extended Kalman Filter.
Driver for the VN100S IMU.