Skip to content

Commit 660e712

Browse files
authored
Merge pull request #6 from ongdexter/feature/timestamp
Added prediction with latest imu timestamp and added timestamp to odo…
2 parents fba41b2 + ee52a19 commit 660e712

File tree

5 files changed

+26
-2
lines changed

5 files changed

+26
-2
lines changed

glider/include/glider/core/odometry.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ class Odometry
3535
Odometry(gtsam::Values& val, gtsam::Key key, double scale, int64_t timestamp, bool init = true);
3636
Odometry(gtsam::NavState& ns, bool init = true);
3737
Odometry(gtsam::NavState& ns, Eigen::Vector3d& gyro, bool init = true);
38+
Odometry(gtsam::NavState& ns, Eigen::Vector3d& gyro, int64_t timestamp, bool init = true);
3839

3940
template<typename T>
4041
T getPose() const;

glider/include/ros/glider_node.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,5 +76,7 @@ class GliderNode : public rclcpp::Node
7676

7777
// tracker
7878
Glider::State current_state_;
79+
80+
int64_t latest_imu_timestamp_;
7981
};
8082
}

glider/ros/glider_node.cpp

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,8 @@ GliderNode::GliderNode(const rclcpp::NodeOptions& options) : rclcpp::Node("glide
6868

6969
current_state_ = Glider::State::Uninitialized();
7070

71+
latest_imu_timestamp_ = 0;
72+
7173
if (use_odom)
7274
{
7375
auto odom_sub_options = rclcpp::SubscriptionOptions();
@@ -111,7 +113,11 @@ void GliderNode::interpolationCallback()
111113
{
112114
if (!initialized_ || !current_state_.isInitialized()) return;
113115

114-
int64_t timestamp = getTime(this->now());
116+
if (latest_imu_timestamp_ <= 0)
117+
{
118+
return;
119+
}
120+
int64_t timestamp = latest_imu_timestamp_;
115121
Glider::Odometry odom = glider_->interpolate(timestamp);
116122

117123
if (!odom.isInitialized()) return;
@@ -149,6 +155,8 @@ void GliderNode::imuCallback(const sensor_msgs::msg::Imu::ConstSharedPtr msg)
149155
int64_t timestamp = getTime(msg->header.stamp);
150156

151157
glider_->addIMU(timestamp, accel, gyro, orient);
158+
159+
latest_imu_timestamp_ = timestamp;
152160
}
153161

154162
void GliderNode::magCallback(const sensor_msgs::msg::MagneticField::ConstSharedPtr msg)

glider/src/factor_manager.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -275,7 +275,7 @@ Odometry FactorManager::predict(int64_t timestamp)
275275
}
276276
gtsam::NavState result = pim_copy_->predict(current_state_.getNavState(), bias_);
277277

278-
Odometry ret(result, gyro_);
278+
Odometry ret(result, gyro_, timestamp);
279279

280280
return ret;
281281
}

glider/src/odometry.cpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,19 @@ Odometry::Odometry(gtsam::NavState& ns, Eigen::Vector3d& gyro, bool init)
5050
initialized_ = init;
5151
}
5252

53+
Odometry::Odometry(gtsam::NavState& ns, Eigen::Vector3d& gyro, int64_t timestamp, bool init)
54+
{
55+
position_ = ns.position();
56+
orientation_ = ns.attitude();
57+
pose_ = gtsam::Pose3(orientation_, position_);
58+
velocity_ = ns.v();
59+
altitude_ = position_.z();
60+
heading_ = orientation_.yaw();
61+
gyro_ = gyro;
62+
initialized_ = init;
63+
timestamp_ = timestamp;
64+
}
65+
5366
Odometry Odometry::Uninitialized()
5467
{
5568
Odometry odom;

0 commit comments

Comments
 (0)