#include <combined_nav_state.h>
◆ CombinedNavState() [1/3]
localization_common::CombinedNavState::CombinedNavState |
( |
const gtsam::NavState & |
nav_state, |
|
|
const gtsam::imuBias::ConstantBias & |
bias, |
|
|
const Time |
timestamp |
|
) |
| |
◆ CombinedNavState() [2/3]
localization_common::CombinedNavState::CombinedNavState |
( |
const gtsam::Pose3 & |
pose, |
|
|
const gtsam::Velocity3 & |
velocity, |
|
|
const gtsam::imuBias::ConstantBias & |
bias, |
|
|
const Time |
timestamp |
|
) |
| |
◆ CombinedNavState() [3/3]
localization_common::CombinedNavState::CombinedNavState |
( |
| ) |
|
|
default |
◆ bias()
const gtsam::imuBias::ConstantBias& localization_common::CombinedNavState::bias |
( |
| ) |
const |
|
inline |
◆ nav_state()
const gtsam::NavState& localization_common::CombinedNavState::nav_state |
( |
| ) |
const |
|
inline |
◆ pose()
gtsam::Pose3 localization_common::CombinedNavState::pose |
( |
| ) |
const |
|
inline |
◆ timestamp()
Time localization_common::CombinedNavState::timestamp |
( |
| ) |
const |
|
inline |
◆ velocity()
const gtsam::Velocity3& localization_common::CombinedNavState::velocity |
( |
| ) |
const |
|
inline |
◆ boost::serialization::access
friend class boost::serialization::access |
|
friend |
The documentation for this class was generated from the following files: