├── launch
└── kaist2bag.launch
├── .gitignore
├── src
├── fog_converter.h
├── gps_converter.h
├── vrs_converter.h
├── converter.h
├── altimeter_converter.h
├── encoder_converter.h
├── imu_converter.h
├── stereo_converter.h
├── sick_converter.h
├── velodyne_converter.h
├── converter.cpp
├── fog_converter.cpp
├── altimeter_converter.cpp
├── gps_converter.cpp
├── vrs_converter.cpp
├── stereo_converter.cpp
├── velodyne_converter.cpp
├── sick_converter.cpp
├── encoder_converter.cpp
├── main.cpp
└── imu_converter.cpp
├── config
└── config.yaml
├── LICENSE
├── README.md
├── package.xml
├── scripts
└── mergebag.py
└── CMakeLists.txt
/launch/kaist2bag.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | # Prerequisites
2 | *.d
3 |
4 | # Compiled Object files
5 | *.slo
6 | *.lo
7 | *.o
8 | *.obj
9 |
10 | # Precompiled Headers
11 | *.gch
12 | *.pch
13 |
14 | # Compiled Dynamic libraries
15 | *.so
16 | *.dylib
17 | *.dll
18 |
19 | # Fortran module files
20 | *.mod
21 | *.smod
22 |
23 | # Compiled Static libraries
24 | *.lai
25 | *.la
26 | *.a
27 | *.lib
28 |
29 | # Executables
30 | *.exe
31 | *.out
32 | *.app
33 |
--------------------------------------------------------------------------------
/src/fog_converter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/21/21.
3 | //
4 |
5 | #ifndef SRC_FOG_CONVERTER_H
6 | #define SRC_FOG_CONVERTER_H
7 |
8 | #include
9 | #include "converter.h"
10 |
11 | namespace kaist2bag {
12 |
13 | class FogConverter : public Converter {
14 | public:
15 | FogConverter(const std::string& dataset_dir, const std::string& save_dir, const std::string& topic);
16 | virtual ~FogConverter() = default;
17 |
18 | int Convert() override;
19 |
20 | std::string default_data_file = "sensor_data/fog.csv";
21 |
22 | private:
23 | std::string topic_;
24 | std::string bag_name_;
25 | };
26 |
27 |
28 | } // namespace kaist2bag
29 |
30 | #endif //SRC_FOG_CONVERTER_H
31 |
--------------------------------------------------------------------------------
/src/gps_converter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/22/21.
3 | //
4 |
5 | #ifndef SRC_GPS_CONVERTER_H
6 | #define SRC_GPS_CONVERTER_H
7 |
8 | #include
9 | #include "converter.h"
10 |
11 | namespace kaist2bag {
12 |
13 | class GpsConverter : public Converter {
14 | public:
15 | GpsConverter(const std::string& dataset_dir, const std::string& save_dir, const std::string& topic);
16 | virtual ~GpsConverter() = default;
17 |
18 | int Convert() override;
19 |
20 | std::string default_data_file = "sensor_data/gps.csv";
21 |
22 | private:
23 | std::string topic_;
24 | std::string bag_name_;
25 | };
26 |
27 |
28 | } // namespace kaist2bag
29 |
30 | #endif //SRC_GPS_CONVERTER_H
31 |
--------------------------------------------------------------------------------
/src/vrs_converter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/22/21.
3 | //
4 |
5 | #ifndef SRC_VRS_CONVERTER_H
6 | #define SRC_VRS_CONVERTER_H
7 |
8 | #include
9 | #include "converter.h"
10 |
11 | namespace kaist2bag {
12 |
13 | class VrsConverter : public Converter {
14 | public:
15 | VrsConverter(const std::string& dataset_dir, const std::string& save_dir, const std::string& topic);
16 | virtual ~VrsConverter() = default;
17 |
18 | int Convert() override;
19 |
20 | std::string default_data_file = "sensor_data/vrs_gps.csv";
21 |
22 | private:
23 | std::string topic_;
24 | std::string bag_name_;
25 | };
26 |
27 |
28 | } // namespace kaist2bag
29 |
30 | #endif //SRC_VRS_CONVERTER_H
31 |
--------------------------------------------------------------------------------
/src/converter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/11/21.
3 | //
4 |
5 | #ifndef SRC_CONVERTER_H
6 | #define SRC_CONVERTER_H
7 |
8 | #include
9 | #include
10 |
11 | namespace kaist2bag {
12 |
13 | std::string FilterSlash(const std::string& input);
14 |
15 | class Converter {
16 | public:
17 | Converter(const std::string& dataset_dir, const std::string& save_dir);
18 | virtual ~Converter() = default;
19 |
20 | virtual int Convert();
21 | virtual bool DirValid();
22 |
23 | protected:
24 | void CheckAndCreateSaveDir();
25 |
26 | protected:
27 | std::string dataset_dir_;
28 | std::string save_dir_;
29 | bool dir_valid_;
30 | };
31 |
32 |
33 | } // namespace kaist2bag
34 |
35 | #endif //SRC_CONVERTER_H
36 |
--------------------------------------------------------------------------------
/src/altimeter_converter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/11/21.
3 | //
4 |
5 | #ifndef SRC_ALTIMETER_CONVERTER_H
6 | #define SRC_ALTIMETER_CONVERTER_H
7 |
8 | #include
9 | #include "converter.h"
10 |
11 | namespace kaist2bag {
12 |
13 | class AltimeterConverter : public Converter {
14 | public:
15 | AltimeterConverter(const std::string& dataset_dir, const std::string& save_dir, const std::string& topic);
16 | virtual ~AltimeterConverter() = default;
17 |
18 | int Convert() override;
19 |
20 | std::string default_data_file = "sensor_data/altimeter.csv";
21 |
22 | private:
23 | std::string topic_;
24 | std::string bag_name_;
25 | };
26 |
27 |
28 | } // namespace kaist2bag
29 |
30 | #endif //SRC_ALTIMETER_CONVERTER_H
31 |
--------------------------------------------------------------------------------
/src/encoder_converter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/21/21.
3 | //
4 |
5 | #ifndef SRC_ENCODER_CONVERTER_H
6 | #define SRC_ENCODER_CONVERTER_H
7 |
8 | #include "converter.h"
9 |
10 | namespace kaist2bag {
11 |
12 | class EncoderConverter : public Converter {
13 | public:
14 | EncoderConverter(const std::string& dataset_dir, const std::string& save_dir, const std::string &irp_topic, const std::string &raw_topic);
15 | virtual ~EncoderConverter() = default;
16 |
17 | int Convert() override;
18 |
19 | std::string default_data_file = "sensor_data/encoder.csv";
20 | std::string default_calib_file = "calibration/EncoderParameter.txt";
21 |
22 | private:
23 | std::string irp_topic_;
24 | std::string raw_topic_;
25 | std::string irp_bag_name_;
26 | std::string raw_bag_name_;
27 | };
28 |
29 |
30 |
31 |
32 | } // namespace kaist2bag
33 |
34 | #endif //SRC_ENCODER_CONVERTER_H
35 |
--------------------------------------------------------------------------------
/config/config.yaml:
--------------------------------------------------------------------------------
1 | dataset: "/home/tao/sda/dataset/kaist/urban30/urban30-gangnam"
2 | save_to: "/home/tao/sda/dataset/kaist/urban30/urban30-gangnam/bag"
3 |
4 | altimeter: true
5 | altimeter_topic: "/altimeter_data"
6 |
7 | encoder: true
8 | encoder_irp_topic: "/encoder_count"
9 | encoder_raw_topic: "/joint_states"
10 |
11 | fog: true
12 | fog_topic: "/dsp1760_data"
13 |
14 | gps: true
15 | gps_topic: "/gps/fix"
16 |
17 | vrs: true
18 | vrs_topic: "/vrs_gps_data"
19 |
20 | imu: true
21 | imu_irp_topic: "/xsens_imu_data"
22 | imu_raw_topic: "/imu/data_raw"
23 | imu_mag_topic: "/imu/mag"
24 |
25 | velodyne: true
26 | velodyne_left_topic: "/ns2/velodyne_points"
27 | velodyne_right_topic: "/ns1/velodyne_points"
28 |
29 | sick: true
30 | sick_back_topic: "/lms511_back/scan"
31 | sick_middle_topic: "/lms511_middle/scan"
32 |
33 | stereo: true
34 | stereo_left_topic: "/stereo/left/image_raw"
35 | stereo_right_topic: "/stereo/right/image_raw"
36 |
--------------------------------------------------------------------------------
/src/imu_converter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/24/21.
3 | //
4 |
5 | #ifndef SRC_IMU_CONVERTER_H
6 | #define SRC_IMU_CONVERTER_H
7 | #include
8 | #include "converter.h"
9 |
10 | namespace kaist2bag {
11 |
12 | class ImuConverter : public Converter {
13 | public:
14 | ImuConverter(const std::string& dataset_dir, const std::string& save_dir,
15 | const std::string& irp_topic, const std::string& raw_topic,
16 | const std::string& mag_topic);
17 | virtual ~ImuConverter() = default;
18 |
19 | int Convert() override;
20 |
21 | std::string default_data_file = "sensor_data/xsens_imu.csv";
22 |
23 | private:
24 | std::string irp_topic_;
25 | std::string raw_topic_;
26 | std::string mag_topic_;
27 | std::string irp_bag_name_;
28 | std::string raw_bag_name_;
29 | std::string mag_bag_name_;
30 | };
31 |
32 |
33 | } // namespace kaist2bag
34 | #endif //SRC_IMU_CONVERTER_H
35 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2021 tsyxyz
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # kaist2bag
2 | A tool to convert KAIST urban dataset to rosbag.
3 |
4 | Only tested on Ubuntu 20.04.
5 |
6 |
7 |
8 | ## Guide
9 |
10 | 1. Download desired database files from the [website](https://sites.google.com/view/complex-urban-dataset)
11 |
12 | 2. Extract `.gz.tar` files into their folders
13 | ```
14 | find . -name 'urban28*.tar.gz' -execdir tar -xzvf '{}' \;
15 | ```
16 |
17 | 3. Clone and build this repository
18 | ```
19 | cd src
20 | git clone https://github.com/irapkaist/irp_sen_msgs.git
21 | git clone https://github.com/tsyxyz/kaist2bag.git
22 | cd ..
23 | catkin build
24 | ```
25 |
26 | 4. Edit the [config file](config/config.yaml) with path and desired topics
27 |
28 |
29 | 5. Create a rosbag file for each sensor type
30 | ```
31 | source devel/setup.bash
32 | roslaunch kaist2bag kaist2bag.launch
33 | ```
34 |
35 | 6. Merge all bags into a single one (if desired)
36 | ```
37 | rosrun kaist2bag mergebag.py merged.bag ...
38 | ```
39 |
40 |
41 |
42 |
43 | ## Acknowledge
44 |
45 | File parsing code are referenced from [file_player](https://github.com/irapkaist/file_player).
46 |
47 |
48 |
49 |
--------------------------------------------------------------------------------
/src/stereo_converter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/28/21.
3 | //
4 |
5 | #ifndef SRC_STEREO_CONVERTER_H
6 | #define SRC_STEREO_CONVERTER_H
7 | #include
8 | #include "converter.h"
9 |
10 | namespace kaist2bag {
11 |
12 | class StereoConverter : public Converter {
13 | public:
14 | StereoConverter(const std::string& dataset_dir, const std::string& save_dir,
15 | const std::string& left_topic, const std::string& right_topic);
16 | virtual ~StereoConverter() = default;
17 |
18 | int Convert() override;
19 |
20 | std::string default_stamp_file = "sensor_data/stereo_stamp.csv";
21 | std::string default_left_data_dir = "image/stereo_left";
22 | std::string default_right_data_dir = "image/stereo_right";
23 |
24 | private:
25 | std::string left_topic_;
26 | std::string left_bag_name_;
27 | std::string right_topic_;
28 | std::string right_bag_name_;
29 |
30 | void Convert(const std::string& stamp_file, const std::string& data_dir,
31 | const std::string& bag_file, const std::string& topic,
32 | const std::string& frame_id);
33 | };
34 |
35 |
36 | } // namespace kaist2bag
37 | #endif //SRC_STEREO_CONVERTER_H
38 |
--------------------------------------------------------------------------------
/src/sick_converter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/28/21.
3 | //
4 |
5 | #ifndef SRC_SICK_CONVERTER_H
6 | #define SRC_SICK_CONVERTER_H
7 | #include
8 | #include "converter.h"
9 |
10 | namespace kaist2bag {
11 |
12 | class SickConverter : public Converter {
13 | public:
14 | SickConverter(const std::string& dataset_dir, const std::string& save_dir,
15 | const std::string& back_topic, const std::string& middle_topic);
16 | virtual ~SickConverter() = default;
17 |
18 | int Convert() override;
19 |
20 | std::string default_back_stamp_file = "sensor_data/SICK_back_stamp.csv";
21 | std::string default_back_data_dir = "sensor_data/SICK_back";
22 | std::string default_middle_stamp_file = "sensor_data/SICK_middle_stamp.csv";
23 | std::string default_middle_data_dir = "sensor_data/SICK_middle";
24 |
25 | private:
26 | std::string back_topic_;
27 | std::string back_bag_name_;
28 | std::string middle_topic_;
29 | std::string middle_bag_name_;
30 |
31 | void Convert(const std::string& stamp_file, const std::string& data_dir,
32 | const std::string& bag_file, const std::string& topic,
33 | const std::string& frame_id);
34 | };
35 |
36 |
37 | } // namespace kaist2bag
38 | #endif //SRC_SICK_CONVERTER_H
39 |
--------------------------------------------------------------------------------
/src/velodyne_converter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/25/21.
3 | //
4 |
5 | #ifndef SRC_VELODYNE_CONVERTER_H
6 | #define SRC_VELODYNE_CONVERTER_H
7 | #include
8 | #include "converter.h"
9 |
10 | namespace kaist2bag {
11 |
12 | class VelodyneConverter : public Converter {
13 | public:
14 | VelodyneConverter(const std::string& dataset_dir, const std::string& save_dir,
15 | const std::string& left_topic, const std::string& right_topic);
16 | virtual ~VelodyneConverter() = default;
17 |
18 | int Convert() override;
19 |
20 | std::string default_left_stamp_file = "sensor_data/VLP_left_stamp.csv";
21 | std::string default_left_data_dir = "sensor_data/VLP_left";
22 | std::string default_right_stamp_file = "sensor_data/VLP_right_stamp.csv";
23 | std::string default_right_data_dir = "sensor_data/VLP_right";
24 |
25 | private:
26 | std::string left_topic_;
27 | std::string left_bag_name_;
28 | std::string right_topic_;
29 | std::string right_bag_name_;
30 |
31 | void Convert(const std::string& stamp_file, const std::string& data_dir,
32 | const std::string& bag_file, const std::string& topic,
33 | const std::string& frame_id);
34 | };
35 |
36 |
37 | } // namespace kaist2bag
38 | #endif //SRC_VELODYNE_CONVERTER_H
39 |
--------------------------------------------------------------------------------
/src/converter.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/11/21.
3 | //
4 |
5 | #include "converter.h"
6 |
7 | #include
8 | #include
9 | #include
10 |
11 | namespace kaist2bag {
12 |
13 | std::string FilterSlash(const std::string& input) {
14 | if (input.empty()) return std::string();
15 | std::string str = input;
16 | if (*str.begin() == '/') {
17 | str.erase(str.begin());
18 | if (str.empty()) return std::string();
19 | }
20 |
21 | if (*(str.end() - 1) == '/') {
22 | str.erase(str.end() - 1);
23 | if (str.empty()) return std::string();
24 | }
25 | std::replace(str.begin(), str.end(), '/', '_');
26 | return str;
27 | }
28 |
29 | Converter::Converter(const std::string &dataset_dir, const std::string &save_dir)
30 | : dataset_dir_(dataset_dir), save_dir_(save_dir){
31 | struct stat buffer;
32 | dir_valid_ = (stat(dataset_dir_.c_str(), &buffer) == 0);
33 | }
34 |
35 | int Converter::Convert() {
36 | return 0;
37 | }
38 |
39 | bool Converter::DirValid() {
40 | return dir_valid_;
41 | }
42 |
43 | void Converter::CheckAndCreateSaveDir() {
44 | if (!boost::filesystem::is_directory(save_dir_) || !boost::filesystem::exists(save_dir_)) {
45 | boost::filesystem::create_directory(save_dir_);
46 | }
47 | }
48 |
49 | } // namespace kaist2bag
--------------------------------------------------------------------------------
/src/fog_converter.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/21/21.
3 | //
4 |
5 | #include "fog_converter.h"
6 |
7 | #include
8 | #include
9 | #include
10 |
11 | namespace kaist2bag {
12 |
13 | FogConverter::FogConverter(const std::string &dataset_dir, const std::string &save_dir,
14 | const std::string &topic)
15 | : Converter(dataset_dir, save_dir), topic_(topic) {
16 | bag_name_ = FilterSlash(topic_) + ".bag";
17 | }
18 |
19 | int FogConverter::Convert() {
20 | CheckAndCreateSaveDir();
21 |
22 | boost::filesystem::path bag_file = boost::filesystem::path(save_dir_) / bag_name_;
23 | rosbag::Bag bag(bag_file.string(), rosbag::bagmode::Write);
24 | ROS_INFO("saving %s", bag_file.c_str());
25 |
26 | const std::string data_file = dataset_dir_ + "/" + default_data_file;
27 | FILE* fp = fopen(data_file.c_str(), "r");
28 | irp_sen_msgs::fog_3axis fog_data;
29 | int64_t stamp;
30 | float roll, pitch, yaw;
31 | while (fscanf(fp, "%ld,%f,%f,%f\n", &stamp, &roll, &pitch, &yaw) == 4) {
32 | fog_data.header.stamp.fromNSec(stamp);
33 | fog_data.header.frame_id = "dsp1760";
34 | fog_data.d_roll = roll;
35 | fog_data.d_pitch = pitch;
36 | fog_data.d_yaw = yaw;
37 |
38 | bag.write(topic_, fog_data.header.stamp, fog_data);
39 | }
40 | bag.close();
41 | fclose(fp);
42 | ROS_INFO("done saving %s", bag_file.c_str());
43 |
44 | return 0;
45 | }
46 |
47 | } // namespace kaist2bag
--------------------------------------------------------------------------------
/src/altimeter_converter.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/11/21.
3 | //
4 |
5 | #include "altimeter_converter.h"
6 |
7 | #include
8 | #include
9 | #include
10 |
11 | namespace kaist2bag {
12 |
13 | AltimeterConverter::AltimeterConverter(const std::string &dataset_dir, const std::string &save_dir,
14 | const std::string &topic)
15 | : Converter(dataset_dir, save_dir), topic_(topic) {
16 | bag_name_ = FilterSlash(topic_) + ".bag";
17 | }
18 |
19 | int AltimeterConverter::Convert() {
20 | CheckAndCreateSaveDir();
21 |
22 | boost::filesystem::path bag_file = boost::filesystem::path(save_dir_) / bag_name_;
23 | rosbag::Bag bag(bag_file.string(), rosbag::bagmode::Write);
24 | ROS_INFO("saving %s", bag_file.c_str());
25 |
26 | const std::string data_file = dataset_dir_ + "/" + default_data_file;
27 | FILE* fp = fopen(data_file.c_str(), "r");
28 | irp_sen_msgs::altimeter altimeter_data;
29 | int64_t stamp;
30 | double altimeter_value;
31 | while (fscanf(fp, "%ld,%lf\n", &stamp, &altimeter_value) == 2) {
32 | altimeter_data.header.stamp.fromNSec(stamp);
33 | altimeter_data.header.frame_id = "altimeter";
34 | altimeter_data.data = altimeter_value;
35 |
36 | bag.write(topic_, altimeter_data.header.stamp, altimeter_data);
37 | }
38 | bag.close();
39 | fclose(fp);
40 | ROS_INFO("done saving %s", bag_file.c_str());
41 |
42 | return 0;
43 | }
44 |
45 | } // namespace kaist2bag
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | kaist2bag
4 | 0.0.0
5 | The kaist2bag package
6 |
7 | tsyxyz
8 |
9 | MIT
10 |
11 | catkin
12 | roscpp
13 | rospy
14 | std_msgs
15 | geometry_msgs
16 | message_generation
17 | rosbag
18 | image_transport
19 | cv_bridge
20 | pcl_ros
21 | pcl_conversions
22 | pcl_msgs
23 | irp_sen_msgs
24 | tf
25 | roscpp
26 | rospy
27 | std_msgs
28 | roscpp
29 | rospy
30 | std_msgs
31 | geometry_msgs
32 | message_generation
33 | rosbag
34 | image_transport
35 | cv_bridge
36 | pcl_ros
37 | pcl_conversions
38 | pcl_msgs
39 | irp_sen_msgs
40 | tf
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
--------------------------------------------------------------------------------
/src/gps_converter.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/22/21.
3 | //
4 |
5 | #include "gps_converter.h"
6 |
7 | #include
8 | #include
9 | #include
10 |
11 | namespace kaist2bag {
12 |
13 | GpsConverter::GpsConverter(const std::string &dataset_dir, const std::string &save_dir,
14 | const std::string &topic)
15 | : Converter(dataset_dir, save_dir), topic_(topic) {
16 | bag_name_ = FilterSlash(topic_) + ".bag";
17 | }
18 |
19 | int GpsConverter::Convert() {
20 | CheckAndCreateSaveDir();
21 |
22 | boost::filesystem::path bag_file = boost::filesystem::path(save_dir_) / bag_name_;
23 | rosbag::Bag bag(bag_file.string(), rosbag::bagmode::Write);
24 | ROS_INFO("saving %s", bag_file.c_str());
25 |
26 | const std::string data_file = dataset_dir_ + "/" + default_data_file;
27 | FILE* fp = fopen(data_file.c_str(), "r");
28 | sensor_msgs::NavSatFix gps_data;
29 | int64_t stamp;
30 | double latitude, longitude, altitude;
31 | double cov[9];
32 | while (fscanf(fp,"%ld,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf\n",
33 | &stamp,&latitude,&longitude,&altitude,
34 | &cov[0],&cov[1],&cov[2],&cov[3],&cov[4],
35 | &cov[5],&cov[6],&cov[7],&cov[8]) == 13) {
36 | gps_data.header.stamp.fromNSec(stamp);
37 | gps_data.header.frame_id = "gps";
38 | gps_data.latitude = latitude;
39 | gps_data.longitude = longitude;
40 | gps_data.altitude = altitude;
41 | for (int i = 0; i < 9; ++i) {
42 | gps_data.position_covariance[i] = cov[i];
43 | }
44 |
45 | bag.write(topic_, gps_data.header.stamp, gps_data);
46 | }
47 | bag.close();
48 | fclose(fp);
49 | ROS_INFO("done saving %s", bag_file.c_str());
50 |
51 | return 0;
52 | }
53 |
54 | } // namespace kaist2bag
--------------------------------------------------------------------------------
/scripts/mergebag.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | # original source:
4 | # http://www.clearpathrobotics.com/assets/downloads/support/merge_bag.py
5 |
6 | import sys
7 | import argparse
8 | from fnmatch import fnmatchcase
9 |
10 | from rosbag import Bag
11 |
12 | def main():
13 |
14 | parser = argparse.ArgumentParser(description='Merge one or more bag files with the possibilities of filtering topics.')
15 | parser.add_argument('outputbag',
16 | help='output bag file with topics merged')
17 | parser.add_argument('inputbag', nargs='+',
18 | help='input bag files')
19 | parser.add_argument('-v', '--verbose', action="store_true", default=False,
20 | help='verbose output')
21 | parser.add_argument('-t', '--topics', default="*",
22 | help='string interpreted as a list of topics (wildcards \'*\' and \'?\' allowed) to include in the merged bag file')
23 |
24 | args = parser.parse_args()
25 |
26 | topics = args.topics.split(' ')
27 |
28 | total_included_count = 0
29 | total_skipped_count = 0
30 |
31 | if (args.verbose):
32 | print("Writing bag file: " + args.outputbag)
33 | print("Matching topics against patters: '%s'" % ' '.join(topics))
34 |
35 | with Bag(args.outputbag, 'w') as o:
36 | for ifile in args.inputbag:
37 | matchedtopics = []
38 | included_count = 0
39 | skipped_count = 0
40 | if (args.verbose):
41 | print("> Reading bag file: " + ifile)
42 | with Bag(ifile, 'r') as ib:
43 | for topic, msg, t in ib:
44 | if any(fnmatchcase(topic, pattern) for pattern in topics):
45 | if not topic in matchedtopics:
46 | matchedtopics.append(topic)
47 | if (args.verbose):
48 | print("Including matched topic '%s'" % topic)
49 | o.write(topic, msg, t)
50 | included_count += 1
51 | else:
52 | skipped_count += 1
53 | total_included_count += included_count
54 | total_skipped_count += skipped_count
55 | if (args.verbose):
56 | print("< Included %d messages and skipped %d" % (included_count, skipped_count))
57 |
58 | if (args.verbose):
59 | print("Total: Included %d messages and skipped %d" % (total_included_count, total_skipped_count))
60 |
61 | if __name__ == "__main__":
62 | main()
63 |
64 |
--------------------------------------------------------------------------------
/src/vrs_converter.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/22/21.
3 | //
4 |
5 | #include "vrs_converter.h"
6 |
7 | #include
8 | #include
9 | #include
10 |
11 | namespace kaist2bag {
12 |
13 | VrsConverter::VrsConverter(const std::string &dataset_dir, const std::string &save_dir,
14 | const std::string &topic)
15 | : Converter(dataset_dir, save_dir), topic_(topic) {
16 | bag_name_ = FilterSlash(topic_) + ".bag";
17 | }
18 |
19 | int VrsConverter::Convert() {
20 | CheckAndCreateSaveDir();
21 |
22 | boost::filesystem::path bag_file = boost::filesystem::path(save_dir_) / bag_name_;
23 | rosbag::Bag bag(bag_file.string(), rosbag::bagmode::Write);
24 | ROS_INFO("saving %s", bag_file.c_str());
25 |
26 | const std::string data_file = dataset_dir_ + "/" + default_data_file;
27 | FILE* fp = fopen(data_file.c_str(), "r");
28 | irp_sen_msgs::vrs vrs_data;
29 | int64_t stamp;
30 | double latitude, longitude, altitude, altitude_orthometric;
31 | double x_coordinate, y_coordinate, horizental_precision, lat_std, lon_std, altitude_std,
32 | heading_magnet, speed_knot, speed_km;
33 | int fix_state, number_of_sat, heading_valid;
34 | char GNVTG_mode;
35 | while (fscanf(fp,"%ld,%lf,%lf,%lf,%lf,%lf,%d,%d,%lf,%lf,%lf,%lf,%d,%lf,%lf,%lf,%c,%lf\n",
36 | &stamp,&latitude,&longitude,&x_coordinate,&y_coordinate,&altitude,&fix_state,
37 | &number_of_sat,&horizental_precision,&lat_std,&lon_std,&altitude_std,
38 | &heading_valid,&heading_magnet,&speed_knot,&speed_km,&GNVTG_mode,&altitude_orthometric) == 18) {
39 | vrs_data.header.stamp.fromNSec(stamp);
40 | vrs_data.header.frame_id = "altimeter";
41 | vrs_data.latitude = latitude;
42 | vrs_data.altitude_orthometric = altitude_orthometric;
43 | vrs_data.longitude = longitude;
44 | vrs_data.x_coordinate = x_coordinate;
45 | vrs_data.y_coordinate = y_coordinate;
46 | vrs_data.altitude = altitude;
47 | vrs_data.fix_state = fix_state;
48 | if (fix_state == 1) vrs_data.fix_state_str = "normal";
49 | if (fix_state == 4) vrs_data.fix_state_str = "fix";
50 | if (fix_state == 5) vrs_data.fix_state_str = "float";
51 | vrs_data.number_of_sat = number_of_sat;
52 | vrs_data.horizental_precision = horizental_precision;
53 | vrs_data.lat_std = lat_std;
54 | vrs_data.lon_std = lon_std;
55 | vrs_data.altitude_std = altitude_std;
56 | vrs_data.heading_valid = heading_valid;
57 | vrs_data.heading_magnet = heading_magnet;
58 | vrs_data.speed_knot = speed_knot;
59 | vrs_data.speed_km = speed_km;
60 | vrs_data.GNVTG_mode = GNVTG_mode;
61 |
62 | bag.write(topic_, vrs_data.header.stamp, vrs_data);
63 | }
64 | bag.close();
65 | fclose(fp);
66 | ROS_INFO("done saving %s", bag_file.c_str());
67 |
68 | return 0;
69 | }
70 |
71 | } // namespace kaist2bag
72 |
--------------------------------------------------------------------------------
/src/stereo_converter.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/28/21.
3 | //
4 |
5 | #include "stereo_converter.h"
6 |
7 | #include
8 | #include
9 | #include
10 | #include
11 | #include
12 | #include
13 | #include
14 | #include
15 | #include
16 |
17 | namespace kaist2bag {
18 |
19 | StereoConverter::StereoConverter(const std::string &dataset_dir, const std::string &save_dir,
20 | const std::string &left_topic, const std::string& right_topic)
21 | : Converter(dataset_dir, save_dir), left_topic_(left_topic), right_topic_(right_topic) {
22 | left_bag_name_ = FilterSlash(left_topic_) + ".bag";
23 | right_bag_name_ = FilterSlash(right_topic_) + ".bag";
24 | }
25 |
26 | int StereoConverter::Convert() {
27 | CheckAndCreateSaveDir();
28 |
29 | boost::filesystem::path left_bag_file = boost::filesystem::path(save_dir_) / left_bag_name_;
30 | boost::filesystem::path right_bag_file = boost::filesystem::path(save_dir_) / right_bag_name_;
31 |
32 | const std::string stamp_file = dataset_dir_ + "/" + default_stamp_file;
33 | const std::string left_data_dir = dataset_dir_ + "/" + default_left_data_dir;
34 | const std::string right_data_dir = dataset_dir_ + "/" + default_right_data_dir;
35 |
36 | ROS_INFO("saving %s", left_bag_file.c_str());
37 | Convert(stamp_file, left_data_dir, left_bag_file.string(), left_topic_, "/stereo/left");
38 | ROS_INFO("done saving %s", left_bag_file.c_str());
39 | ROS_INFO("saving %s", right_bag_file.c_str());
40 | Convert(stamp_file, right_data_dir, right_bag_file.string(), right_topic_, "/stereo/right");
41 | ROS_INFO("done saving %s", right_bag_file.c_str());
42 |
43 | return 0;
44 | }
45 |
46 | void StereoConverter::Convert(const std::string& stamp_file, const std::string& data_dir, const std::string& bag_file,
47 | const std::string& topic, const std::string& frame_id) {
48 | rosbag::Bag bag(bag_file, rosbag::bagmode::Write);
49 | bag.setChunkThreshold(768*1024);
50 | bag.setCompression(rosbag::compression::BZ2);
51 |
52 | FILE* fp = fopen(stamp_file.c_str(), "r");
53 | int64_t stamp;
54 | std::vector all_stamps;
55 | while (fscanf(fp, "%ld\n", &stamp) == 1) {
56 | all_stamps.push_back(stamp);
57 | }
58 | fclose(fp);
59 |
60 | size_t total = all_stamps.size();
61 | for (size_t i = 0; i < all_stamps.size(); ++i) {
62 | std::string st = std::to_string(all_stamps[i]);
63 | std::string frame_file = data_dir + "/" + st + ".png";
64 | ROS_INFO("converting %s\n", frame_file.c_str());
65 | if (!boost::filesystem::exists(frame_file)) {
66 | ROS_WARN("%s not exist\n", frame_file.c_str());
67 | continue;
68 | }
69 | cv::Mat img = cv::imread(frame_file, CV_LOAD_IMAGE_ANYDEPTH);
70 | cv_bridge::CvImage img_msg;
71 | img_msg.header.stamp.fromNSec(all_stamps[i]);
72 | img_msg.header.frame_id = frame_id;
73 | img_msg.encoding = sensor_msgs::image_encodings::BAYER_BGGR8;
74 | img_msg.image = img;
75 | sensor_msgs::Image msg;
76 | img_msg.toImageMsg(msg);
77 | bag.write(topic, msg.header.stamp, msg);
78 |
79 | ROS_INFO("done converting %s\n", frame_file.c_str());
80 | ROS_INFO("total %lu, already convert %lu, remain %lu\n", total, i + 1, total - i - 1);
81 | }
82 | bag.close();
83 | }
84 |
85 | } // namespace kaist2bag
--------------------------------------------------------------------------------
/src/velodyne_converter.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/25/21.
3 | //
4 |
5 | #include "velodyne_converter.h"
6 |
7 | #include
8 | #include
9 | #include
10 | #include
11 | #include
12 | #include
13 |
14 | namespace kaist2bag {
15 |
16 | VelodyneConverter::VelodyneConverter(const std::string &dataset_dir, const std::string &save_dir,
17 | const std::string &left_topic, const std::string& right_topic)
18 | : Converter(dataset_dir, save_dir), left_topic_(left_topic), right_topic_(right_topic) {
19 | left_bag_name_ = FilterSlash(left_topic_) + ".bag";
20 | right_bag_name_ = FilterSlash(right_topic_) + ".bag";
21 | }
22 |
23 | int VelodyneConverter::Convert() {
24 | CheckAndCreateSaveDir();
25 |
26 | boost::filesystem::path left_bag_file = boost::filesystem::path(save_dir_) / left_bag_name_;
27 | boost::filesystem::path right_bag_file = boost::filesystem::path(save_dir_) / right_bag_name_;
28 |
29 | const std::string left_stamp_file = dataset_dir_ + "/" + default_left_stamp_file;
30 | const std::string left_data_dir = dataset_dir_ + "/" + default_left_data_dir;
31 | const std::string right_stamp_file = dataset_dir_ + "/" + default_right_stamp_file;
32 | const std::string right_data_dir = dataset_dir_ + "/" + default_right_data_dir;
33 |
34 | ROS_INFO("saving %s", left_bag_file.c_str());
35 | Convert(left_stamp_file, left_data_dir, left_bag_file.string(), left_topic_, "left_velodyne");
36 | ROS_INFO("done saving %s", left_bag_file.c_str());
37 | ROS_INFO("saving %s", right_bag_file.c_str());
38 | Convert(right_stamp_file, right_data_dir, right_bag_file.string(), right_topic_, "right_velodyne");
39 | ROS_INFO("done saving %s", right_bag_file.c_str());
40 |
41 | return 0;
42 | }
43 |
44 | void VelodyneConverter::Convert(const std::string& stamp_file, const std::string& data_dir, const std::string& bag_file,
45 | const std::string& topic, const std::string& frame_id) {
46 | rosbag::Bag bag(bag_file, rosbag::bagmode::Write);
47 | bag.setChunkThreshold(768*1024);
48 | bag.setCompression(rosbag::compression::BZ2);
49 |
50 | FILE* fp = fopen(stamp_file.c_str(), "r");
51 | int64_t stamp;
52 | std::vector all_stamps;
53 | while (fscanf(fp, "%ld\n", &stamp) == 1) {
54 | all_stamps.push_back(stamp);
55 | }
56 | fclose(fp);
57 |
58 | size_t total = all_stamps.size();
59 | for (size_t i = 0; i < all_stamps.size(); ++i) {
60 | std::string st = std::to_string(all_stamps[i]);
61 | std::string frame_file = data_dir + "/" + st + ".bin";
62 | ROS_INFO("converting %s\n", frame_file.c_str());
63 | if (!boost::filesystem::exists(frame_file)) {
64 | ROS_WARN("%s not exist\n", frame_file.c_str());
65 | continue;
66 | }
67 | std::ifstream file;
68 | file.open(frame_file, std::ios::in | std::ios::binary);
69 | pcl::PointCloud pcl_cloud;
70 | while (!file.eof()) {
71 | pcl::PointXYZI point;
72 | file.read(reinterpret_cast(&point.x), sizeof(float));
73 | file.read(reinterpret_cast(&point.y), sizeof(float));
74 | file.read(reinterpret_cast(&point.z), sizeof(float));
75 | file.read(reinterpret_cast(&point.intensity), sizeof(float));
76 | pcl_cloud.points.push_back(point);
77 | }
78 | file.close();
79 | sensor_msgs::PointCloud2 cloud;
80 | pcl::toROSMsg(pcl_cloud, cloud);
81 | cloud.header.stamp.fromNSec(all_stamps[i]);
82 | cloud.header.frame_id = frame_id;
83 | bag.write(topic, cloud.header.stamp, cloud);
84 | ROS_INFO("bag write %s, %u points\n", topic.c_str(), cloud.height * cloud.width);
85 | ROS_INFO("done converting %s\n", frame_file.c_str());
86 | ROS_INFO("total %lu, already convert %lu, remain %lu\n", total, i + 1, total - i - 1);
87 | }
88 | bag.close();
89 | }
90 |
91 | } // namespace kaist2bag
--------------------------------------------------------------------------------
/src/sick_converter.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/28/21.
3 | //
4 |
5 | #include "sick_converter.h"
6 |
7 | #include
8 | #include
9 | #include
10 | #include
11 |
12 | namespace kaist2bag {
13 |
14 | SickConverter::SickConverter(const std::string &dataset_dir, const std::string &save_dir,
15 | const std::string &back_topic, const std::string& middle_topic)
16 | : Converter(dataset_dir, save_dir), back_topic_(back_topic), middle_topic_(middle_topic) {
17 | back_bag_name_ = FilterSlash(back_topic_) + ".bag";
18 | middle_bag_name_ = FilterSlash(middle_topic_) + ".bag";
19 | }
20 |
21 | int SickConverter::Convert() {
22 | CheckAndCreateSaveDir();
23 |
24 | boost::filesystem::path back_bag_file = boost::filesystem::path(save_dir_) / back_bag_name_;
25 | boost::filesystem::path middle_bag_file = boost::filesystem::path(save_dir_) / middle_bag_name_;
26 |
27 | const std::string back_stamp_file = dataset_dir_ + "/" + default_back_stamp_file;
28 | const std::string back_data_dir = dataset_dir_ + "/" + default_back_data_dir;
29 | const std::string middle_stamp_file = dataset_dir_ + "/" + default_middle_stamp_file;
30 | const std::string middle_data_dir = dataset_dir_ + "/" + default_middle_data_dir;
31 |
32 | ROS_INFO("saving %s", back_bag_file.c_str());
33 | Convert(back_stamp_file, back_data_dir, back_bag_file.string(), back_topic_, "back_sick");
34 | ROS_INFO("done saving %s", back_bag_file.c_str());
35 | ROS_INFO("saving %s", middle_bag_file.c_str());
36 | Convert(middle_stamp_file, middle_data_dir, middle_bag_file.string(), middle_topic_, "middle_sick");
37 | ROS_INFO("done saving %s", middle_bag_file.c_str());
38 |
39 | return 0;
40 | }
41 |
42 | void SickConverter::Convert(const std::string& stamp_file, const std::string& data_dir, const std::string& bag_file,
43 | const std::string& topic, const std::string& frame_id) {
44 | rosbag::Bag bag(bag_file, rosbag::bagmode::Write);
45 | bag.setChunkThreshold(768*1024);
46 | bag.setCompression(rosbag::compression::BZ2);
47 |
48 | FILE* fp = fopen(stamp_file.c_str(), "r");
49 | int64_t stamp;
50 | std::vector all_stamps;
51 | while (fscanf(fp, "%ld\n", &stamp) == 1) {
52 | all_stamps.push_back(stamp);
53 | }
54 | fclose(fp);
55 |
56 | size_t total = all_stamps.size();
57 | for (size_t i = 0; i < all_stamps.size(); ++i) {
58 | std::string st = std::to_string(all_stamps[i]);
59 | std::string frame_file = data_dir + "/" + st + ".bin";
60 | ROS_INFO("converting %s\n", frame_file.c_str());
61 | if (!boost::filesystem::exists(frame_file)) {
62 | ROS_WARN("%s not exist\n", frame_file.c_str());
63 | continue;
64 | }
65 | std::ifstream file;
66 | file.open(frame_file, std::ios::in | std::ios::binary);
67 | irp_sen_msgs::LaserScanArray scan_array;
68 | sensor_msgs::LaserScan scan;
69 | while (!file.eof()) {
70 | float range;
71 | float intensity;
72 | file.read(reinterpret_cast(&range), sizeof(float));
73 | file.read(reinterpret_cast(&intensity), sizeof(float));
74 | scan.ranges.push_back(range);
75 | scan.intensities.push_back((intensity));
76 | }
77 | file.close();
78 | scan.header.stamp.fromNSec(all_stamps[i]);
79 | scan.header.frame_id = frame_id;
80 | scan.angle_min = -1.65806281567;
81 | scan.angle_max = -1.65806281567;
82 | scan.angle_increment = 0.0116355288774;
83 | scan.time_increment = 0.0;
84 | scan.range_min = 0.0;
85 | scan.range_max = 81.0;
86 | scan_array.LaserScans.push_back(scan);
87 | scan_array.size = scan_array.LaserScans.size();
88 |
89 | scan_array.header.stamp.fromNSec(all_stamps[i]);
90 | scan_array.header.frame_id = "back_sick";
91 | bag.write(topic, scan_array.header.stamp, scan_array);
92 | ROS_INFO("done converting %s\n", frame_file.c_str());
93 | ROS_INFO("total %lu, already convert %lu, remain %lu\n", total, i + 1, total - i - 1);
94 | }
95 | bag.close();
96 | }
97 |
98 | } // namespace kaist2bag
--------------------------------------------------------------------------------
/src/encoder_converter.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/21/21.
3 | //
4 |
5 | #include "encoder_converter.h"
6 |
7 | #include
8 | #include
9 | #include
10 | #include
11 |
12 | namespace kaist2bag {
13 |
14 |
15 | EncoderConverter::EncoderConverter(const std::string &dataset_dir, const std::string &save_dir,
16 | const std::string &irp_topic, const std::string &raw_topic)
17 | : Converter(dataset_dir, save_dir), irp_topic_(irp_topic), raw_topic_(raw_topic) {
18 | irp_bag_name_ = FilterSlash(irp_topic_) + ".bag";
19 | raw_bag_name_ = FilterSlash(raw_topic_) + ".bag";
20 | }
21 |
22 | int EncoderConverter::Convert() {
23 | CheckAndCreateSaveDir();
24 |
25 | boost::filesystem::path irp_bag_file = boost::filesystem::path(save_dir_) / irp_bag_name_;
26 | boost::filesystem::path raw_bag_file = boost::filesystem::path(save_dir_) / raw_bag_name_;
27 | rosbag::Bag irp_bag(irp_bag_file.string(), rosbag::bagmode::Write);
28 | rosbag::Bag raw_bag(raw_bag_file.string(), rosbag::bagmode::Write);
29 | ROS_INFO("saving %s", irp_bag_file.c_str());
30 | ROS_INFO("saving %s", raw_bag_file.c_str());
31 |
32 | sensor_msgs::JointState joint_data;
33 | joint_data.name.push_back("front_left_wheel_joint");
34 | joint_data.name.push_back("front_right_wheel_joint");
35 | joint_data.name.push_back("back_left_wheel_joint");
36 | joint_data.name.push_back("back_right_wheel_joint");
37 | joint_data.position.push_back(0.0);
38 | joint_data.position.push_back(0.0);
39 | joint_data.position.push_back(0.0);
40 | joint_data.position.push_back(0.0);
41 | joint_data.velocity.push_back(0.0);
42 | joint_data.velocity.push_back(0.0);
43 | joint_data.velocity.push_back(0.0);
44 | joint_data.velocity.push_back(0.0);
45 | bool has_previous = false;
46 | int64_t pre_stamp, pre_left_count, pre_right_count;
47 |
48 | int encoder_resolution_ = 0;
49 | double encoder_left_diameter_ = 0.0;
50 | double encoder_right_diameter_ = 0.0;
51 | double encoder_wheel_base_ = 0.0;
52 | const std::string calib_file = dataset_dir_ + "/" + default_calib_file;
53 | std::ifstream file(calib_file.c_str());
54 | std::string str;
55 | while (std::getline(file, str)) {
56 | std::vector strs;
57 | boost::split(strs, str, boost::is_any_of(" "));
58 | if(!strs[1].compare("resolution:")){
59 | encoder_resolution_ = std::stoi(strs[2]);
60 | }
61 | if(!strs[1].compare("left")){
62 | encoder_left_diameter_ = std::stod(strs[4]);
63 | }
64 | if(!strs[1].compare("right")){
65 | encoder_right_diameter_ = std::stod(strs[4]);
66 | }
67 | if(!strs[1].compare("wheel")){
68 | encoder_wheel_base_ = std::stod(strs[3]);
69 | }
70 | }
71 |
72 | const std::string data_file = dataset_dir_ + "/" + default_data_file;
73 | FILE* fp = fopen(data_file.c_str(), "r");
74 | irp_sen_msgs::encoder encoder_data;
75 | int64_t stamp, left_count, right_count;
76 | while (fscanf(fp, "%ld,%ld,%ld\n", &stamp, &left_count, &right_count) == 3) {
77 | encoder_data.header.stamp.fromNSec(stamp);
78 | encoder_data.header.frame_id = "encoder";
79 | encoder_data.left_count = left_count;
80 | encoder_data.right_count = right_count;
81 | irp_bag.write(irp_topic_, encoder_data.header.stamp, encoder_data);
82 |
83 | if(has_previous) {
84 |
85 | double stamp_diff = 1e-9 * static_cast(stamp - pre_stamp);
86 | int64_t d_left_cnt = left_count - pre_left_count;
87 | int64_t d_right_cnt = right_count - pre_right_count;
88 | double degl = ((double)d_left_cnt/(double)encoder_resolution_) * 2 * M_PI;
89 | double degr = ((double)d_right_cnt/(double)encoder_resolution_) * 2 * M_PI;
90 | double wl = degl / stamp_diff;
91 | double wr = degr / stamp_diff;
92 |
93 | joint_data.header.stamp.fromNSec(stamp);
94 | joint_data.header.frame_id = "encoder";
95 | joint_data.position[0] += degl;
96 | joint_data.position[1] += degr;
97 | joint_data.position[2] += degl;
98 | joint_data.position[3] += degr;
99 | joint_data.velocity[0] = wl;
100 | joint_data.velocity[1] = wr;
101 | joint_data.velocity[2] = wl;
102 | joint_data.velocity[3] = wr;
103 | raw_bag.write(raw_topic_, joint_data.header.stamp, joint_data);
104 |
105 | }
106 | has_previous = true;
107 | pre_stamp = stamp;
108 | pre_left_count = left_count;
109 | pre_right_count = right_count;
110 |
111 | }
112 | irp_bag.close();
113 | raw_bag.close();
114 | fclose(fp);
115 | ROS_INFO("done saving %s", irp_bag_file.c_str());
116 | ROS_INFO("done saving %s", raw_bag_file.c_str());
117 |
118 | return 0;
119 | }
120 | } // namespace kaist2bag
121 |
122 |
--------------------------------------------------------------------------------
/src/main.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 | #include
4 | #include "altimeter_converter.h"
5 | #include "encoder_converter.h"
6 | #include "fog_converter.h"
7 | #include "gps_converter.h"
8 | #include "vrs_converter.h"
9 | #include "imu_converter.h"
10 | #include "velodyne_converter.h"
11 | #include "sick_converter.h"
12 | #include "stereo_converter.h"
13 |
14 | using namespace kaist2bag;
15 |
16 | enum SensorType {
17 | kAltimeter = 0,
18 | kEncoder,
19 | kFog,
20 | kGps,
21 | kVrs,
22 | kImu,
23 | kVelodyne,
24 | kSick,
25 | kStereo,
26 | kSensorTypeCount
27 | };
28 |
29 | int main(int argc, char** argv) {
30 | ros::init(argc, argv, "kaist2bag");
31 |
32 | ros::NodeHandle nh;
33 | std::vector sensors(kSensorTypeCount, false);
34 | std::vector sensor_names = {
35 | "altimeter",
36 | "encoder",
37 | "fog",
38 | "gps",
39 | "vrs",
40 | "imu",
41 | "velodyne",
42 | "sick",
43 | "stereo"
44 | };
45 |
46 | for (size_t i = 0; i < sensors.size(); ++i) {
47 | bool sensor_on = false;
48 | nh.getParam(sensor_names[i], sensor_on);
49 | sensors[i] = sensor_on;
50 | }
51 |
52 | std::string dataset;
53 | nh.getParam("dataset", dataset);
54 | std::string save_to;
55 | nh.getParam("save_to", save_to);
56 | double t0 = ros::Time::now().toSec();
57 |
58 |
59 | if(sensors[SensorType::kAltimeter]) {
60 | std::string altimeter_topic;
61 | nh.getParam("altimeter_topic", altimeter_topic);
62 | AltimeterConverter altimeter(dataset, save_to, altimeter_topic);
63 | altimeter.Convert();
64 | }
65 | double t1 = ros::Time::now().toSec();
66 | double altimeter_cost = t1 - t0;
67 |
68 |
69 | if(sensors[SensorType::kEncoder]) {
70 | std::string encoder_irp_topic, encoder_raw_topic;
71 | nh.getParam("encoder_irp_topic", encoder_irp_topic);
72 | nh.getParam("encoder_raw_topic", encoder_raw_topic);
73 | EncoderConverter encoder(dataset, save_to, encoder_irp_topic, encoder_raw_topic);
74 | encoder.Convert();
75 | }
76 | double t2 = ros::Time::now().toSec();
77 | double encoder_cost = t2 - t1;
78 |
79 |
80 | if(sensors[SensorType::kFog]) {
81 | std::string fog_topic;
82 | nh.getParam("fog_topic", fog_topic);
83 | FogConverter fog(dataset, save_to, fog_topic);
84 | fog.Convert();
85 | }
86 | double t3 = ros::Time::now().toSec();
87 | double fog_cost = t3 - t2;
88 |
89 |
90 | if(sensors[SensorType::kGps]) {
91 | std::string gps_topic;
92 | nh.getParam("gps_topic", gps_topic);
93 | GpsConverter gps(dataset, save_to, gps_topic);
94 | gps.Convert();
95 | }
96 | double t4 = ros::Time::now().toSec();
97 | double gps_cost = t4 - t3;
98 |
99 |
100 | if(sensors[SensorType::kVrs]) {
101 | std::string vrs_topic;
102 | nh.getParam("vrs_topic", vrs_topic);
103 | VrsConverter vrs(dataset, save_to, vrs_topic);
104 | vrs.Convert();
105 | }
106 | double t5 = ros::Time::now().toSec();
107 | double vrs_cost = t5 - t4;
108 |
109 |
110 | if(sensors[SensorType::kImu]) {
111 | std::string irp_topic, raw_topic, mag_topic;
112 | nh.getParam("imu_irp_topic", irp_topic);
113 | nh.getParam("imu_raw_topic", raw_topic);
114 | nh.getParam("imu_mag_topic", mag_topic);
115 | ImuConverter imu(dataset, save_to, irp_topic, raw_topic, mag_topic);
116 | imu.Convert();
117 | }
118 | double t6 = ros::Time::now().toSec();
119 | double imu_cost = t6 - t5;
120 |
121 |
122 | if(sensors[SensorType::kVelodyne]) {
123 | std::string vlp_left_topic, vlp_right_topic;
124 | nh.getParam("velodyne_left_topic", vlp_left_topic);
125 | nh.getParam("velodyne_right_topic", vlp_right_topic);
126 | VelodyneConverter vlp(dataset, save_to, vlp_left_topic, vlp_right_topic);
127 | vlp.Convert();
128 | }
129 | double t7 = ros::Time::now().toSec();
130 | double velodyne_cost = t7 - t6;
131 |
132 |
133 | if(sensors[SensorType::kSick]) {
134 | std::string sick_back_topic, sick_middle_topic;
135 | nh.getParam("sick_back_topic", sick_back_topic);
136 | nh.getParam("sick_middle_topic", sick_middle_topic);
137 | SickConverter sick(dataset, save_to, sick_back_topic, sick_middle_topic);
138 | sick.Convert();
139 | }
140 | double t8 = ros::Time::now().toSec();
141 | double sick_cost = t8 - t7;
142 |
143 |
144 | if(sensors[SensorType::kStereo]) {
145 | std::string stereo_left_topic, stereo_right_topic;
146 | nh.getParam("stereo_left_topic", stereo_left_topic);
147 | nh.getParam("stereo_right_topic", stereo_right_topic);
148 | StereoConverter stereo(dataset, save_to, stereo_left_topic, stereo_right_topic);
149 | stereo.Convert();
150 | }
151 | double t9 = ros::Time::now().toSec();
152 | double stereo_cost = t9 - t8;
153 |
154 |
155 | double all_cost = t9 - t0;
156 | ROS_INFO("altimeter_cost %f\n", altimeter_cost);
157 | ROS_INFO("encoder_cost %f\n", encoder_cost);
158 | ROS_INFO("fog_cost %f\n", fog_cost);
159 | ROS_INFO("gps_cost %f\n", gps_cost);
160 | ROS_INFO("vrs_cost %f\n", vrs_cost);
161 | ROS_INFO("imu_cost %f\n", imu_cost);
162 | ROS_INFO("velodyne_cost %f\n", velodyne_cost);
163 | ROS_INFO("sick_cost %f\n", sick_cost);
164 | ROS_INFO("stereo_cost %f\n", stereo_cost);
165 | ROS_INFO("all_cost %f\n", all_cost);
166 |
167 | return 0;
168 | }
--------------------------------------------------------------------------------
/src/imu_converter.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by tao on 7/24/21.
3 | //
4 |
5 | #include "imu_converter.h"
6 |
7 | #include
8 | #include
9 | #include
10 | #include
11 | #include
12 |
13 | namespace kaist2bag {
14 |
15 | ImuConverter::ImuConverter(const std::string& dataset_dir, const std::string& save_dir,
16 | const std::string& irp_topic, const std::string& raw_topic,
17 | const std::string& mag_topic)
18 | : Converter(dataset_dir, save_dir), irp_topic_(irp_topic), raw_topic_(raw_topic),
19 | mag_topic_(mag_topic) {
20 | irp_bag_name_ = FilterSlash(irp_topic_) + ".bag";
21 | raw_bag_name_ = FilterSlash(raw_topic_) + ".bag";
22 | mag_bag_name_ = FilterSlash(mag_topic_) + ".bag";
23 | }
24 |
25 | int ImuConverter::Convert() {
26 | CheckAndCreateSaveDir();
27 |
28 | boost::filesystem::path irp_bag_file = boost::filesystem::path(save_dir_) / irp_bag_name_;
29 | boost::filesystem::path raw_bag_file = boost::filesystem::path(save_dir_) / raw_bag_name_;
30 | boost::filesystem::path mag_bag_file = boost::filesystem::path(save_dir_) / mag_bag_name_;
31 | rosbag::Bag irp_bag(irp_bag_file.string(), rosbag::bagmode::Write);
32 | rosbag::Bag raw_bag(raw_bag_file.string(), rosbag::bagmode::Write);
33 |
34 | rosbag::Bag mag_bag;
35 | bool mag_bag_opened = false;
36 |
37 | ROS_INFO("saving %s", irp_bag_file.c_str());
38 | ROS_INFO("saving %s", raw_bag_file.c_str());
39 |
40 |
41 | const std::string data_file = dataset_dir_ + "/" + default_data_file;
42 | FILE* fp = fopen(data_file.c_str(), "r");
43 | irp_sen_msgs::imu irp_imu;
44 | sensor_msgs::Imu sensor_msgs_imu;
45 | sensor_msgs::MagneticField sensor_msgs_mag;
46 |
47 | int64_t stamp;
48 | double q_x,q_y,q_z,q_w,x,y,z,g_x,g_y,g_z,a_x,a_y,a_z,m_x,m_y,m_z;
49 | while (1){
50 |
51 | int length = fscanf(fp,"%ld,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf\n",
52 | &stamp,&q_x,&q_y,&q_z,&q_w,&x,&y,&z,&g_x,&g_y,&g_z,&a_x,&a_y,&a_z,&m_x,&m_y,&m_z);
53 |
54 | if(length != 8 && length != 17) break;
55 |
56 |
57 | irp_imu.header.stamp.fromNSec(stamp);
58 | irp_imu.header.frame_id = "imu";
59 | irp_imu.quaternion_data.x = q_x;
60 | irp_imu.quaternion_data.y = q_y;
61 | irp_imu.quaternion_data.z = q_z;
62 | irp_imu.quaternion_data.w = q_w;
63 | irp_imu.eular_data.x = x;
64 | irp_imu.eular_data.y = y;
65 | irp_imu.eular_data.z = z;
66 |
67 | if(length > 8)
68 | {
69 | irp_imu.gyro_data.x = g_x;
70 | irp_imu.gyro_data.y = g_y;
71 | irp_imu.gyro_data.z = g_z;
72 | irp_imu.acceleration_data.x = a_x;
73 | irp_imu.acceleration_data.y = a_y;
74 | irp_imu.acceleration_data.z = a_z;
75 | irp_imu.magneticfield_data.x = m_x;
76 | irp_imu.magneticfield_data.y = m_y;
77 | irp_imu.magneticfield_data.z = m_z;
78 | }
79 |
80 |
81 | sensor_msgs_imu.header.stamp.fromNSec(stamp);
82 | sensor_msgs_imu.header.frame_id = "imu";
83 | sensor_msgs_imu.orientation.x = q_x;
84 | sensor_msgs_imu.orientation.y = q_y;
85 | sensor_msgs_imu.orientation.z = q_z;
86 | sensor_msgs_imu.orientation.w = q_w;
87 | sensor_msgs_imu.orientation_covariance[0] = 3;
88 | sensor_msgs_imu.orientation_covariance[4] = 3;
89 | sensor_msgs_imu.orientation_covariance[8] = 3;
90 |
91 | if(length > 8)
92 | {
93 | sensor_msgs_imu.angular_velocity.x = g_x;
94 | sensor_msgs_imu.angular_velocity.y = g_y;
95 | sensor_msgs_imu.angular_velocity.z = g_z;
96 | sensor_msgs_imu.angular_velocity_covariance[0] = 3;
97 | sensor_msgs_imu.angular_velocity_covariance[4] = 3;
98 | sensor_msgs_imu.angular_velocity_covariance[8] = 3;
99 | sensor_msgs_imu.linear_acceleration.x = a_x;
100 | sensor_msgs_imu.linear_acceleration.y = a_y;
101 | sensor_msgs_imu.linear_acceleration.z = a_z;
102 | sensor_msgs_imu.linear_acceleration_covariance[0] = 3;
103 | sensor_msgs_imu.linear_acceleration_covariance[4] = 3;
104 | sensor_msgs_imu.linear_acceleration_covariance[8] = 3;
105 |
106 | sensor_msgs_mag.header.stamp.fromNSec(stamp);
107 | sensor_msgs_mag.header.frame_id = "imu";
108 | sensor_msgs_mag.magnetic_field.x = m_x;
109 | sensor_msgs_mag.magnetic_field.y = m_y;
110 | sensor_msgs_mag.magnetic_field.z = m_z;
111 | }
112 |
113 |
114 | irp_bag.write(irp_topic_, irp_imu.header.stamp, irp_imu);
115 | raw_bag.write(raw_topic_, sensor_msgs_imu.header.stamp, sensor_msgs_imu);
116 | if(length > 8)
117 | {
118 | if(!mag_bag_opened)
119 | {
120 | ROS_INFO("saving %s", mag_bag_file.c_str());
121 | mag_bag.open(mag_bag_file.string(), rosbag::bagmode::Write);
122 | mag_bag_opened = true;
123 | }
124 | mag_bag.write(mag_topic_, sensor_msgs_mag.header.stamp, sensor_msgs_mag);
125 | }
126 | }
127 | irp_bag.close();
128 | raw_bag.close();
129 | if(mag_bag_opened)
130 | {
131 | mag_bag.close();
132 | mag_bag_opened = false;
133 | }
134 |
135 | fclose(fp);
136 | ROS_INFO("done saving %s", irp_bag_file.c_str());
137 | ROS_INFO("done saving %s", raw_bag_file.c_str());
138 | ROS_INFO("done saving %s", mag_bag_file.c_str());
139 |
140 | return 0;
141 | }
142 |
143 | } // namespace kaist2bag
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.0.2)
2 | project(kaist2bag)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | add_compile_options(-std=c++14)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | roscpp
12 | rospy
13 | std_msgs
14 | geometry_msgs
15 | message_generation
16 | rosbag
17 | image_transport
18 | cv_bridge
19 | pcl_ros
20 | pcl_conversions
21 | pcl_msgs
22 | irp_sen_msgs
23 | tf
24 | )
25 |
26 | find_package(Boost REQUIRED COMPONENTS
27 | filesystem)
28 |
29 | ## System dependencies are found with CMake's conventions
30 | # find_package(Boost REQUIRED COMPONENTS system)
31 |
32 |
33 | ## Uncomment this if the package has a setup.py. This macro ensures
34 | ## modules and global scripts declared therein get installed
35 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
36 | # catkin_python_setup()
37 |
38 | ################################################
39 | ## Declare ROS messages, services and actions ##
40 | ################################################
41 |
42 | ## To declare and build messages, services or actions from within this
43 | ## package, follow these steps:
44 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
45 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
46 | ## * In the file package.xml:
47 | ## * add a build_depend tag for "message_generation"
48 | ## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
49 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
50 | ## but can be declared for certainty nonetheless:
51 | ## * add a exec_depend tag for "message_runtime"
52 | ## * In this file (CMakeLists.txt):
53 | ## * add "message_generation" and every package in MSG_DEP_SET to
54 | ## find_package(catkin REQUIRED COMPONENTS ...)
55 | ## * add "message_runtime" and every package in MSG_DEP_SET to
56 | ## catkin_package(CATKIN_DEPENDS ...)
57 | ## * uncomment the add_*_files sections below as needed
58 | ## and list every .msg/.srv/.action file to be processed
59 | ## * uncomment the generate_messages entry below
60 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
61 |
62 | ## Generate messages in the 'msg' folder
63 | # add_message_files(
64 | # FILES
65 | # Message1.msg
66 | # Message2.msg
67 | # )
68 |
69 | ## Generate services in the 'srv' folder
70 | # add_service_files(
71 | # FILES
72 | # Service1.srv
73 | # Service2.srv
74 | # )
75 |
76 | ## Generate actions in the 'action' folder
77 | # add_action_files(
78 | # FILES
79 | # Action1.action
80 | # Action2.action
81 | # )
82 |
83 | ## Generate added messages and services with any dependencies listed here
84 | # generate_messages(
85 | # DEPENDENCIES
86 | # std_msgs
87 | # )
88 |
89 | ################################################
90 | ## Declare ROS dynamic reconfigure parameters ##
91 | ################################################
92 |
93 | ## To declare and build dynamic reconfigure parameters within this
94 | ## package, follow these steps:
95 | ## * In the file package.xml:
96 | ## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
97 | ## * In this file (CMakeLists.txt):
98 | ## * add "dynamic_reconfigure" to
99 | ## find_package(catkin REQUIRED COMPONENTS ...)
100 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
101 | ## and list every .cfg file to be processed
102 |
103 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
104 | # generate_dynamic_reconfigure_options(
105 | # cfg/DynReconf1.cfg
106 | # cfg/DynReconf2.cfg
107 | # )
108 |
109 | ###################################
110 | ## catkin specific configuration ##
111 | ###################################
112 | ## The catkin_package macro generates cmake config files for your package
113 | ## Declare things to be passed to dependent projects
114 | ## INCLUDE_DIRS: uncomment this if your package contains header files
115 | ## LIBRARIES: libraries you create in this project that dependent projects also need
116 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
117 | ## DEPENDS: system dependencies of this project that dependent projects also need
118 | catkin_package(
119 | LIBRARIES kaist2bag
120 | CATKIN_DEPENDS
121 | roscpp
122 | rospy
123 | std_msgs
124 | geometry_msgs
125 | message_generation
126 | rosbag
127 | image_transport
128 | cv_bridge
129 | pcl_ros
130 | pcl_conversions
131 | pcl_msgs
132 | irp_sen_msgs
133 | tf
134 | # DEPENDS system_lib
135 | )
136 |
137 | ###########
138 | ## Build ##
139 | ###########
140 |
141 | ## Specify additional locations of header files
142 | ## Your package locations should be listed before other locations
143 | include_directories(
144 | ${catkin_INCLUDE_DIRS}
145 | ${Boost_INCLUDE_DIRS}
146 | )
147 |
148 | ## Declare a C++ library
149 | # add_library(${PROJECT_NAME}
150 | # src/${PROJECT_NAME}/kaist2bag.cpp
151 | # )
152 |
153 | ## Add cmake target dependencies of the library
154 | ## as an example, code may need to be generated before libraries
155 | ## either from message generation or dynamic reconfigure
156 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
157 |
158 | ## Declare a C++ executable
159 | ## With catkin_make all packages are built within a single CMake context
160 | ## The recommended prefix ensures that target names across packages don't collide
161 | add_executable(${PROJECT_NAME}
162 | src/main.cpp
163 | src/converter.cpp
164 | src/altimeter_converter.cpp
165 | src/encoder_converter.cpp
166 | src/fog_converter.cpp
167 | src/gps_converter.cpp
168 | src/vrs_converter.cpp
169 | src/imu_converter.cpp
170 | src/velodyne_converter.cpp
171 | src/sick_converter.cpp
172 | src/stereo_converter.cpp
173 | )
174 |
175 | ## Rename C++ executable without prefix
176 | ## The above recommended prefix causes long target names, the following renames the
177 | ## target back to the shorter version for ease of user use
178 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
179 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
180 |
181 | ## Add cmake target dependencies of the executable
182 | ## same as for the library above
183 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
184 |
185 | ## Specify libraries to link a library or executable target against
186 | target_link_libraries(${PROJECT_NAME}
187 | ${catkin_LIBRARIES}
188 | ${Boost_LIBRARIES}
189 | )
190 |
191 | #############
192 | ## Install ##
193 | #############
194 |
195 | # all install targets should use catkin DESTINATION variables
196 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
197 |
198 | ## Mark executable scripts (Python etc.) for installation
199 | ## in contrast to setup.py, you can choose the destination
200 | catkin_install_python(PROGRAMS
201 | scripts/mergebag.py
202 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
203 | )
204 |
205 | ## Mark executables for installation
206 | ## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
207 | # install(TARGETS ${PROJECT_NAME}_node
208 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
209 | # )
210 |
211 | ## Mark libraries for installation
212 | ## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
213 | # install(TARGETS ${PROJECT_NAME}
214 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
215 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
216 | # RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
217 | # )
218 |
219 | ## Mark cpp header files for installation
220 | # install(DIRECTORY include/${PROJECT_NAME}/
221 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
222 | # FILES_MATCHING PATTERN "*.h"
223 | # PATTERN ".svn" EXCLUDE
224 | # )
225 |
226 | ## Mark other files for installation (e.g. launch and bag files, etc.)
227 | # install(FILES
228 | # # myfile1
229 | # # myfile2
230 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
231 | # )
232 |
233 | #############
234 | ## Testing ##
235 | #############
236 |
237 | ## Add gtest based cpp test target and link libraries
238 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_kaist2bag.cpp)
239 | # if(TARGET ${PROJECT_NAME}-test)
240 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
241 | # endif()
242 |
243 | ## Add folders to be run by python nosetests
244 | # catkin_add_nosetests(test)
245 |
--------------------------------------------------------------------------------