Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add option --start-offset #169

Merged
merged 1 commit into from
Sep 30, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions src/run_slam_offline.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ void tracking(const std::shared_ptr<stella_vslam_ros::system>& slam_ros,
const std::string& color_topic,
const std::string& depth_topic,
const std::string& bag_storage_id,
const double start_offset,
const bool no_sleep,
const std::string& viewer_string) {
auto& SLAM = slam_ros->slam_;
Expand Down Expand Up @@ -108,6 +109,12 @@ void tracking(const std::shared_ptr<stella_vslam_ros::system>& slam_ros,
storage_options.storage_id = bag_storage_id;
rosbag2_cpp::Reader reader;
reader.open(storage_options);
auto metadata = reader.get_metadata();
auto starting_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
metadata.starting_time.time_since_epoch())
.count()
+ start_offset * 1e9;
reader.seek(starting_time);
rclcpp::Serialization<sensor_msgs::msg::Image> serialization;
std::queue<std::shared_ptr<sensor_msgs::msg::Image>> que;
double track_time;
Expand Down Expand Up @@ -290,6 +297,7 @@ int main(int argc, char* argv[]) {
auto color_topic = op.add<popl::Value<std::string>>("", "color", "color image topic name for RGBD", "camera/color/image_raw");
auto depth_topic = op.add<popl::Value<std::string>>("", "depth", "depth image topic name for RGBD", "camera/depth/image_raw");
auto bag_storage_id = op.add<popl::Value<std::string>>("", "storage-id", "rosbag2 storage id (default: sqlite3)", "sqlite3");
auto start_offset = op.add<popl::Value<double>>("", "start-offset", "start offset", 0.0);
auto vocab_file_path = op.add<popl::Value<std::string>>("v", "vocab", "vocabulary file path");
auto setting_file_path = op.add<popl::Value<std::string>>("c", "config", "setting file path");
auto mask_img_path = op.add<popl::Value<std::string>>("", "mask", "mask image path", "");
Expand Down Expand Up @@ -430,6 +438,7 @@ int main(int argc, char* argv[]) {
color_topic->value(),
depth_topic->value(),
bag_storage_id->value(),
start_offset->value(),
no_sleep->is_set(),
viewer_string);

Expand Down