#include "nav_msgs/Odometry.h"#include "grizzly_msgs/Drive.h"#include <grizzly_msgs/eigen.h>#include "sensor_msgs/JointState.h"#include <Eigen/Core>#include <Eigen/Dense>

Go to the source code of this file.
Classes | |
| class | DeadReckoning |
Variables | |
| const Eigen::MatrixXd | ODOM_POSE_COVAR_MOTION |
| const Eigen::MatrixXd | ODOM_POSE_COVAR_NOMOVE |
| const Eigen::MatrixXd | ODOM_TWIST_COVAR_MOTION |
| const Eigen::MatrixXd | ODOM_TWIST_COVAR_NOMOVE |
| const Eigen::MatrixXd ODOM_POSE_COVAR_MOTION |
(Eigen::MatrixXd(6, 6) << 1e-3, 0, 0, 0, 0, 0, 0, 1e-1, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 0.174).finished()
Definition at line 34 of file dead_reckoning.h.
| const Eigen::MatrixXd ODOM_POSE_COVAR_NOMOVE |
(Eigen::MatrixXd(6, 6) << 1e-9, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 1e-9).finished()
Definition at line 42 of file dead_reckoning.h.
| const Eigen::MatrixXd ODOM_TWIST_COVAR_MOTION |
(Eigen::MatrixXd(6, 6) << 1e-3, 0, 0, 0, 0, 0, 0, 1e-1, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 0.174).finished()
Definition at line 50 of file dead_reckoning.h.
| const Eigen::MatrixXd ODOM_TWIST_COVAR_NOMOVE |
(Eigen::MatrixXd(6, 6) << 1e-9, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 1e6, 0, 0, 0, 0, 0, 0, 1e-9).finished()
Definition at line 58 of file dead_reckoning.h.