#ifndef main_INC #define main_INC #include #include #include #include #include #include #include #include "types.h" #include "body.h" #include "camera.h" #include "ourerr.hpp" #include "state.h" #include "vision.h" //#define ROS_PUBLISH /* Uncomment to publish ROS node */ //#define ROS_SUBSCRIBE /* Uncomment to subscribe to ROS */ #define ANGBIASX 0.001107 #define ANGBIASY 0.008842 #define ANGBIASZ -0.001122 #define ACCBIASX -0.018000 #define ACCBIASY 0.012100 #define ACCBIASZ -0.010000 //#define ANGBIASX 1.019*-2.795871394666666222e-03 /* */ //#define ANGBIASY .980*6.984255690000021506e-03 //#define ANGBIASZ 0.96*1.418145565750002614e-03 //#define ACCBIASX 0.95*-0.03713532 //#define ACCBIASY 0.65*0.01465135 //#define ACCBIASZ -1*-0.00709229 //#define ACCBIASX 0.99*-0.03713532 //#define ACCBIASY 0.2*0.01465135 //#define ACCBIASZ -1*-0.00709229 //#define ACCBIASX -0.03713532 //#define ACCBIASY 0.01465135 //#define ACCBIASZ -1*-0.00709229 //#define CANOECENTER 0.82 /* center of gravity of canoe */ #define CANOECENTER 0.62 /* center of gravity of canoe */ #define CANOEHEIGHT -0.46 //#define CANOEHEIGHT -0.75 #define DOWNSAMPLE 1 /* */ #define HEIGHT_FROM_ATTITUDE /* use the attitude to measure the height */ #define MEASURE_HEIGHT #if ROS_PUBLISH #include #include #endif /* ----- ROS_PUBLISH ----- */ using Eigen::Matrix; using Eigen::Matrix3d; using Eigen::Matrix4d; using Eigen::Quaterniond; using Eigen::Vector3d; double aboveWater(const Quaterniond &q); int parseLine(char *line, message *msg); timestamp update_dt(const timestamp t, timestamp *t_old); #if STATESIZE==13 void covCallback(const message &msg, State &mu, const attitude_t &att); void imgCallback(message &msg, State &mu, Camera &cam); void imuCallback(const message &msg, State &mu, const timestamp dt); void utmCallback(const message &msg, State &mu); #else void covCallback(const message &msg, State &mu, const Quaterniond &q); void imgCallback(message &msg, State &mu, Camera &cam, const Quaterniond &q); void imuCallback(const message &msg, State &mu, const Quaterniond &q, const timestamp dt); void utmCallback(const message &msg, State &mu, const Quaterniond &q); #endif void pvaCallback(const message &msg, Matrix &X, Quaterniond &q); Matrix attitude_jacobian(double roll, double pitch, double yaw); #endif /* ----- #ifndef main_INC ----- */