1、编译
cd ~/msckf
catkin_make --pkg msckf_vio --cmake-args -DCMAKE_BUILD_TYPE=Release
2、运行(运行euroc数据集)
首先roscore开启ros节点
cd ~/msckf
source ~/msckf/devel/setup.bash
roslaunch msckf_vio msckf_vio_euroc.launch
cd ~/msckf
source ~/msckf/devel/setup.bash
rosrun rviz rviz -d /home/dyt/msckf/src/msckf_vio/rviz/rviz_euroc_config.rviz
cd ~/msckf
source ~/msckf/devel/setup.bash
rosbag play /home/dyt/DYT/compare/euroc6/MH_05/data.bag
3、运行(运行tum数据集)
首先roscore开启ros节点
cd ~/msckf
source ~/msckf/devel/setup.bash
roslaunch msckf_vio msckf_vio_tum.launch
cd ~/msckf
source ~/msckf/devel/setup.bash
rosrun rviz rviz -d /home/dyt/msckf/src/msckf_vio/rviz/rviz_tum_config.rviz
cd ~/msckf
source ~/msckf/devel/setup.bash
rosbag play /home/dyt/DYT/compare/tum/room1/data.bag
4、运行(运行kitti数据集)
首先roscore开启ros节点
cd ~/msckf
source ~/msckf/devel/setup.bash
roslaunch msckf_vio msckf_vio_kitti.launch
cd ~/msckf
source ~/msckf/devel/setup.bash
rosrun rviz rviz -d /home/dyt/msckf/src/msckf_vio/rviz/rviz_kitti_config.rviz
cd ~/msckf
source ~/msckf/devel/setup.bash
rosbag play /home/dyt/compare11/kitti/kitti2bag-master/kitti2bag/kitti_2011_10_03_drive_0042_synced.bag
运行KITTI数据集:
1、首先需要处理kitti数据集,使用kitti2bag工具,运行Python指令:
python kitti2bag1.py raw_synced /home/dyt/ -t 2011_10_03 -r 0042
代码如下:
#!env python
# -*- coding: utf-8 -*-import systry:import pykitti
except ImportError as e:print('Could not load module \'pykitti\'. Please run `pip install pykitti`')sys.exit(1)import tf
import os
import cv2
import rospy
import rosbag
import progressbar
from tf2_msgs.msg import TFMessage
from datetime import datetime
from std_msgs.msg import Header
from sensor_msgs.msg import CameraInfo, Imu, PointField, NavSatFix
import sensor_msgs.point_cloud2 as pcl2
from geometry_msgs.msg import TransformStamped, TwistStamped, Transform
from cv_bridge import CvBridge
import numpy as np
import argparsedef save_imu_data(bag, kitti, imu_frame_id, topic):print("Exporting IMU")for timestamp, oxts in zip(kitti.timestamps, kitti.oxts):q = tf.transformations.quaternion_from_euler(oxts.packet.roll, oxts.packet.pitch, oxts.packet.yaw)imu = Imu()imu.header.frame_id = imu_frame_idimu.header.stamp = rospy.Time.from_sec(float(timestamp.strftime("%s.%f")))imu.orientation.x = q[0]imu.orientation.y = q[1]imu.orientation.z = q[2]imu.orientation.w = q[3]imu.linear_acceleration.x = oxts.packet.aximu.linear_acceleration.y = oxts.packet.ayimu.linear_acceleration.z = oxts.packet.azimu.angular_velocity.x = oxts.packet.wximu.angular_velocity.y = oxts.packet.wyimu.angular_velocity.z = oxts.packet.wzbag.write(topic, imu, t=imu.header.stamp)def save_dynamic_tf(bag, kitti, kitti_type, initial_time):print("Exporting time dependent transformations")if kitti_type.find("raw") != -1:for timestamp, oxts in zip(kitti.timestamps, kitti.oxts):tf_oxts_msg = TFMessage()tf_oxts_transform = TransformStamped()tf_oxts_transform.header.stamp = rospy.Time.from_sec(float(timestamp.strftime("%s.%f")))tf_oxts_transform.header.frame_id = 'world'tf_oxts_transform.child_frame_id = 'base_link'transform = (oxts.T_w_imu)t = transform[0:3, 3]q = tf.transformations.quaternion_from_matrix(transform)oxts_tf = Transform()oxts_tf.translation.x = t[0]oxts_tf.translation.y = t[1]oxts_tf.translation.z = t[2]oxts_tf.rotation.x = q[0]oxts_tf.rotation.y = q[1]oxts_tf.rotation.z = q[2]oxts_tf.rotation.w = q[3]tf_oxts_transform.transform = oxts_tftf_oxts_msg.transforms.append(tf_oxts_transform)bag.write('/tf', tf_oxts_msg, tf_oxts_msg.transforms[0].header.stamp)elif kitti_type.find("odom") != -1:timestamps = map(lambda x: initial_time + x.total_seconds(), kitti.timestamps)for timestamp, tf_matrix in zip(timestamps, kitti.T_w_cam0):tf_msg = TFMessage()tf_stamped = TransformStamped()tf_stamped.header.stamp = rospy.Time.from_sec(timestamp)tf_stamped.header.frame_id = 'world'tf_stamped.child_frame_id = 'camera_left't = tf_matrix[0:3, 3]q = tf.transformations.quaternion_from_matrix(tf_matrix)transform = Transform()transform.translation.x = t[0]transform.translation.y = t[1]transform.translation.z = t[2]transform.rotation.x = q[0]transform.rotation.y = q[1]transform.rotation.z = q[2]transform.rotation.w = q[3]tf_stamped.transform = transformtf_msg.transforms.append(tf_stamped)bag.write('/tf', tf_msg, tf_msg.transforms[0].header.stamp)def save_camera_data(bag, kitti_type, kitti, util, bridge, camera, camera_frame_id, topic, initial_time):print("Exporting camera {}".format(camera))if kitti_type.find("raw") != -1:camera_pad = '{0:02d}'.format(camera)image_dir = os.path.join(kitti.data_path, 'image_{}'.format(camera_pad))image_path = os.path.join(image_dir, 'data')image_filenames = sorted(os.listdir(image_path))with open(os.path.join(image_dir, 'timestamps.txt')) as f:image_datetimes = map(lambda x: datetime.strptime(x[:-4], '%Y-%m-%d %H:%M:%S.%f'), f.readlines())calib = CameraInfo()calib.header.frame_id = camera_frame_idcalib.width, calib.height = tuple(util['S_rect_{}'.format(camera_pad)].tolist())calib.distortion_model = 'plumb_bob'calib.K = util['K_{}'.format(camera_pad)]calib.R = util['R_rect_{}'.format(camera_pad)]calib.D = util['D_{}'.format(camera_pad)]calib.P = util['P_rect_{}'.format(camera_pad)]elif kitti_type.find("odom") != -1:camera_pad = '{0:01d}'.format(camera)image_path = os.path.join(kitti.sequence_path, 'image_{}'.format(camera_pad))image_filenames = sorted(os.listdir(image_path))image_datetimes = map(lambda x: initial_time + x.total_seconds(), kitti.timestamps)calib = CameraInfo()calib.header.frame_id = camera_frame_idcalib.P = util['P{}'.format(camera_pad)]iterable = zip(image_datetimes, image_filenames)bar = progressbar.ProgressBar()for dt, filename in bar(iterable):image_filename = os.path.join(image_path, filename)cv_image = cv2.imread(image_filename)calib.height, calib.width = cv_image.shape[:2]if camera in (0, 1):cv_image = cv2.cvtColor(cv_image, cv2.COLOR_BGR2GRAY)encoding = "mono8" if camera in (0, 1) else "bgr8"image_message = bridge.cv2_to_imgmsg(cv_image, encoding=encoding)image_message.header.frame_id = camera_frame_idif kitti_type.find("raw") != -1:image_message.header.stamp = rospy.Time.from_sec(float(datetime.strftime(dt, "%s.%f")))topic_ext = "/image_raw"elif kitti_type.find("odom") != -1:image_message.header.stamp = rospy.Time.from_sec(dt)topic_ext = "/image_rect"calib.header.stamp = image_message.header.stampbag.write(topic + topic_ext, image_message, t = image_message.header.stamp)bag.write(topic + '/camera_info', calib, t = calib.header.stamp) def get_static_transform(from_frame_id, to_frame_id, transform):t = transform[0:3, 3]q = tf.transformations.quaternion_from_matrix(transform)tf_msg = TransformStamped()tf_msg.header.frame_id = from_frame_idtf_msg.child_frame_id = to_frame_idtf_msg.transform.translation.x = float(t[0])tf_msg.transform.translation.y = float(t[1])tf_msg.transform.translation.z = float(t[2])tf_msg.transform.rotation.x = float(q[0])tf_msg.transform.rotation.y = float(q[1])tf_msg.transform.rotation.z = float(q[2])tf_msg.transform.rotation.w = float(q[3])return tf_msgdef inv(transform):"Invert rigid body transformation matrix"R = transform[0:3, 0:3]t = transform[0:3, 3]t_inv = -1 * R.T.dot(t)transform_inv = np.eye(4)transform_inv[0:3, 0:3] = R.Ttransform_inv[0:3, 3] = t_invreturn transform_invdef save_static_transforms(bag, transforms, timestamps):print("Exporting static transformations")tfm = TFMessage()for transform in transforms:t = get_static_transform(from_frame_id=transform[0], to_frame_id=transform[1], transform=transform[2])tfm.transforms.append(t)for timestamp in timestamps:time = rospy.Time.from_sec(float(timestamp.strftime("%s.%f")))for i in range(len(tfm.transforms)):tfm.transforms[i].header.stamp = timebag.write('/tf_static', tfm, t=time)def run_kitti2bag():parser = argparse.ArgumentParser(description = "Convert KITTI dataset to ROS bag file the easy way!")# Accepted argument valueskitti_types = ["raw_synced", "odom_color", "odom_gray"]odometry_sequences = []for s in range(22):odometry_sequences.append(str(s).zfill(2))parser.add_argument("kitti_type", choices = kitti_types, help = "KITTI dataset type")parser.add_argument("dir", nargs = "?", default = os.getcwd(), help = "base directory of the dataset, if no directory passed the deafult is current working directory")parser.add_argument("-t", "--date", help = "date of the raw dataset (i.e. 2011_09_26), option is only for RAW datasets.")parser.add_argument("-r", "--drive", help = "drive number of the raw dataset (i.e. 0001), option is only for RAW datasets.")parser.add_argument("-s", "--sequence", choices = odometry_sequences,help = "sequence of the odometry dataset (between 00 - 21), option is only for ODOMETRY datasets.")args = parser.parse_args()bridge = CvBridge()compression = rosbag.Compression.NONE# compression = rosbag.Compression.BZ2# compression = rosbag.Compression.LZ4# CAMERAScameras = [(0, 'camera_gray_left', '/kitti/camera_gray_left'),(1, 'camera_gray_right', '/kitti/camera_gray_right')]if args.kitti_type.find("raw") != -1:if args.date == None:print("Date option is not given. It is mandatory for raw dataset.")print("Usage for raw dataset: kitti2bag raw_synced [dir] -t <date> -r <drive>")sys.exit(1)elif args.drive == None:print("Drive option is not given. It is mandatory for raw dataset.")print("Usage for raw dataset: kitti2bag raw_synced [dir] -t <date> -r <drive>")sys.exit(1)bag = rosbag.Bag("kitti_{}_drive_{}_{}.bag".format(args.date, args.drive, args.kitti_type[4:]), 'w', compression=compression)kitti = pykitti.raw(args.dir, args.date, args.drive)if not os.path.exists(kitti.data_path):print('Path {} does not exists. Exiting.'.format(kitti.data_path))sys.exit(1)if len(kitti.timestamps) == 0:print('Dataset is empty? Exiting.')sys.exit(1)try:# IMUimu_frame_id = 'imu_link'imu_topic = '/kitti/oxts/imu'T_base_link_to_imu = np.eye(4, 4)T_base_link_to_imu[0:3, 3] = [-2.71/2.0-0.05, 0.32, 0.93]# tf_statictransforms = [('base_link', imu_frame_id, T_base_link_to_imu),(imu_frame_id, cameras[0][1], inv(kitti.calib.T_cam0_imu)),(imu_frame_id, cameras[1][1], inv(kitti.calib.T_cam1_imu))]util = pykitti.utils.read_calib_file(os.path.join(kitti.calib_path, 'calib_cam_to_cam.txt'))# Exportsave_static_transforms(bag, transforms, kitti.timestamps)save_dynamic_tf(bag, kitti, args.kitti_type, initial_time=None)save_imu_data(bag, kitti, imu_frame_id, imu_topic)for camera in cameras:save_camera_data(bag, args.kitti_type, kitti, util, bridge,camera=camera[0], camera_frame_id=camera[1], topic=camera[2], initial_time=None)finally:print("## OVERVIEW ##")print(bag)bag.close()elif args.kitti_type.find("odom") != -1:if args.sequence == None:print("Sequence option is not given. It is mandatory for odometry dataset.")print("Usage for odometry dataset: kitti2bag {odom_color, odom_gray} [dir] -s <sequence>")sys.exit(1)bag = rosbag.Bag("kitti_data_odometry_{}_sequence_{}.bag".format(args.kitti_type[5:],args.sequence), 'w', compression=compression)kitti = pykitti.odometry(args.dir, args.sequence)if not os.path.exists(kitti.sequence_path):print('Path {} does not exists. Exiting.'.format(kitti.sequence_path))sys.exit(1)kitti.load_calib() kitti.load_timestamps() if len(kitti.timestamps) == 0:print('Dataset is empty? Exiting.')sys.exit(1)if args.sequence in odometry_sequences[:11]:print("Odometry dataset sequence {} has ground truth information (poses).".format(args.sequence))kitti.load_poses()try:util = pykitti.utils.read_calib_file(os.path.join(args.dir,'sequences',args.sequence, 'calib.txt'))current_epoch = (datetime.utcnow() - datetime(1970, 1, 1)).total_seconds()# Exportif args.kitti_type.find("gray") != -1:used_cameras = cameras[:2]elif args.kitti_type.find("color") != -1:used_cameras = cameras[-2:]save_dynamic_tf(bag, kitti, args.kitti_type, initial_time=current_epoch)for camera in used_cameras:save_camera_data(bag, args.kitti_type, kitti, util, bridge, camera=camera[0], camera_frame_id=camera[1], topic=camera[2], initial_time=current_epoch)finally:print("## OVERVIEW ##")print(bag)bag.close()
if __name__ == '__main__':run_kitti2bag()
查看topic:
rosbag info kitti_2011_10_03_drive_0042_synced.bag
2、在msckf_vio里面新建launch文件和yaml文件,注意旋转矩阵需要修改。