summaryrefslogtreecommitdiff
path: root/src/main.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/main.cpp')
-rw-r--r--src/main.cpp10
1 files changed, 5 insertions, 5 deletions
diff --git a/src/main.cpp b/src/main.cpp
index 6cc4317..5d4ea71 100644
--- a/src/main.cpp
+++ b/src/main.cpp
@@ -31,7 +31,7 @@ using std::cerr;
#else /* ----- not USE_ROS ----- */
void
-covCallback(const message &msg, State &mu, const Quaternion<double> &q)
+covCallback(const message &msg, State &mu, const Quaterniond &q)
{
if (seencov && seenutm && seenpva) return;
seencov=true;
@@ -49,7 +49,7 @@ imgCallback(const message *msg)
}
void
-imuCallback(const message &msg, State &mu, const Quaternion<double> &q, const timestamp dt)
+imuCallback(const message &msg, State &mu, const Quaterniond &q, const timestamp dt)
{
if (!seenutm || !seenpva || !seencov || (dt.secs==0 && dt.nsecs==0)) return;
Vector3d acc(msg.linear_acceleration.y,msg.linear_acceleration.x,-msg.linear_acceleration.z);
@@ -63,7 +63,7 @@ imuCallback(const message &msg, State &mu, const Quaternion<double> &q, const ti
}
void
-pvaCallback(const message &msg, State &mu, Quaternion<double> &q)
+pvaCallback(const message &msg, State &mu, Quaterniond &q)
{
// Update quaternion
using Eigen::AngleAxisd;
@@ -76,7 +76,7 @@ pvaCallback(const message &msg, State &mu, Quaternion<double> &q)
R = AngleAxisd(yaw, Vector3d::UnitZ())
* AngleAxisd(roll, Vector3d::UnitX())
* AngleAxisd(pitch, Vector3d::UnitY());
- q = Quaternion<double>(R);
+ q = Quaterniond(R);
// Set body velocity
if (!seenpva || !seencov || !seenutm) {
@@ -217,7 +217,7 @@ int
main(int argc, char **argv)
{
State mu;
- Quaternion<double> qbw;
+ Quaterniond qbw;
// bias in FRD coordinates
Vector3d acc_bias;
acc_bias << -0.03713532, 1.125*0.01465135, -1*-0.00709229;