@@ -165,47 +165,53 @@ void CudaPointcloudPreprocessorNode::twistCallback(
165
165
166
166
while (!twist_queue_.empty ()) {
167
167
// for replay rosbag
168
- if (
169
- rclcpp::Time (twist_queue_.front ().header .stamp ) > rclcpp::Time (twist_msg_ptr->header .stamp )) {
170
- twist_queue_.pop_front ();
171
- } else if ( // NOLINT
168
+ bool backwards_time_jump_detected =
169
+ rclcpp::Time (twist_queue_.front ().header .stamp ) > rclcpp::Time (twist_msg_ptr->header .stamp );
170
+ bool is_queue_longer_than_1s =
172
171
rclcpp::Time (twist_queue_.front ().header .stamp ) <
173
- rclcpp::Time (twist_msg_ptr->header .stamp ) - rclcpp::Duration::from_seconds (1.0 )) {
172
+ rclcpp::Time (twist_msg_ptr->header .stamp ) - rclcpp::Duration::from_seconds (1.0 );
173
+
174
+ if (backwards_time_jump_detected) {
175
+ twist_queue_.clear ();
176
+ } else if (is_queue_longer_than_1s) {
174
177
twist_queue_.pop_front ();
178
+ } else {
179
+ break ;
175
180
}
176
- break ;
177
181
}
178
182
}
179
183
180
184
void CudaPointcloudPreprocessorNode::imuCallback (
181
185
const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg)
182
186
{
183
- tf2::Transform tf2_imu_link_to_base_link{};
184
- getTransform (base_frame_, imu_msg->header .frame_id , &tf2_imu_link_to_base_link);
185
- geometry_msgs::msg::TransformStamped::SharedPtr tf_base2imu_ptr =
186
- std::make_shared<geometry_msgs::msg::TransformStamped>();
187
- tf_base2imu_ptr->transform .rotation = tf2::toMsg (tf2_imu_link_to_base_link.getRotation ());
187
+ tf2::Transform imu_to_base_tf2{};
188
+ getTransform (base_frame_, imu_msg->header .frame_id , &imu_to_base_tf2);
189
+ geometry_msgs::msg::TransformStamped imu_to_base_msg;
190
+ imu_to_base_msg.transform .rotation = tf2::toMsg (imu_to_base_tf2.getRotation ());
188
191
189
192
geometry_msgs::msg::Vector3Stamped angular_velocity;
190
193
angular_velocity.vector = imu_msg->angular_velocity ;
191
194
192
195
geometry_msgs::msg::Vector3Stamped transformed_angular_velocity;
193
- tf2::doTransform (angular_velocity, transformed_angular_velocity, *tf_base2imu_ptr );
196
+ tf2::doTransform (angular_velocity, transformed_angular_velocity, imu_to_base_msg );
194
197
transformed_angular_velocity.header = imu_msg->header ;
195
198
angular_velocity_queue_.push_back (transformed_angular_velocity);
196
199
197
200
while (!angular_velocity_queue_.empty ()) {
198
201
// for rosbag replay
199
- if (
200
- rclcpp::Time (angular_velocity_queue_.front ().header .stamp ) >
201
- rclcpp::Time (imu_msg->header .stamp )) {
202
- angular_velocity_queue_.pop_front ();
203
- } else if ( // NOLINT
202
+ bool backwards_time_jump_detected = rclcpp::Time (angular_velocity_queue_.front ().header .stamp ) >
203
+ rclcpp::Time (imu_msg->header .stamp );
204
+ bool is_queue_longer_than_1s =
204
205
rclcpp::Time (angular_velocity_queue_.front ().header .stamp ) <
205
- rclcpp::Time (imu_msg->header .stamp ) - rclcpp::Duration::from_seconds (1.0 )) {
206
+ rclcpp::Time (imu_msg->header .stamp ) - rclcpp::Duration::from_seconds (1.0 );
207
+
208
+ if (backwards_time_jump_detected) {
209
+ angular_velocity_queue_.clear ();
210
+ } else if (is_queue_longer_than_1s) {
206
211
angular_velocity_queue_.pop_front ();
212
+ } else {
213
+ break ;
207
214
}
208
- break ;
209
215
}
210
216
}
211
217
0 commit comments