Skip to content

Instantly share code, notes, and snippets.

# The MIT License (MIT)
#
# Copyright (c) 2023 ymd-stella
#
# Permission is hereby granted, free of charge, to any person obtaining a copy
# of this software and associated documentation files (the "Software"), to deal
# in the Software without restriction, including without limitation the rights
# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
# copies of the Software, and to permit persons to whom the Software is
# furnished to do so, subject to the following conditions:
@ymd-stella
ymd-stella / save_tum_rgbd.py
Last active December 25, 2022 04:37
Saves color and depth images in TUM RGB-D format. Tested on ROS melodic.
#!/usr/bin/python
import cv2
import cv_bridge
import datetime
import message_filters
import numpy as np
import os
import rospy
import sys
import sensor_msgs
#!/usr/bin/env python3
"""
python3 tum_to_bag.py --src test.tum --dst map.db
"""
import argparse
import math
import numpy as np
from scipy.spatial.transform import Rotation as R
from rosbags.rosbag1 import Writer
#!/usr/bin/python
import argparse
import rosbag
import tf_bag
import tf2_py
parser = argparse.ArgumentParser()
parser.add_argument("filepath", type=str)
args = parser.parse_args()
@ymd-stella
ymd-stella / read_poses_from_db_and_convert_to_bag.py
Last active November 23, 2022 08:32
Reads keyframe poses from map data in sqlite3 format and export it to a bag file..
#!/usr/bin/env python3
"""
python3 read_poses_from_db_and_print_tum.py map.db
"""
import argparse
import sqlite3
import struct
import math
import numpy as np
from scipy.spatial.transform import Rotation as R
#!/usr/bin/env python3
"""
You can plot with the following commands
```
python3 read_poses_from_db_and_print_tum.py map.db > pose.tum
evo_traj tum pose.tum -p --save_plot plot.pdf --plot_mode xz
```
"""
import argparse
@ymd-stella
ymd-stella / read_poses_from_db.py
Last active August 21, 2022 08:27
Reads keyframe poses from map data in sqlite3 format.
#!/usr/bin/env python3
import argparse
import sqlite3
import struct
import numpy as np
def main():
parser = argparse.ArgumentParser()
parser.add_argument("filepath", type=str)
import msgpack
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D
import numpy as np
from numpy.linalg import inv
from scipy.spatial.transform import Rotation as R
import open3d as o3d
with open("map.msg", "rb") as f:
u = msgpack.Unpacker(f)
import msgpack
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D
import numpy as np
from scipy.spatial.transform import Rotation as R
with open("map.msg", "rb") as f:
u = msgpack.Unpacker(f)
msg = u.unpack()
repositories:
ament/ament_cmake:
type: git
url: https://github.com/ament/ament_cmake.git
version: master
ament/ament_index:
type: git
url: https://github.com/ament/ament_index.git
version: master
ament/ament_lint: