├── .github
└── workflows
│ ├── humble.yml
│ ├── jazzy.yml
│ ├── kilted.yml
│ └── rolling.yml
├── CMakeLists.txt
├── LICENSE
├── README.md
├── package.xml
├── resources
├── gifs
│ ├── compressing_black.gif
│ ├── compressing_white.gif
│ ├── decompressing_black.gif
│ ├── decompressing_white.gif
│ ├── merging_black.gif
│ ├── merging_white.gif
│ ├── publishing_black.gif
│ ├── publishing_white.gif
│ ├── recording_black.gif
│ └── recording_white.gif
├── icons
│ ├── bag_info_black.svg
│ ├── bag_info_white.svg
│ ├── bag_to_images_black.svg
│ ├── bag_to_images_white.svg
│ ├── bag_to_pcd_black.svg
│ ├── bag_to_pcd_white.svg
│ ├── bag_to_video_black.svg
│ ├── bag_to_video_white.svg
│ ├── bag_tools_black.svg
│ ├── bag_tools_white.svg
│ ├── compress_bag_black.svg
│ ├── compress_bag_white.svg
│ ├── conversion_tools_black.svg
│ ├── conversion_tools_white.svg
│ ├── decompress_bag_black.svg
│ ├── decompress_bag_white.svg
│ ├── dummy_bag_black.svg
│ ├── dummy_bag_white.svg
│ ├── edit_bag_black.svg
│ ├── edit_bag_white.svg
│ ├── gear_black.svg
│ ├── gear_white.svg
│ ├── info_tools_black.svg
│ ├── info_tools_white.svg
│ ├── main.svg
│ ├── merge_bags_black.svg
│ ├── merge_bags_white.svg
│ ├── minus_black.svg
│ ├── minus_white.svg
│ ├── pcd_to_bag_black.svg
│ ├── pcd_to_bag_white.svg
│ ├── plus_black.svg
│ ├── plus_white.svg
│ ├── publish_images_black.svg
│ ├── publish_images_white.svg
│ ├── publish_video_black.svg
│ ├── publish_video_white.svg
│ ├── publishing_tools_black.svg
│ ├── publishing_tools_white.svg
│ ├── record_bag_black.svg
│ ├── record_bag_white.svg
│ ├── topics_services_info_black.svg
│ ├── topics_services_info_white.svg
│ ├── video_to_bag_black.svg
│ └── video_to_bag_white.svg
└── resources.qrc
├── src
├── CMakeLists.txt
├── cli
│ ├── BagToImages.cpp
│ ├── BagToPCDs.cpp
│ ├── BagToVideo.cpp
│ ├── CMakeLists.txt
│ ├── CompressBag.cpp
│ ├── DecompressBag.cpp
│ ├── DummyBag.cpp
│ ├── MergeBags.cpp
│ ├── PCDsToBag.cpp
│ ├── PublishImages.cpp
│ ├── PublishVideo.cpp
│ └── VideoToBag.cpp
├── main.cpp
├── ros
│ ├── CMakeLists.txt
│ └── thread
│ │ ├── BagToImagesThread.cpp
│ │ ├── BagToImagesThread.hpp
│ │ ├── BagToPCDsThread.cpp
│ │ ├── BagToPCDsThread.hpp
│ │ ├── BagToVideoThread.cpp
│ │ ├── BagToVideoThread.hpp
│ │ ├── BasicThread.cpp
│ │ ├── BasicThread.hpp
│ │ ├── CMakeLists.txt
│ │ ├── ChangeCompressionBagThread.cpp
│ │ ├── ChangeCompressionBagThread.hpp
│ │ ├── DummyBagThread.cpp
│ │ ├── DummyBagThread.hpp
│ │ ├── EditBagThread.cpp
│ │ ├── EditBagThread.hpp
│ │ ├── MergeBagsThread.cpp
│ │ ├── MergeBagsThread.hpp
│ │ ├── PCDsToBagThread.cpp
│ │ ├── PCDsToBagThread.hpp
│ │ ├── PublishImagesThread.cpp
│ │ ├── PublishImagesThread.hpp
│ │ ├── PublishVideoThread.cpp
│ │ ├── PublishVideoThread.hpp
│ │ ├── RecordBagThread.cpp
│ │ ├── RecordBagThread.hpp
│ │ ├── VideoToBagThread.cpp
│ │ └── VideoToBagThread.hpp
├── ui
│ ├── CMakeLists.txt
│ ├── HelperWidgets
│ │ ├── BasicBagWidget.cpp
│ │ ├── BasicBagWidget.hpp
│ │ ├── CMakeLists.txt
│ │ ├── MessageCountWidget.cpp
│ │ ├── MessageCountWidget.hpp
│ │ ├── TopicListingInputWidget.cpp
│ │ ├── TopicListingInputWidget.hpp
│ │ ├── TopicWidget.cpp
│ │ └── TopicWidget.hpp
│ ├── InputWidgets
│ │ ├── AdvancedInputWidget.cpp
│ │ ├── AdvancedInputWidget.hpp
│ │ ├── BagInfoWidget.cpp
│ │ ├── BagInfoWidget.hpp
│ │ ├── BagToImagesWidget.cpp
│ │ ├── BagToImagesWidget.hpp
│ │ ├── BagToPCDsWidget.cpp
│ │ ├── BagToPCDsWidget.hpp
│ │ ├── BagToVideoWidget.cpp
│ │ ├── BagToVideoWidget.hpp
│ │ ├── BasicInputWidget.cpp
│ │ ├── BasicInputWidget.hpp
│ │ ├── CMakeLists.txt
│ │ ├── ChangeCompressionWidget.cpp
│ │ ├── ChangeCompressionWidget.hpp
│ │ ├── DummyBagWidget.cpp
│ │ ├── DummyBagWidget.hpp
│ │ ├── EditBagWidget.cpp
│ │ ├── EditBagWidget.hpp
│ │ ├── MergeBagsWidget.cpp
│ │ ├── MergeBagsWidget.hpp
│ │ ├── PCDsToBagWidget.cpp
│ │ ├── PCDsToBagWidget.hpp
│ │ ├── PublishWidget.cpp
│ │ ├── PublishWidget.hpp
│ │ ├── RecordBagWidget.cpp
│ │ ├── RecordBagWidget.hpp
│ │ ├── TopicsServicesInfoWidget.cpp
│ │ ├── TopicsServicesInfoWidget.hpp
│ │ ├── VideoToBagWidget.cpp
│ │ └── VideoToBagWidget.hpp
│ ├── MainWindow.cpp
│ ├── MainWindow.hpp
│ ├── ProgressWidget.cpp
│ ├── ProgressWidget.hpp
│ ├── SettingsDialog.cpp
│ ├── SettingsDialog.hpp
│ ├── StartWidget.cpp
│ ├── StartWidget.hpp
│ └── settings
│ │ ├── CMakeLists.txt
│ │ ├── DialogSettings.cpp
│ │ ├── DialogSettings.hpp
│ │ ├── GeneralSettings.hpp
│ │ └── input
│ │ ├── AdvancedSettings.cpp
│ │ ├── AdvancedSettings.hpp
│ │ ├── BagToImagesSettings.cpp
│ │ ├── BagToImagesSettings.hpp
│ │ ├── BagToVideoSettings.cpp
│ │ ├── BagToVideoSettings.hpp
│ │ ├── BasicSettings.cpp
│ │ ├── BasicSettings.hpp
│ │ ├── CMakeLists.txt
│ │ ├── CompressBagSettings.cpp
│ │ ├── CompressBagSettings.hpp
│ │ ├── DeleteSourceSettings.cpp
│ │ ├── DeleteSourceSettings.hpp
│ │ ├── DummyBagSettings.cpp
│ │ ├── DummyBagSettings.hpp
│ │ ├── EditBagSettings.cpp
│ │ ├── EditBagSettings.hpp
│ │ ├── MergeBagsSettings.cpp
│ │ ├── MergeBagsSettings.hpp
│ │ ├── PCDsToBagSettings.cpp
│ │ ├── PCDsToBagSettings.hpp
│ │ ├── PublishSettings.cpp
│ │ ├── PublishSettings.hpp
│ │ ├── RGBSettings.cpp
│ │ ├── RGBSettings.hpp
│ │ ├── RecordBagSettings.cpp
│ │ ├── RecordBagSettings.hpp
│ │ ├── VideoSettings.cpp
│ │ ├── VideoSettings.hpp
│ │ ├── VideoToBagSettings.cpp
│ │ └── VideoToBagSettings.hpp
└── utils
│ ├── CMakeLists.txt
│ ├── Parameters.hpp
│ ├── UtilsCLI.cpp
│ ├── UtilsCLI.hpp
│ ├── UtilsROS.cpp
│ ├── UtilsROS.hpp
│ ├── UtilsUI.cpp
│ ├── UtilsUI.hpp
│ ├── VideoEncoder.cpp
│ └── VideoEncoder.hpp
├── test
├── CMakeLists.txt
├── main.cpp
├── ros
│ └── threads
│ │ └── ThreadsTest.cpp
├── ui
│ └── settings
│ │ └── SettingsTest.cpp
└── utils
│ ├── UtilsCLITest.cpp
│ ├── UtilsROSTest.cpp
│ └── UtilsUITest.cpp
└── uncrustify.cfg
/.github/workflows/humble.yml:
--------------------------------------------------------------------------------
1 | name: humble
2 |
3 | on: [push]
4 |
5 | env:
6 | BUILD_TYPE: Release
7 |
8 | jobs:
9 | run_humble:
10 | runs-on: ubuntu-22.04
11 | steps:
12 | - name: Checkout
13 | uses: actions/checkout@v3
14 |
15 | - uses: ros-tooling/setup-ros@v0.7
16 | with:
17 | required-ros-distributions: humble
18 |
19 | - name: Install dependencies
20 | run: sudo apt update && sudo apt install -y qt6-base-dev ros-humble-catch-ros2
21 |
22 | - name: Create workspace and copy repo there
23 | run: mkdir -p ros2_ws/src/ros2_utils_tool && cp -r resources src test CMakeLists.txt package.xml ros2_ws/src/ros2_utils_tool
24 |
25 | - name: Source ROS and build ws
26 | run: cd ros2_ws && source /opt/ros/humble/setup.bash && colcon build --packages-select ros2_utils_tool
27 |
28 | - name: Source ws and run tests
29 | run: cd ros2_ws && source install/setup.bash && ros2 run ros2_utils_tool tool_tests
30 |
--------------------------------------------------------------------------------
/.github/workflows/jazzy.yml:
--------------------------------------------------------------------------------
1 | name: jazzy
2 |
3 | on: [push]
4 |
5 | env:
6 | BUILD_TYPE: Release
7 |
8 | jobs:
9 | run_jazzy:
10 | runs-on: ubuntu-24.04
11 | steps:
12 | - name: Checkout
13 | uses: actions/checkout@v3
14 |
15 | - uses: ros-tooling/setup-ros@v0.7
16 | with:
17 | required-ros-distributions: jazzy
18 |
19 | - name: Install dependencies
20 | run: sudo apt update && sudo apt install -y qt6-base-dev ros-jazzy-catch-ros2
21 |
22 | - name: Create workspace and copy repo there
23 | run: mkdir -p ros2_ws/src/ros2_utils_tool && cp -r resources src test CMakeLists.txt package.xml ros2_ws/src/ros2_utils_tool
24 |
25 | - name: Source ROS and build ws
26 | run: cd ros2_ws && source /opt/ros/jazzy/setup.bash && colcon build --packages-select ros2_utils_tool
27 |
28 | - name: Source ws and run tests
29 | run: cd ros2_ws && source install/setup.bash && ros2 run ros2_utils_tool tool_tests
30 |
--------------------------------------------------------------------------------
/.github/workflows/kilted.yml:
--------------------------------------------------------------------------------
1 | name: kilted
2 |
3 | on: [push]
4 |
5 | env:
6 | BUILD_TYPE: Release
7 |
8 | jobs:
9 | run_kilted:
10 | runs-on: ubuntu-24.04
11 | steps:
12 | - name: Checkout
13 | uses: actions/checkout@v3
14 |
15 | - uses: ros-tooling/setup-ros@v0.7
16 | with:
17 | required-ros-distributions: kilted
18 |
19 | - name: Install dependencies
20 | run: sudo apt update && sudo apt install -y qt6-base-dev ros-kilted-catch-ros2
21 |
22 | - name: Create workspace and copy repo there
23 | run: mkdir -p ros2_ws/src/ros2_utils_tool && cp -r resources src test CMakeLists.txt package.xml ros2_ws/src/ros2_utils_tool
24 |
25 | - name: Source ROS and build ws
26 | run: cd ros2_ws && source /opt/ros/kilted/setup.bash && colcon build --packages-select ros2_utils_tool
27 |
28 | - name: Source ws and run tests
29 | run: cd ros2_ws && source install/setup.bash && ros2 run ros2_utils_tool tool_tests
30 |
--------------------------------------------------------------------------------
/.github/workflows/rolling.yml:
--------------------------------------------------------------------------------
1 | name: rolling
2 |
3 | on: [push]
4 |
5 | env:
6 | BUILD_TYPE: Release
7 |
8 | jobs:
9 | run_rolling:
10 | runs-on: ubuntu-latest
11 | steps:
12 | - name: Checkout
13 | uses: actions/checkout@v3
14 |
15 | - uses: ros-tooling/setup-ros@v0.7
16 | with:
17 | required-ros-distributions: rolling
18 |
19 | - name: Install dependencies
20 | run: sudo apt update && sudo apt install -y qt6-base-dev ros-rolling-catch-ros2
21 |
22 | - name: Create workspace and copy repo there
23 | run: mkdir -p ros2_ws/src/ros2_utils_tool && cp -r resources src test CMakeLists.txt package.xml ros2_ws/src/ros2_utils_tool
24 |
25 | - name: Source ROS and build ws
26 | run: cd ros2_ws && source /opt/ros/rolling/setup.bash && colcon build --packages-select ros2_utils_tool
27 |
28 | - name: Source ws and run tests
29 | run: cd ros2_ws && source install/setup.bash && ros2 run ros2_utils_tool tool_tests
30 |
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | ros2_utils_tool
4 | 0.12.0
5 | The ros2_utils_tool package
6 |
7 | maxime
8 | EUPLv1.2
9 |
10 | cv_bridge
11 | pcl_conversions
12 | rclcpp
13 | rosbag2_cpp
14 | rosbag2_transport
15 | sensor_msgs
16 |
17 | catch_ros2
18 |
19 | ament_cmake
20 |
21 |
22 | ament_cmake
23 |
24 |
25 |
--------------------------------------------------------------------------------
/resources/gifs/compressing_black.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MaxFleur/ros2_utils_tool/a8319f61815c23b5592ae2f76b1287e87e501a5e/resources/gifs/compressing_black.gif
--------------------------------------------------------------------------------
/resources/gifs/compressing_white.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MaxFleur/ros2_utils_tool/a8319f61815c23b5592ae2f76b1287e87e501a5e/resources/gifs/compressing_white.gif
--------------------------------------------------------------------------------
/resources/gifs/decompressing_black.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MaxFleur/ros2_utils_tool/a8319f61815c23b5592ae2f76b1287e87e501a5e/resources/gifs/decompressing_black.gif
--------------------------------------------------------------------------------
/resources/gifs/decompressing_white.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MaxFleur/ros2_utils_tool/a8319f61815c23b5592ae2f76b1287e87e501a5e/resources/gifs/decompressing_white.gif
--------------------------------------------------------------------------------
/resources/gifs/merging_black.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MaxFleur/ros2_utils_tool/a8319f61815c23b5592ae2f76b1287e87e501a5e/resources/gifs/merging_black.gif
--------------------------------------------------------------------------------
/resources/gifs/merging_white.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MaxFleur/ros2_utils_tool/a8319f61815c23b5592ae2f76b1287e87e501a5e/resources/gifs/merging_white.gif
--------------------------------------------------------------------------------
/resources/gifs/publishing_black.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MaxFleur/ros2_utils_tool/a8319f61815c23b5592ae2f76b1287e87e501a5e/resources/gifs/publishing_black.gif
--------------------------------------------------------------------------------
/resources/gifs/publishing_white.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MaxFleur/ros2_utils_tool/a8319f61815c23b5592ae2f76b1287e87e501a5e/resources/gifs/publishing_white.gif
--------------------------------------------------------------------------------
/resources/gifs/recording_black.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MaxFleur/ros2_utils_tool/a8319f61815c23b5592ae2f76b1287e87e501a5e/resources/gifs/recording_black.gif
--------------------------------------------------------------------------------
/resources/gifs/recording_white.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MaxFleur/ros2_utils_tool/a8319f61815c23b5592ae2f76b1287e87e501a5e/resources/gifs/recording_white.gif
--------------------------------------------------------------------------------
/resources/icons/bag_info_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
20 |
--------------------------------------------------------------------------------
/resources/icons/bag_info_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
20 |
--------------------------------------------------------------------------------
/resources/icons/bag_to_video_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
24 |
--------------------------------------------------------------------------------
/resources/icons/bag_to_video_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
24 |
--------------------------------------------------------------------------------
/resources/icons/bag_tools_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
15 |
--------------------------------------------------------------------------------
/resources/icons/bag_tools_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
15 |
--------------------------------------------------------------------------------
/resources/icons/compress_bag_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
19 |
--------------------------------------------------------------------------------
/resources/icons/compress_bag_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
19 |
--------------------------------------------------------------------------------
/resources/icons/decompress_bag_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
19 |
--------------------------------------------------------------------------------
/resources/icons/decompress_bag_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
19 |
--------------------------------------------------------------------------------
/resources/icons/dummy_bag_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
19 |
--------------------------------------------------------------------------------
/resources/icons/dummy_bag_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
19 |
--------------------------------------------------------------------------------
/resources/icons/edit_bag_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
30 |
--------------------------------------------------------------------------------
/resources/icons/edit_bag_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
30 |
--------------------------------------------------------------------------------
/resources/icons/gear_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
20 |
--------------------------------------------------------------------------------
/resources/icons/gear_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
20 |
--------------------------------------------------------------------------------
/resources/icons/info_tools_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
15 |
--------------------------------------------------------------------------------
/resources/icons/info_tools_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
15 |
--------------------------------------------------------------------------------
/resources/icons/main.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
26 |
--------------------------------------------------------------------------------
/resources/icons/merge_bags_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
24 |
--------------------------------------------------------------------------------
/resources/icons/merge_bags_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
24 |
--------------------------------------------------------------------------------
/resources/icons/minus_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
14 |
--------------------------------------------------------------------------------
/resources/icons/minus_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
14 |
--------------------------------------------------------------------------------
/resources/icons/plus_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
15 |
--------------------------------------------------------------------------------
/resources/icons/plus_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
15 |
--------------------------------------------------------------------------------
/resources/icons/publish_images_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
35 |
--------------------------------------------------------------------------------
/resources/icons/publish_images_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
35 |
--------------------------------------------------------------------------------
/resources/icons/publish_video_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
27 |
--------------------------------------------------------------------------------
/resources/icons/publish_video_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
27 |
--------------------------------------------------------------------------------
/resources/icons/publishing_tools_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
20 |
--------------------------------------------------------------------------------
/resources/icons/publishing_tools_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
20 |
--------------------------------------------------------------------------------
/resources/icons/record_bag_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
28 |
--------------------------------------------------------------------------------
/resources/icons/record_bag_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
28 |
--------------------------------------------------------------------------------
/resources/icons/topics_services_info_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
29 |
--------------------------------------------------------------------------------
/resources/icons/topics_services_info_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
29 |
--------------------------------------------------------------------------------
/resources/icons/video_to_bag_black.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
24 |
--------------------------------------------------------------------------------
/resources/icons/video_to_bag_white.svg:
--------------------------------------------------------------------------------
1 |
2 |
3 |
24 |
--------------------------------------------------------------------------------
/resources/resources.qrc:
--------------------------------------------------------------------------------
1 |
2 |
3 | gifs/compressing_black.gif
4 | gifs/compressing_white.gif
5 | gifs/decompressing_black.gif
6 | gifs/decompressing_white.gif
7 | gifs/merging_black.gif
8 | gifs/merging_white.gif
9 | gifs/publishing_black.gif
10 | gifs/publishing_white.gif
11 | gifs/recording_black.gif
12 | gifs/recording_white.gif
13 |
14 | icons/bag_info_black.svg
15 | icons/bag_info_white.svg
16 | icons/bag_to_pcd_black.svg
17 | icons/bag_to_pcd_white.svg
18 | icons/bag_to_images_black.svg
19 | icons/bag_to_images_white.svg
20 | icons/bag_to_video_black.svg
21 | icons/bag_to_video_white.svg
22 | icons/bag_tools_black.svg
23 | icons/bag_tools_white.svg
24 | icons/compress_bag_black.svg
25 | icons/compress_bag_white.svg
26 | icons/conversion_tools_black.svg
27 | icons/conversion_tools_white.svg
28 | icons/decompress_bag_black.svg
29 | icons/decompress_bag_white.svg
30 | icons/dummy_bag_black.svg
31 | icons/dummy_bag_white.svg
32 | icons/edit_bag_black.svg
33 | icons/edit_bag_white.svg
34 | icons/gear_black.svg
35 | icons/gear_white.svg
36 | icons/info_tools_black.svg
37 | icons/info_tools_white.svg
38 | icons/main.svg
39 | icons/merge_bags_black.svg
40 | icons/merge_bags_white.svg
41 | icons/minus_black.svg
42 | icons/minus_white.svg
43 | icons/pcd_to_bag_black.svg
44 | icons/pcd_to_bag_white.svg
45 | icons/plus_black.svg
46 | icons/plus_white.svg
47 | icons/publishing_tools_black.svg
48 | icons/publishing_tools_white.svg
49 | icons/publish_images_black.svg
50 | icons/publish_images_white.svg
51 | icons/publish_video_black.svg
52 | icons/publish_video_white.svg
53 | icons/record_bag_black.svg
54 | icons/record_bag_white.svg
55 | icons/topics_services_info_black.svg
56 | icons/topics_services_info_white.svg
57 | icons/video_to_bag_black.svg
58 | icons/video_to_bag_white.svg
59 |
60 |
61 |
--------------------------------------------------------------------------------
/src/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | add_subdirectory(cli)
2 | add_subdirectory(ros)
3 | add_subdirectory(ui)
4 | add_subdirectory(utils)
5 |
--------------------------------------------------------------------------------
/src/cli/BagToPCDs.cpp:
--------------------------------------------------------------------------------
1 | #include "BagToPCDsThread.hpp"
2 |
3 | #include "Parameters.hpp"
4 | #include "UtilsCLI.hpp"
5 | #include "UtilsROS.hpp"
6 |
7 | #include
8 | #include
9 |
10 | #include
11 | #include
12 |
13 | void
14 | showHelp()
15 | {
16 | std::cout << "Usage: ros2 run mediassist4_ros_tools tool_bag_to_pcds path/to/bag path/to/pcds\n" << std::endl;
17 | std::cout << "Additional parameters:" << std::endl;
18 | std::cout << "-t or --topic_name: Point cloud topic inside the bag. If no topic name is specified, the first found point cloud topic in the bag is taken.\n" << std::endl;
19 | std::cout << "-h or --help: Show this help." << std::endl;
20 | }
21 |
22 |
23 | volatile sig_atomic_t signalStatus = 0;
24 |
25 | int
26 | main(int argc, char* argv[])
27 | {
28 | // Create application
29 | QCoreApplication app(argc, argv);
30 |
31 | const auto& arguments = app.arguments();
32 | const QStringList checkList{ "-t", "-h", "--topic_name", "--help" };
33 | if (arguments.size() < 3 || arguments.contains("--help") || arguments.contains("-h")) {
34 | showHelp();
35 | return 0;
36 | }
37 | if (const auto& argument = Utils::CLI::containsInvalidParameters(arguments, checkList); argument != std::nullopt) {
38 | showHelp();
39 | throw std::runtime_error("Unrecognized argument '" + *argument + "'!");
40 | }
41 |
42 | Parameters::AdvancedParameters parameters;
43 |
44 | // Handle bag directory
45 | parameters.sourceDirectory = arguments.at(1);
46 | Utils::CLI::checkBagSourceDirectory(parameters.sourceDirectory);
47 |
48 | // PCD files directory
49 | parameters.targetDirectory = arguments.at(2);
50 | Utils::CLI::checkParentDirectory(parameters.targetDirectory);
51 |
52 | // Check for optional arguments
53 | if (arguments.size() > 3) {
54 | // Topic name
55 | Utils::CLI::checkTopicNameValidity(arguments, parameters.sourceDirectory, "sensor_msgs/msg/PointCloud2", parameters.topicName);
56 | }
57 |
58 | // Search for topic name in bag file if not specified
59 | if (parameters.topicName.isEmpty()) {
60 | Utils::CLI::checkForTargetTopic(parameters.sourceDirectory, parameters.topicName, false);
61 | }
62 |
63 | if (std::filesystem::exists(parameters.targetDirectory.toStdString())) {
64 | if (!Utils::CLI::shouldContinue("The target directory already exists. Continue? [y/n]")) {
65 | return 0;
66 | }
67 | }
68 |
69 | // Create thread and connect to its informations
70 | auto* const bagToPCDsThread = new BagToPCDsThread(parameters, std::thread::hardware_concurrency());
71 | QObject::connect(bagToPCDsThread, &BagToPCDsThread::progressChanged, [] (const QString& progressString, int progress) {
72 | const auto progressStringCMD = Utils::CLI::drawProgressString(progress);
73 | // Always clear the last line for a nice "progress bar" feeling
74 | std::cout << progressString.toStdString() << " " << progressStringCMD << " " << progress << "%" << "\r" << std::flush;
75 | });
76 | QObject::connect(bagToPCDsThread, &BagToPCDsThread::finished, [] {
77 | std::cout << "" << std::endl; // Extra line to stop flushing
78 | std::cout << "Writing pcds finished!" << std::endl;
79 | return EXIT_SUCCESS;
80 | });
81 | QObject::connect(bagToPCDsThread, &BagToPCDsThread::finished, bagToPCDsThread, &QObject::deleteLater);
82 |
83 | signal(SIGINT, [] (int signal) {
84 | signalStatus = signal;
85 | });
86 |
87 | std::cout << "Writing pcds. Please wait..." << std::endl;
88 | Utils::CLI::runThread(bagToPCDsThread, signalStatus);
89 |
90 | return EXIT_SUCCESS;
91 | }
92 |
--------------------------------------------------------------------------------
/src/cli/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | add_library (rt_cli INTERFACE)
2 |
3 | target_include_directories (rt_cli
4 | INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}
5 | )
6 |
7 | target_sources(rt_cli INTERFACE
8 | ${CMAKE_CURRENT_LIST_DIR}/BagToImages.cpp
9 | ${CMAKE_CURRENT_LIST_DIR}/BagToPCDs.cpp
10 | ${CMAKE_CURRENT_LIST_DIR}/BagToVideo.cpp
11 | ${CMAKE_CURRENT_LIST_DIR}/CompressBag.cpp
12 | ${CMAKE_CURRENT_LIST_DIR}/DecompressBag.cpp
13 | ${CMAKE_CURRENT_LIST_DIR}/DummyBag.cpp
14 | ${CMAKE_CURRENT_LIST_DIR}/MergeBags.cpp
15 | ${CMAKE_CURRENT_LIST_DIR}/PCDsToBag.cpp
16 | ${CMAKE_CURRENT_LIST_DIR}/PublishImages.cpp
17 | ${CMAKE_CURRENT_LIST_DIR}/PublishVideo.cpp
18 | ${CMAKE_CURRENT_LIST_DIR}/VideoToBag.cpp
19 | )
20 |
21 | target_link_libraries(rt_cli
22 | INTERFACE Qt::Widgets rt_thread rt_utils
23 | )
24 |
--------------------------------------------------------------------------------
/src/cli/DecompressBag.cpp:
--------------------------------------------------------------------------------
1 | #include "ChangeCompressionBagThread.hpp"
2 |
3 | #include "UtilsCLI.hpp"
4 | #include "Parameters.hpp"
5 | #include "UtilsROS.hpp"
6 |
7 | #include
8 | #include
9 |
10 | #include
11 | #include
12 | #include
13 | #include
14 |
15 | void
16 | showHelp()
17 | {
18 | std::cout << "Usage: ros2 run mediassist4_ros_tools tool_decompress_bag path/to/compressed/source/bag /path/to/uncompressed/target/bag \n" << std::endl;
19 | std::cout << "Additional parameters:" << std::endl;
20 | std::cout << "-d or --delete: Delete the source file after completion." << std::endl;
21 | std::cout << "-h or --help: Show this help." << std::endl;
22 | }
23 |
24 |
25 | volatile sig_atomic_t signalStatus = 0;
26 |
27 | int
28 | main(int argc, char* argv[])
29 | {
30 | // Create application
31 | QCoreApplication app(argc, argv);
32 |
33 | const auto arguments = app.arguments();
34 | if (arguments.size() < 3 || arguments.contains("--help") || arguments.contains("-h")) {
35 | showHelp();
36 | return 0;
37 | }
38 | if (const auto& argument = Utils::CLI::containsInvalidParameters(arguments, { "-d", "--delete" }); argument != std::nullopt) {
39 | showHelp();
40 | throw std::runtime_error("Unrecognized argument '" + *argument + "'!");
41 | }
42 |
43 | Parameters::CompressBagParameters parameters;
44 |
45 | // Compressed source bag directory
46 | parameters.sourceDirectory = arguments.at(1);
47 | if (!std::filesystem::exists(parameters.sourceDirectory.toStdString())) {
48 | throw std::runtime_error("Source bag file not found. Make sure that the bag file exists!");
49 | }
50 | if (const auto alreadyCompressed = Utils::ROS::doesDirectoryContainCompressedBagFile(parameters.sourceDirectory); !alreadyCompressed) {
51 | throw std::runtime_error("The bag file is invalid or not in compressed format!");
52 | }
53 |
54 | // Compressed target bag directory
55 | parameters.targetDirectory = arguments.at(2);
56 | Utils::CLI::checkParentDirectory(parameters.targetDirectory);
57 |
58 | // Check for optional arguments
59 | if (arguments.size() > 3) {
60 | // Delete source
61 | parameters.deleteSource = Utils::CLI::containsArguments(arguments, "-d", "--delete");
62 | }
63 |
64 | if (std::filesystem::exists(parameters.targetDirectory.toStdString())) {
65 | if (!Utils::CLI::shouldContinue("The target directory already exists. Continue? [y/n]")) {
66 | return 0;
67 | }
68 | }
69 |
70 | // Create thread and connect to its informations
71 | auto* const decompressBagThread = new ChangeCompressionBagThread(parameters, std::thread::hardware_concurrency(), false);
72 | auto isCompressing = false;
73 | std::thread processingThread;
74 |
75 | QObject::connect(decompressBagThread, &ChangeCompressionBagThread::processing, [&processingThread, &isCompressing] {
76 | processingThread = std::thread(Utils::CLI::showProcessingString, std::ref(isCompressing), Utils::CLI::CLI_DECOMPRESS);
77 |
78 | return EXIT_SUCCESS;
79 | });
80 | QObject::connect(decompressBagThread, &ChangeCompressionBagThread::finished, [&isCompressing, &processingThread] {
81 | isCompressing = false;
82 | processingThread.join();
83 |
84 | std::cout << "" << std::endl; // Extra line to stop flushing
85 | std::cout << "Decompressing finished!" << std::endl;
86 | return EXIT_SUCCESS;
87 | });
88 | QObject::connect(decompressBagThread, &ChangeCompressionBagThread::finished, decompressBagThread, &QObject::deleteLater);
89 |
90 | signal(SIGINT, [] (int signal) {
91 | signalStatus = signal;
92 | });
93 | Utils::CLI::runThread(decompressBagThread, signalStatus);
94 |
95 | return EXIT_SUCCESS;
96 | }
97 |
--------------------------------------------------------------------------------
/src/main.cpp:
--------------------------------------------------------------------------------
1 | #include "ui/MainWindow.hpp"
2 |
3 | #include "rclcpp/rclcpp.hpp"
4 |
5 | #include
6 |
7 | int
8 | main(int argc, char* argv[])
9 | {
10 | // Initialize ROS and Qt
11 | rclcpp::init(argc, argv);
12 | QApplication app(argc, argv);
13 | app.setWindowIcon(QIcon(":/icons/main.svg"));
14 |
15 | MainWindow mainWindow;
16 | mainWindow.show();
17 |
18 | while (rclcpp::ok()) {
19 | app.processEvents();
20 | std::this_thread::sleep_for(std::chrono::milliseconds(20));
21 | }
22 |
23 | rclcpp::shutdown();
24 | return EXIT_SUCCESS;
25 | }
26 |
--------------------------------------------------------------------------------
/src/ros/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | add_subdirectory(thread)
2 |
--------------------------------------------------------------------------------
/src/ros/thread/BagToImagesThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Thread used to write a bag images topic to a set of images
7 | class BagToImagesThread : public BasicThread {
8 | Q_OBJECT
9 | public:
10 | explicit
11 | BagToImagesThread(const Parameters::BagToImagesParameters& parameters,
12 | unsigned int numberOfThreads,
13 | QObject* parent = nullptr);
14 |
15 | void
16 | run() override;
17 |
18 | private:
19 | const Parameters::BagToImagesParameters& m_parameters;
20 |
21 | const unsigned int m_numberOfThreads;
22 | };
23 |
--------------------------------------------------------------------------------
/src/ros/thread/BagToPCDsThread.cpp:
--------------------------------------------------------------------------------
1 | #include "BagToPCDsThread.hpp"
2 |
3 | #include "UtilsROS.hpp"
4 |
5 | #include
6 |
7 | #include "rosbag2_cpp/reader.hpp"
8 |
9 | #include "sensor_msgs/msg/point_cloud2.hpp"
10 |
11 | #include
12 |
13 | BagToPCDsThread::BagToPCDsThread(const Parameters::AdvancedParameters& parameters,
14 | unsigned int numberOfThreads, QObject* parent) :
15 | BasicThread(parameters.sourceDirectory, parameters.topicName, parent),
16 | m_parameters(parameters), m_numberOfThreads(numberOfThreads)
17 | {
18 | }
19 |
20 |
21 | void
22 | BagToPCDsThread::run()
23 | {
24 | const auto targetDirectoryStd = m_parameters.targetDirectory.toStdString();
25 |
26 | if (!std::filesystem::exists(targetDirectoryStd)) {
27 | std::filesystem::create_directory(targetDirectoryStd);
28 | }
29 | if (!std::filesystem::is_empty(targetDirectoryStd)) {
30 | for (const auto& entry : std::filesystem::directory_iterator(targetDirectoryStd)) {
31 | std::filesystem::remove_all(entry.path());
32 | }
33 | }
34 |
35 | // Prepare parameters
36 | const auto messageCount = Utils::ROS::getTopicMessageCount(m_sourceDirectory, m_topicName);
37 | const auto messageCountNumberOfDigits = int(log10(*messageCount) + 1);
38 |
39 | rosbag2_cpp::Reader reader;
40 | reader.open(m_sourceDirectory);
41 |
42 | rclcpp::Serialization serialization;
43 | rosbag2_storage::SerializedBagMessageSharedPtr message;
44 | auto rosMessage = std::make_shared();
45 |
46 | auto iterationCount = 0;
47 | std::mutex mutex;
48 |
49 | // Move to own lambda for multithreading
50 | const auto writePCD = [this, &targetDirectoryStd, &reader, &message, &iterationCount, &mutex,
51 | serialization, rosMessage, messageCount, messageCountNumberOfDigits] {
52 | while (true) {
53 | mutex.lock();
54 |
55 | if (isInterruptionRequested() || !reader.has_next()) {
56 | mutex.unlock();
57 | break;
58 | }
59 |
60 | // Deserialize
61 | message = reader.read_next();
62 | if (message->topic_name != m_topicName) {
63 | mutex.unlock();
64 | continue;
65 | }
66 | rclcpp::SerializedMessage serializedMessage(*message->serialized_data);
67 | serialization.deserialize_message(&serializedMessage, rosMessage.get());
68 |
69 | // Inform of progress update
70 | iterationCount++;
71 | emit progressChanged("Writing pcd file " + QString::number(iterationCount) + " of " + QString::number(*messageCount) + "...",
72 | ((float) iterationCount / (float) *messageCount) * 100);
73 |
74 | // Have to create this as extra string to keep it atomic inside the mutex
75 | std::stringstream formatedIterationCount;
76 | // Use leading zeroes
77 | formatedIterationCount << std::setw(messageCountNumberOfDigits) << std::setfill('0') << iterationCount;
78 | const auto targetString = targetDirectoryStd + "/" + formatedIterationCount.str() + ".pcd";
79 |
80 | mutex.unlock();
81 |
82 | // Convert to cloud and then write to pcd
83 | pcl::PCLPointCloud2 cloud;
84 | pcl_conversions::toPCL(*rosMessage, cloud);
85 | pcl::PCDWriter writer;
86 | writer.write(targetString, cloud);
87 | }
88 | };
89 |
90 | while (reader.has_next()) {
91 | if (isInterruptionRequested()) {
92 | return;
93 | }
94 |
95 | std::vector threadPool;
96 | for (unsigned int i = 0; i < m_numberOfThreads; ++i) {
97 | threadPool.emplace_back(writePCD);
98 | }
99 | for (auto& thread : threadPool) {
100 | thread.join();
101 | }
102 | }
103 |
104 | reader.close();
105 |
106 | emit finished();
107 | }
108 |
--------------------------------------------------------------------------------
/src/ros/thread/BagToPCDsThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Thread used to write a bag images topic to a set of pcd files
7 | class BagToPCDsThread : public BasicThread {
8 | Q_OBJECT
9 | public:
10 | explicit
11 | BagToPCDsThread(const Parameters::AdvancedParameters& parameters,
12 | unsigned int numberOfThreads,
13 | QObject* parent = nullptr);
14 |
15 | void
16 | run() override;
17 |
18 | private:
19 | const Parameters::AdvancedParameters& m_parameters;
20 |
21 | const unsigned int m_numberOfThreads;
22 | };
23 |
--------------------------------------------------------------------------------
/src/ros/thread/BagToVideoThread.cpp:
--------------------------------------------------------------------------------
1 | #include "BagToVideoThread.hpp"
2 |
3 | #include "UtilsROS.hpp"
4 | #include "VideoEncoder.hpp"
5 |
6 | #include "rosbag2_cpp/reader.hpp"
7 |
8 | #include "sensor_msgs/msg/image.hpp"
9 |
10 | #ifdef ROS_HUMBLE
11 | #include
12 | #else
13 | #include
14 | #endif
15 |
16 | BagToVideoThread::BagToVideoThread(const Parameters::BagToVideoParameters& parameters, bool useHardwareAcceleration,
17 | QObject* parent) :
18 | BasicThread(parameters.sourceDirectory, parameters.topicName, parent),
19 | m_parameters(parameters), m_useHardwareAcceleration(useHardwareAcceleration)
20 | {
21 | }
22 |
23 |
24 | void
25 | BagToVideoThread::run()
26 | {
27 | rosbag2_cpp::Reader reader;
28 | reader.open(m_sourceDirectory);
29 |
30 | // Prepare parameters
31 | const auto messageCount = Utils::ROS::getTopicMessageCount(m_sourceDirectory, m_topicName);
32 | rclcpp::Serialization serialization;
33 | rosbag2_storage::SerializedBagMessageSharedPtr message;
34 | auto rosMessage = std::make_shared();
35 | cv_bridge::CvImagePtr cvPointer;
36 |
37 | auto iterationCount = 0;
38 | const auto topicNameStdString = m_topicName;
39 | const auto videoEncoder = std::make_shared(m_parameters.format == "mp4" ? cv::VideoWriter::fourcc('m', 'p', '4', 'v') :
40 | m_parameters.lossless ? cv::VideoWriter::fourcc('F', 'F', 'V', '1')
41 | : cv::VideoWriter::fourcc('X', '2', '6', '4'));
42 |
43 | // Now the main encoding
44 | while (reader.has_next()) {
45 | if (isInterruptionRequested()) {
46 | reader.close();
47 | return;
48 | }
49 |
50 | // Read and deserialize the message
51 | message = reader.read_next();
52 | if (message->topic_name != topicNameStdString) {
53 | continue;
54 | }
55 |
56 | rclcpp::SerializedMessage serializedMessage(*message->serialized_data);
57 | serialization.deserialize_message(&serializedMessage, rosMessage.get());
58 |
59 | // Setup the video encoder on the first iteration
60 | if (iterationCount == 0) {
61 | if (!videoEncoder->setVideoWriter(m_parameters.targetDirectory.toStdString(), m_parameters.fps,
62 | rosMessage->width, rosMessage->height,
63 | m_useHardwareAcceleration, m_parameters.useBWImages)) {
64 | emit failed();
65 | return;
66 | }
67 | }
68 |
69 | // Convert message to cv and encode
70 | cvPointer = cv_bridge::toCvCopy(rosMessage, rosMessage->encoding);
71 |
72 | if (m_parameters.useBWImages) {
73 | // It seems that just setting the VIDEOWRITER_PROP_IS_COLOR in the videowriter leads to a broken video,
74 | // at least if FFMPEG is used. Converting to a gray mat beforehand provides a fix. More information here:
75 | // https://github.com/opencv/opencv/issues/26276#issuecomment-2406825667
76 | cv::Mat greyMat;
77 | cv::cvtColor(cvPointer->image, greyMat, cv::COLOR_BGR2GRAY);
78 | videoEncoder->writeImageToVideo(greyMat);
79 | } else {
80 | if (m_parameters.exchangeRedBlueValues) {
81 | cv::cvtColor(cvPointer->image, cvPointer->image, cv::COLOR_BGR2RGB);
82 | }
83 | videoEncoder->writeImageToVideo(cvPointer->image);
84 | }
85 |
86 | iterationCount++;
87 | emit progressChanged("Writing frame " + QString::number(iterationCount) + " of " + QString::number(*messageCount) + "...",
88 | ((float) iterationCount / (float) *messageCount) * 100);
89 | }
90 |
91 | reader.close();
92 | emit finished();
93 | }
94 |
--------------------------------------------------------------------------------
/src/ros/thread/BagToVideoThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Thread writing a bag images topic to a video file
7 | class BagToVideoThread : public BasicThread {
8 | Q_OBJECT
9 | public:
10 | explicit
11 | BagToVideoThread(const Parameters::BagToVideoParameters& parameters,
12 | bool useHardwareAcceleration,
13 | QObject* parent = nullptr);
14 |
15 | void
16 | run() override;
17 |
18 | private:
19 | const Parameters::BagToVideoParameters& m_parameters;
20 |
21 | const bool m_useHardwareAcceleration;
22 | };
23 |
--------------------------------------------------------------------------------
/src/ros/thread/BasicThread.cpp:
--------------------------------------------------------------------------------
1 | #include "BasicThread.hpp"
2 |
3 | BasicThread::BasicThread(const QString& sourceDirectory,
4 | const QString& topicName,
5 | QObject* parent) :
6 | QThread(parent), m_sourceDirectory(sourceDirectory.toStdString()), m_topicName(topicName.toStdString())
7 | {
8 | }
9 |
--------------------------------------------------------------------------------
/src/ros/thread/BasicThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | // Basic thread class, overridden by custom classes
6 | class BasicThread : public QThread {
7 | Q_OBJECT
8 | public:
9 | explicit
10 | BasicThread(const QString& sourceDirectory,
11 | const QString& topicName,
12 | QObject* parent = nullptr);
13 |
14 | signals:
15 | void
16 | informOfGatheringData();
17 |
18 | // Update progress displayal in widget
19 | void
20 | progressChanged(const QString& progressString,
21 | int progress);
22 |
23 | void
24 | finished();
25 |
26 | void
27 | processing();
28 |
29 | // Might fail in some cases (CV instance opening failed, invalid input params...)
30 | void
31 | failed();
32 |
33 | protected:
34 | const std::string m_sourceDirectory;
35 | const std::string m_topicName;
36 | };
37 |
--------------------------------------------------------------------------------
/src/ros/thread/ChangeCompressionBagThread.cpp:
--------------------------------------------------------------------------------
1 | #include "ChangeCompressionBagThread.hpp"
2 |
3 | #include "rosbag2_transport/bag_rewrite.hpp"
4 |
5 | #include
6 |
7 | ChangeCompressionBagThread::ChangeCompressionBagThread(const Parameters::CompressBagParameters& parameters,
8 | int numberOfThreads, bool compress, QObject* parent) :
9 | BasicThread(parameters.sourceDirectory, parameters.topicName, parent),
10 | m_parameters(parameters), m_numberOfThreads(numberOfThreads), m_compress(compress)
11 | {
12 | }
13 |
14 |
15 | void
16 | ChangeCompressionBagThread::run()
17 | {
18 | const auto targetDirectoryStd = m_parameters.targetDirectory.toStdString();
19 | if (std::filesystem::exists(targetDirectoryStd)) {
20 | std::filesystem::remove_all(targetDirectoryStd);
21 | }
22 |
23 | // Input params
24 | rosbag2_storage::StorageOptions inputStorage;
25 | inputStorage.uri = m_sourceDirectory;
26 |
27 | // Output params
28 | rosbag2_storage::StorageOptions outputStorage;
29 | outputStorage.uri = targetDirectoryStd;
30 |
31 | rosbag2_transport::RecordOptions outputRecord;
32 | #ifdef ROS_HUMBLE
33 | outputRecord.all = true;
34 | #else
35 | outputRecord.all_topics = true;
36 | #endif
37 | if (m_compress) {
38 | outputRecord.compression_format = "zstd";
39 | outputRecord.compression_mode = m_parameters.compressPerMessage ? "message" : "file";
40 | outputRecord.compression_threads = m_numberOfThreads;
41 | // Need to set this so no messages are dropped
42 | outputRecord.compression_queue_size = 0;
43 | }
44 |
45 | std::vector > outputBags;
46 | outputBags.push_back({ outputStorage, outputRecord });
47 |
48 | emit processing();
49 | // Main rewrite
50 | rosbag2_transport::bag_rewrite({ inputStorage }, outputBags);
51 |
52 | if (m_parameters.deleteSource) {
53 | std::filesystem::remove_all(m_sourceDirectory);
54 | }
55 | emit finished();
56 | }
57 |
--------------------------------------------------------------------------------
/src/ros/thread/ChangeCompressionBagThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Thread used to write a compressed to an uncompressed file (or vice versa)
7 | // Makes use of the rosbag2_transport API for simplicity and performance
8 | class ChangeCompressionBagThread : public BasicThread {
9 | Q_OBJECT
10 | public:
11 | explicit
12 | ChangeCompressionBagThread(const Parameters::CompressBagParameters& parameters,
13 | int numberOfThreads,
14 | bool compress,
15 | QObject* parent = nullptr);
16 |
17 | void
18 | run() override;
19 |
20 | private:
21 | const Parameters::CompressBagParameters& m_parameters;
22 |
23 | int m_numberOfThreads;
24 | bool m_compress;
25 | };
26 |
--------------------------------------------------------------------------------
/src/ros/thread/DummyBagThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Dummy bag thread, used to create a bag file with dummy data
7 | class DummyBagThread : public BasicThread {
8 | Q_OBJECT
9 | public:
10 | explicit
11 | DummyBagThread(const Parameters::DummyBagParameters& parameters,
12 | unsigned int numberOfThreads,
13 | QObject* parent = nullptr);
14 |
15 | void
16 | run() override;
17 |
18 | private:
19 | const Parameters::DummyBagParameters& m_parameters;
20 |
21 | const unsigned int m_numberOfThreads;
22 | };
23 |
--------------------------------------------------------------------------------
/src/ros/thread/EditBagThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Thread used to write an edited ROS bag file
7 | class EditBagThread : public BasicThread {
8 | Q_OBJECT
9 | public:
10 | explicit
11 | EditBagThread(const Parameters::EditBagParameters& parameters,
12 | unsigned int numberOfThreads,
13 | QObject* parent = nullptr);
14 |
15 | void
16 | run() override;
17 |
18 | private:
19 | const Parameters::EditBagParameters& m_parameters;
20 |
21 | const unsigned int m_numberOfThreads;
22 | };
23 |
--------------------------------------------------------------------------------
/src/ros/thread/MergeBagsThread.cpp:
--------------------------------------------------------------------------------
1 | #include "MergeBagsThread.hpp"
2 |
3 | #include "rosbag2_transport/bag_rewrite.hpp"
4 |
5 | #include
6 |
7 | MergeBagsThread::MergeBagsThread(const Parameters::MergeBagsParameters& parameters,
8 | unsigned int numberOfThreads, QObject* parent) :
9 | BasicThread(parameters.sourceDirectory, "", parent),
10 | m_parameters(parameters), m_numberOfThreads(numberOfThreads)
11 | {
12 | }
13 |
14 |
15 | void
16 | MergeBagsThread::run()
17 | {
18 | const auto targetDirectoryStd = m_parameters.targetDirectory.toStdString();
19 | if (std::filesystem::exists(targetDirectoryStd)) {
20 | std::filesystem::remove_all(targetDirectoryStd);
21 | }
22 |
23 | // Setup input parameters
24 | rosbag2_storage::StorageOptions inputStorageFirstBag;
25 | inputStorageFirstBag.uri = m_sourceDirectory;
26 | rosbag2_storage::StorageOptions inputStorageSecondBag;
27 | inputStorageSecondBag.uri = m_parameters.secondSourceDirectory.toStdString();
28 |
29 | // Output parameters
30 | rosbag2_storage::StorageOptions outputStorage;
31 | outputStorage.uri = targetDirectoryStd;
32 |
33 | rosbag2_transport::RecordOptions outputRecord;
34 | for (const auto& topic : m_parameters.topics) {
35 | if (!topic.isSelected) {
36 | continue;
37 | }
38 |
39 | outputRecord.topics.push_back(topic.name.toStdString());
40 | }
41 |
42 | std::vector > outputBags;
43 | outputBags.push_back({ outputStorage, outputRecord });
44 |
45 | emit processing();
46 | // Do merge
47 | rosbag2_transport::bag_rewrite({ inputStorageFirstBag, inputStorageSecondBag }, outputBags);
48 |
49 | if (m_parameters.deleteSource) {
50 | std::filesystem::remove_all(m_sourceDirectory);
51 | std::filesystem::remove_all(m_parameters.secondSourceDirectory.toStdString());
52 | }
53 | emit finished();
54 | }
55 |
--------------------------------------------------------------------------------
/src/ros/thread/MergeBagsThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Thread used to merge a bag file using two input bag files
7 | // Makes use of the rosbag2_transport API for simplicity and performance
8 | class MergeBagsThread : public BasicThread {
9 | Q_OBJECT
10 | public:
11 | explicit
12 | MergeBagsThread(const Parameters::MergeBagsParameters& parameters,
13 | unsigned int numberOfThreads,
14 | QObject* parent = nullptr);
15 |
16 | void
17 | run() override;
18 |
19 | private:
20 | const Parameters::MergeBagsParameters& m_parameters;
21 |
22 | const unsigned int m_numberOfThreads;
23 | };
24 |
--------------------------------------------------------------------------------
/src/ros/thread/PCDsToBagThread.cpp:
--------------------------------------------------------------------------------
1 | #include "PCDsToBagThread.hpp"
2 |
3 | #include
4 |
5 | #include "rosbag2_cpp/writer.hpp"
6 |
7 | #include "sensor_msgs/msg/point_cloud.hpp"
8 |
9 | #include
10 |
11 | PCDsToBagThread::PCDsToBagThread(const Parameters::PCDsToBagParameters& parameters, QObject* parent) :
12 | BasicThread(parameters.sourceDirectory, parameters.topicName, parent),
13 | m_parameters(parameters)
14 | {
15 | }
16 |
17 |
18 | void
19 | PCDsToBagThread::run()
20 | {
21 | const auto targetDirectoryStd = m_parameters.targetDirectory.toStdString();
22 | if (std::filesystem::exists(targetDirectoryStd)) {
23 | std::filesystem::remove_all(targetDirectoryStd);
24 | }
25 |
26 | emit informOfGatheringData();
27 |
28 | auto frameCount = 0;
29 | // It is faster to first store all valid pcd file paths and then iterate over those
30 | std::set sortedPCDsSet;
31 | for (auto const& entry : std::filesystem::directory_iterator(m_sourceDirectory)) {
32 | if (entry.path().extension() != ".pcd") {
33 | continue;
34 | }
35 |
36 | sortedPCDsSet.insert(entry.path());
37 | frameCount++;
38 | }
39 |
40 | pcl::PCLPointCloud2 cloud;
41 | sensor_msgs::msg::PointCloud2 message;
42 | pcl::PCDReader reader;
43 |
44 | rosbag2_cpp::Writer writer;
45 | writer.open(targetDirectoryStd);
46 |
47 | auto iterationCount = 1;
48 | auto timeStamp = rclcpp::Clock(RCL_ROS_TIME).now();
49 | const auto duration = rclcpp::Duration::from_seconds(1.0f / (float) m_parameters.rate);
50 |
51 | while (true) {
52 | if (isInterruptionRequested() || sortedPCDsSet.empty()) {
53 | break;
54 | }
55 |
56 | // Read pcd from file
57 | reader.read(*sortedPCDsSet.begin(), cloud);
58 | timeStamp += duration;
59 | // Write
60 | pcl_conversions::fromPCL(cloud, message);
61 | writer.write(message, m_topicName, timeStamp);
62 |
63 | sortedPCDsSet.erase(sortedPCDsSet.begin());
64 | emit progressChanged("Writing pcd file " + QString::number(iterationCount) + " of " + QString::number(frameCount) + "...",
65 | ((float) iterationCount / (float) frameCount) * 100);
66 | iterationCount++;
67 | }
68 |
69 | emit finished();
70 | }
71 |
--------------------------------------------------------------------------------
/src/ros/thread/PCDsToBagThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Thread used to write a set of pcd files to a bag file
7 | class PCDsToBagThread : public BasicThread {
8 | Q_OBJECT
9 |
10 | public:
11 | explicit
12 | PCDsToBagThread(const Parameters::PCDsToBagParameters& parameters,
13 | QObject* parent = nullptr);
14 |
15 | void
16 | run() override;
17 |
18 | private:
19 | const Parameters::PCDsToBagParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ros/thread/PublishImagesThread.cpp:
--------------------------------------------------------------------------------
1 | #include "PublishImagesThread.hpp"
2 |
3 | #include
4 |
5 | #ifdef ROS_HUMBLE
6 | #include
7 | #else
8 | #include
9 | #endif
10 |
11 | #include
12 |
13 | PublishImagesThread::PublishImagesThread(const Parameters::PublishParameters& parameters,
14 | QObject* parent) :
15 | BasicThread(parameters.sourceDirectory, parameters.topicName, parent),
16 | m_parameters(parameters)
17 | {
18 | m_node = std::make_shared("publish_images");
19 | m_publisher = m_node->create_publisher(m_topicName, 10);
20 | }
21 |
22 |
23 | void
24 | PublishImagesThread::run()
25 | {
26 | std::set sortedImagesSet;
27 | auto frameCount = 0;
28 |
29 | emit informOfGatheringData();
30 | // It is faster to first store all valid image file paths and then iterate over those
31 | for (auto const& entry : std::filesystem::directory_iterator(m_sourceDirectory)) {
32 | if (entry.path().extension() != ".jpg" && entry.path().extension() != ".png" && entry.path().extension() != ".bmp") {
33 | continue;
34 | }
35 |
36 | sortedImagesSet.insert(entry.path());
37 | frameCount++;
38 | }
39 | auto setIterator = sortedImagesSet.begin();
40 |
41 | cv::Mat frame;
42 | sensor_msgs::msg::Image message;
43 |
44 | cv_bridge::CvImage cvBridge;
45 | cvBridge.encoding = sensor_msgs::image_encodings::BGR8;
46 |
47 | const int rate = ((1000 / (float) m_parameters.fps) * 1000);
48 | auto iterator = 0;
49 | auto timer = m_node->create_wall_timer(std::chrono::microseconds(rate),
50 | [this, &iterator, &setIterator, &frame, &cvBridge, &message, sortedImagesSet, frameCount] {
51 | if (isInterruptionRequested()) {
52 | return;
53 | }
54 |
55 | // Loop if set
56 | if (iterator == frameCount) {
57 | if (m_parameters.loop) {
58 | setIterator = sortedImagesSet.begin();
59 | iterator = 0;
60 | } else {
61 | return;
62 | }
63 | }
64 |
65 | // Read image from file
66 | frame = cv::imread(*setIterator, cv::IMREAD_COLOR);
67 | if (frame.empty()) {
68 | iterator++;
69 | setIterator++;
70 | return;
71 | }
72 |
73 | if (m_parameters.exchangeRedBlueValues) {
74 | cv::cvtColor(frame, frame, cv::COLOR_BGR2RGB);
75 | }
76 | if (m_parameters.scale) {
77 | cv::resize(frame, frame, cv::Size(m_parameters.width, m_parameters.height), 0, 0);
78 | }
79 |
80 | // Convert and write image
81 | cvBridge.image = frame;
82 | cvBridge.toImageMsg(message);
83 |
84 | m_publisher->publish(message);
85 |
86 | emit progressChanged("Publishing image " + QString::number(iterator + 1) + " of " + QString::number(frameCount) + "...", PROGRESS);
87 | iterator++;
88 | setIterator++;
89 | });
90 |
91 | auto executor = std::make_shared();
92 | executor->add_node(m_node);
93 |
94 | while (!isInterruptionRequested()) {
95 | executor->spin_once();
96 | }
97 |
98 | timer->cancel();
99 | emit finished();
100 | }
101 |
--------------------------------------------------------------------------------
/src/ros/thread/PublishImagesThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | #include "rclcpp/rclcpp.hpp"
7 | #include "sensor_msgs/msg/image.hpp"
8 |
9 | // Thread used to publish image sequences as a ROS topic
10 | // This thread also runs as a separate ROS node to enable the image messages publishing
11 | class PublishImagesThread : public BasicThread {
12 | Q_OBJECT
13 |
14 | public:
15 | explicit
16 | PublishImagesThread(const Parameters::PublishParameters& parameters,
17 | QObject* parent = nullptr);
18 |
19 | void
20 | run() override;
21 |
22 | private:
23 | std::shared_ptr m_node;
24 | rclcpp::Publisher::SharedPtr m_publisher;
25 |
26 | const Parameters::PublishParameters& m_parameters;
27 |
28 | static constexpr int PROGRESS = 0;
29 | };
30 |
--------------------------------------------------------------------------------
/src/ros/thread/PublishVideoThread.cpp:
--------------------------------------------------------------------------------
1 | #include "PublishVideoThread.hpp"
2 |
3 | #include
4 |
5 | #ifdef ROS_HUMBLE
6 | #include
7 | #else
8 | #include
9 | #endif
10 |
11 | PublishVideoThread::PublishVideoThread(const Parameters::PublishParameters& parameters, bool useHardwareAcceleration,
12 | QObject* parent) :
13 | BasicThread(parameters.sourceDirectory, parameters.topicName, parent),
14 | m_parameters(parameters), m_useHardwareAcceleration(useHardwareAcceleration)
15 | {
16 | m_node = std::make_shared("publish_video");
17 | m_publisher = m_node->create_publisher(m_topicName, 10);
18 | }
19 |
20 |
21 | void
22 | PublishVideoThread::run()
23 | {
24 | auto videoCapture = cv::VideoCapture(m_sourceDirectory, cv::CAP_ANY, {
25 | cv::CAP_PROP_HW_ACCELERATION, m_useHardwareAcceleration ? cv::VIDEO_ACCELERATION_ANY : cv::VIDEO_ACCELERATION_NONE
26 | });
27 | if (!videoCapture.isOpened()) {
28 | emit failed();
29 | return;
30 | }
31 |
32 | cv::Mat frame;
33 | sensor_msgs::msg::Image message;
34 |
35 | std_msgs::msg::Header header;
36 | cv_bridge::CvImage cvBridge;
37 | cvBridge.header = header;
38 | cvBridge.encoding = sensor_msgs::image_encodings::BGR8;
39 |
40 | const int rate = ((1000 / (float) videoCapture.get(cv::CAP_PROP_FPS)) * 1000);
41 | auto iterator = 0;
42 | const auto frameCount = videoCapture.get(cv::CAP_PROP_FRAME_COUNT);
43 |
44 | auto timer = m_node->create_wall_timer(std::chrono::microseconds(rate),
45 | [this, &iterator, &videoCapture, &frame, &message, &cvBridge, frameCount] {
46 | if (isInterruptionRequested()) {
47 | return;
48 | }
49 |
50 | // Loop if set
51 | if (iterator == frameCount && m_parameters.loop) {
52 | videoCapture.set(cv::CAP_PROP_POS_FRAMES, 0);
53 | iterator = 0;
54 | }
55 |
56 | // Capture image
57 | videoCapture >> frame;
58 | if (frame.empty()) {
59 | return;
60 | }
61 |
62 | if (m_parameters.exchangeRedBlueValues) {
63 | cv::cvtColor(frame, frame, cv::COLOR_BGR2RGB);
64 | }
65 | if (m_parameters.scale) {
66 | cv::resize(frame, frame, cv::Size(m_parameters.width, m_parameters.height), 0, 0);
67 | }
68 |
69 | // Convert and write image
70 | cvBridge.image = frame;
71 | cvBridge.toImageMsg(message);
72 |
73 | m_publisher->publish(message);
74 |
75 | emit progressChanged("Publishing image " + QString::number(iterator + 1) + " of " + QString::number(frameCount) + "...", PROGRESS);
76 | iterator++;
77 | });
78 |
79 | auto executor = std::make_shared();
80 | executor->add_node(m_node);
81 |
82 | while (!isInterruptionRequested()) {
83 | executor->spin_once();
84 | }
85 |
86 | timer->cancel();
87 | emit finished();
88 | }
89 |
--------------------------------------------------------------------------------
/src/ros/thread/PublishVideoThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | #include "rclcpp/rclcpp.hpp"
7 | #include "sensor_msgs/msg/image.hpp"
8 |
9 | // Thread used to publish a video as ROS topic
10 | // This thread also runs as a separate ROS node to enable the image messages publishing
11 | class PublishVideoThread : public BasicThread {
12 | Q_OBJECT
13 |
14 | public:
15 | explicit
16 | PublishVideoThread(const Parameters::PublishParameters& parameters,
17 | bool useHardwareAcceleration,
18 | QObject* parent = nullptr);
19 |
20 | void
21 | run() override;
22 |
23 | private:
24 | std::shared_ptr m_node;
25 | rclcpp::Publisher::SharedPtr m_publisher;
26 |
27 | const Parameters::PublishParameters& m_parameters;
28 |
29 | const bool m_useHardwareAcceleration;
30 |
31 | static constexpr int PROGRESS = 0;
32 | };
33 |
--------------------------------------------------------------------------------
/src/ros/thread/RecordBagThread.cpp:
--------------------------------------------------------------------------------
1 | #include "RecordBagThread.hpp"
2 |
3 | #include "rclcpp/rclcpp.hpp"
4 | #include "rosbag2_transport/recorder.hpp"
5 |
6 | #include
7 |
8 | RecordBagThread::RecordBagThread(const Parameters::RecordBagParameters& parameters, QObject* parent) :
9 | BasicThread(parameters.sourceDirectory, "", parent), m_parameters(parameters)
10 | {
11 | }
12 |
13 |
14 | void
15 | RecordBagThread::run()
16 | {
17 | const auto targetDirectoryStd = m_parameters.sourceDirectory.toStdString();
18 | if (std::filesystem::exists(targetDirectoryStd)) {
19 | std::filesystem::remove_all(targetDirectoryStd);
20 | }
21 |
22 | rosbag2_storage::StorageOptions storageOptions;
23 | storageOptions.uri = targetDirectoryStd;
24 |
25 | rosbag2_transport::RecordOptions recordOptions;
26 | if (m_parameters.allTopics) {
27 | #ifdef ROS_HUMBLE
28 | recordOptions.all = true;
29 | #else
30 | recordOptions.all_topics = true;
31 | #endif
32 | } else {
33 | for (const auto& topic : m_parameters.topics) {
34 | recordOptions.topics.push_back(topic.toStdString());
35 | }
36 | }
37 | recordOptions.rmw_serialization_format = "cdr";
38 | recordOptions.include_hidden_topics = m_parameters.includeHiddenTopics;
39 | recordOptions.include_unpublished_topics = m_parameters.includeUnpublishedTopics;
40 |
41 | auto writer = std::make_unique();
42 | auto recorder = std::make_shared(std::move(writer), storageOptions, recordOptions);
43 |
44 | // Initialize recorder
45 | recorder->record();
46 | auto executor = std::make_shared();
47 | executor->add_node(recorder);
48 |
49 | // Need to spin it in an extra thread for writing messages (no idea why, though)
50 | auto spinThread = std::thread([executor] {
51 | executor->spin();
52 | });
53 |
54 | rclcpp::Rate rate(50);
55 | while (!isInterruptionRequested()) {
56 | rate.sleep();
57 | }
58 |
59 | recorder->stop();
60 | executor->cancel();
61 | spinThread.join();
62 |
63 | emit finished();
64 | }
65 |
--------------------------------------------------------------------------------
/src/ros/thread/RecordBagThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Thread used to record a bag file
7 | class RecordBagThread : public BasicThread {
8 | Q_OBJECT
9 | public:
10 | explicit
11 | RecordBagThread(const Parameters::RecordBagParameters& parameters,
12 | QObject* parent = nullptr);
13 |
14 | void
15 | run() override;
16 |
17 | private:
18 | const Parameters::RecordBagParameters& m_parameters;
19 | };
20 |
--------------------------------------------------------------------------------
/src/ros/thread/VideoToBagThread.cpp:
--------------------------------------------------------------------------------
1 | #include "VideoToBagThread.hpp"
2 |
3 | #include
4 |
5 | #include "rclcpp/rclcpp.hpp"
6 | #include "rosbag2_cpp/writer.hpp"
7 | #include "sensor_msgs/msg/image.hpp"
8 |
9 | #include
10 |
11 | #ifdef ROS_HUMBLE
12 | #include
13 | #else
14 | #include
15 | #endif
16 |
17 | VideoToBagThread::VideoToBagThread(const Parameters::VideoToBagParameters& parameters, bool useHardwareAcceleration,
18 | QObject* parent) :
19 | BasicThread(parameters.sourceDirectory, parameters.topicName, parent),
20 | m_parameters(parameters), m_useHardwareAcceleration(useHardwareAcceleration)
21 | {
22 | }
23 |
24 |
25 | void
26 | VideoToBagThread::run()
27 | {
28 | auto videoCapture = cv::VideoCapture(m_sourceDirectory, cv::CAP_ANY, {
29 | cv::CAP_PROP_HW_ACCELERATION, m_useHardwareAcceleration ? cv::VIDEO_ACCELERATION_ANY : cv::VIDEO_ACCELERATION_NONE
30 | });
31 | if (!videoCapture.isOpened()) {
32 | emit failed();
33 | return;
34 | }
35 |
36 | const auto targetDirectoryStd = m_parameters.targetDirectory.toStdString();
37 | if (std::filesystem::exists(targetDirectoryStd)) {
38 | std::filesystem::remove_all(targetDirectoryStd);
39 | }
40 |
41 | const auto frameCount = videoCapture.get(cv::CAP_PROP_FRAME_COUNT);
42 | const auto finalFPS = m_parameters.useCustomFPS ? m_parameters.fps : videoCapture.get(cv::CAP_PROP_FPS);
43 | auto timeStamp = rclcpp::Clock(RCL_ROS_TIME).now();
44 | const auto duration = rclcpp::Duration::from_seconds(1.0f / (float) finalFPS);
45 |
46 | rosbag2_cpp::Writer writer;
47 | writer.open(targetDirectoryStd);
48 | auto iterationCount = 0;
49 |
50 | cv::Mat frame;
51 | std_msgs::msg::Header header;
52 | sensor_msgs::msg::Image message;
53 |
54 | cv_bridge::CvImage cvBridge;
55 | cvBridge.header = header;
56 | cvBridge.encoding = sensor_msgs::image_encodings::BGR8;
57 |
58 | while (true) {
59 | if (isInterruptionRequested()) {
60 | writer.close();
61 | return;
62 | }
63 |
64 | // Capture image
65 | videoCapture >> frame;
66 | if (frame.empty()) {
67 | break;
68 | }
69 |
70 | iterationCount++;
71 | if (m_parameters.exchangeRedBlueValues) {
72 | cv::cvtColor(frame, frame, cv::COLOR_BGR2RGB);
73 | }
74 |
75 | // Create empty sensor message
76 | timeStamp += duration;
77 | header.stamp = timeStamp;
78 |
79 | // Convert and write image
80 | cvBridge.image = frame;
81 | cvBridge.toImageMsg(message);
82 | writer.write(message, m_topicName, timeStamp);
83 |
84 | emit progressChanged("Writing message " + QString::number(iterationCount) + " of " + QString::number(frameCount) + "...",
85 | ((float) iterationCount / (float) frameCount) * 100);
86 | }
87 |
88 | writer.close();
89 | emit finished();
90 | }
91 |
--------------------------------------------------------------------------------
/src/ros/thread/VideoToBagThread.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicThread.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Thread used to write a video to a bag file
7 | class VideoToBagThread : public BasicThread {
8 | Q_OBJECT
9 |
10 | public:
11 | explicit
12 | VideoToBagThread(const Parameters::VideoToBagParameters& parameters,
13 | bool useHardwareAcceleration,
14 | QObject* parent = nullptr);
15 |
16 | void
17 | run() override;
18 |
19 | private:
20 | const Parameters::VideoToBagParameters& m_parameters;
21 |
22 | const bool m_useHardwareAcceleration;
23 | };
24 |
--------------------------------------------------------------------------------
/src/ui/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | add_subdirectory(InputWidgets)
2 | add_subdirectory(HelperWidgets)
3 | add_subdirectory(settings)
4 |
5 | add_library (rt_ui INTERFACE)
6 |
7 | target_include_directories (rt_ui
8 | INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}
9 | )
10 |
11 | target_sources(rt_ui INTERFACE
12 | ${CMAKE_CURRENT_LIST_DIR}/MainWindow.cpp
13 | ${CMAKE_CURRENT_LIST_DIR}/MainWindow.hpp
14 | ${CMAKE_CURRENT_LIST_DIR}/ProgressWidget.cpp
15 | ${CMAKE_CURRENT_LIST_DIR}/ProgressWidget.hpp
16 | ${CMAKE_CURRENT_LIST_DIR}/SettingsDialog.cpp
17 | ${CMAKE_CURRENT_LIST_DIR}/SettingsDialog.hpp
18 | ${CMAKE_CURRENT_LIST_DIR}/StartWidget.cpp
19 | ${CMAKE_CURRENT_LIST_DIR}/StartWidget.hpp
20 | )
21 |
22 | target_link_libraries(rt_ui
23 | INTERFACE Qt::Widgets rt_all_threads rt_input_widgets rt_settings rt_utils
24 | )
25 |
--------------------------------------------------------------------------------
/src/ui/HelperWidgets/BasicBagWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicInputWidget.hpp"
4 | #include "DeleteSourceSettings.hpp"
5 | #include "Parameters.hpp"
6 |
7 | #include
8 | #include
9 |
10 | class QCheckBox;
11 | class QLineEdit;
12 | class QTreeWidget;
13 | class QTreeWidgetItem;
14 |
15 | // Widget for displaying bag contents for manipulation
16 | class BasicBagWidget : public BasicInputWidget
17 | {
18 | Q_OBJECT
19 | public:
20 | explicit
21 | BasicBagWidget(Parameters::DeleteSourceParameters& parameters,
22 | const QString& titleText,
23 | const QString& iconText,
24 | const QString& settingsIdentifierText,
25 | QWidget* parent = 0);
26 |
27 | protected slots:
28 | virtual void
29 | itemCheckStateChanged(QTreeWidgetItem* item,
30 | int column) = 0;
31 |
32 | void
33 | targetPushButtonPressed();
34 |
35 | protected:
36 | [[nodiscard]] bool
37 | areIOParametersValid(int topicSize,
38 | int topicSizeWithoutDuplicates,
39 | const QString& secondSourceParameter = QString()) const;
40 |
41 | protected:
42 | QPointer m_treeWidget;
43 |
44 | QPointer m_targetLineEdit;
45 | QPointer m_deleteSourceCheckBox;
46 |
47 | QPointer m_targetBagNameWidget;
48 |
49 | static constexpr int COL_CHECKBOXES = 0;
50 | static constexpr int COL_TOPIC_NAME = 1;
51 | static constexpr int COL_TOPIC_TYPE = 2;
52 |
53 | private:
54 | Parameters::DeleteSourceParameters& m_parameters;
55 |
56 | DeleteSourceSettings m_settings;
57 | };
58 |
--------------------------------------------------------------------------------
/src/ui/HelperWidgets/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | add_library (rt_helper_widgets INTERFACE)
2 |
3 | target_include_directories (rt_helper_widgets
4 | INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}
5 | )
6 |
7 | target_sources(rt_helper_widgets INTERFACE
8 | ${CMAKE_CURRENT_LIST_DIR}/BasicBagWidget.cpp
9 | ${CMAKE_CURRENT_LIST_DIR}/BasicBagWidget.hpp
10 | ${CMAKE_CURRENT_LIST_DIR}/TopicWidget.cpp
11 | ${CMAKE_CURRENT_LIST_DIR}/TopicWidget.hpp
12 | ${CMAKE_CURRENT_LIST_DIR}/MessageCountWidget.cpp
13 | ${CMAKE_CURRENT_LIST_DIR}/MessageCountWidget.hpp
14 | ${CMAKE_CURRENT_LIST_DIR}/TopicListingInputWidget.cpp
15 | ${CMAKE_CURRENT_LIST_DIR}/TopicListingInputWidget.hpp
16 | )
17 |
18 | target_link_libraries(rt_helper_widgets
19 | INTERFACE Qt::Widgets
20 | )
21 |
--------------------------------------------------------------------------------
/src/ui/HelperWidgets/MessageCountWidget.cpp:
--------------------------------------------------------------------------------
1 | #include "MessageCountWidget.hpp"
2 |
3 | #include
4 | #include
5 |
6 | MessageCountWidget::MessageCountWidget(int minimum, int maximum, int currentMaximumValue, QWidget *parent) :
7 | QWidget(parent)
8 | {
9 | m_lowerBox = new QSpinBox;
10 | // Start with a value of 0 instead one 1, most users should be able to handle that :-P
11 | m_lowerBox->setRange(0, maximum);
12 | m_lowerBox->setValue(minimum);
13 |
14 | m_upperBox = new QSpinBox;
15 | m_upperBox->setRange(1, maximum);
16 | m_upperBox->setValue(currentMaximumValue);
17 |
18 | auto* const rangeDifferenceLabel = new QLabel("-");
19 |
20 | auto* const mainLayout = new QHBoxLayout;
21 | mainLayout->addWidget(m_lowerBox);
22 | mainLayout->addStretch();
23 | mainLayout->addWidget(rangeDifferenceLabel);
24 | mainLayout->addStretch();
25 | mainLayout->addWidget(m_upperBox);
26 | // Set these margins because we are going to integrate the widget into existing widgets
27 | // where any extra widgets would create undesired extra space
28 | mainLayout->setContentsMargins(0, 0, 0, 0);
29 |
30 | setLayout(mainLayout);
31 |
32 | connect(m_lowerBox, QOverload::of(&QSpinBox::valueChanged), this, [this] (int value) {
33 | emit lowerValueChanged(value);
34 | });
35 | connect(m_upperBox, QOverload::of(&QSpinBox::valueChanged), this, [this] (int value) {
36 | emit upperValueChanged(value);
37 | });
38 | }
39 |
--------------------------------------------------------------------------------
/src/ui/HelperWidgets/MessageCountWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 | #include
5 | #include
6 |
7 | // Display the lower and upper messages which should be extracted out of an existing ROS bag
8 | // into a newly edited one
9 | class MessageCountWidget : public QWidget
10 | {
11 | Q_OBJECT
12 |
13 | public:
14 | MessageCountWidget(int minimum,
15 | int maximum,
16 | int currentMaximumValue,
17 | QWidget* parent = 0);
18 |
19 | signals:
20 | void
21 | lowerValueChanged(int value);
22 |
23 | void
24 | upperValueChanged(int value);
25 |
26 | public:
27 | int
28 | getLowerValue() const
29 | {
30 | return m_lowerBox->value();
31 | }
32 |
33 | int
34 | getHigherValue() const
35 | {
36 | return m_upperBox->value();
37 | }
38 |
39 | private:
40 | QPointer m_lowerBox;
41 | QPointer m_upperBox;
42 | };
43 |
--------------------------------------------------------------------------------
/src/ui/HelperWidgets/TopicListingInputWidget.cpp:
--------------------------------------------------------------------------------
1 | #include "TopicListingInputWidget.hpp"
2 |
3 | #include "UtilsUI.hpp"
4 |
5 | #include
6 | #include
7 | #include
8 | #include
9 | #include
10 | #include
11 | #include
12 | #include
13 |
14 | #include
15 |
16 | TopicListingInputWidget::TopicListingInputWidget(Parameters::BasicParameters& parameters, const QString& titleText,
17 | const QString& iconText, const QString& settingsIdentifierText,
18 | QWidget *parent) :
19 | BasicInputWidget(titleText, iconText, parent),
20 | m_parameters(parameters), m_settings(parameters, settingsIdentifierText)
21 | {
22 | m_addTopicButton = new QToolButton;
23 | m_addTopicButton->setToolTip("Add another topic.");
24 |
25 | m_topicButtonLayout = new QHBoxLayout;
26 | m_topicButtonLayout->addStretch();
27 | m_topicButtonLayout->addWidget(m_addTopicButton);
28 | m_topicButtonLayout->setSpacing(0);
29 | m_topicButtonLayout->setContentsMargins(0, 0, 0, 0);
30 |
31 | m_controlsLayout = new QVBoxLayout;
32 | m_controlsLayout->addStretch();
33 | m_controlsLayout->addWidget(m_headerPixmapLabel);
34 | m_controlsLayout->addWidget(m_headerLabel);
35 | m_controlsLayout->addSpacing(40);
36 |
37 | auto* const controlsSqueezedLayout = new QHBoxLayout;
38 | controlsSqueezedLayout->addStretch();
39 | controlsSqueezedLayout->addLayout(m_controlsLayout);
40 | controlsSqueezedLayout->addStretch();
41 |
42 | m_okButton->setEnabled(true);
43 |
44 | auto* const mainLayout = new QVBoxLayout;
45 | mainLayout->addLayout(controlsSqueezedLayout);
46 | mainLayout->addLayout(m_buttonLayout);
47 | setLayout(mainLayout);
48 |
49 | auto* const okShortCut = new QShortcut(QKeySequence(Qt::Key_Return), this);
50 |
51 | connect(m_findSourceButton, &QPushButton::clicked, this, &TopicListingInputWidget::sourceButtonPressed);
52 | connect(m_okButton, &QPushButton::clicked, this, &TopicListingInputWidget::okButtonPressed);
53 | connect(okShortCut, &QShortcut::activated, this, &TopicListingInputWidget::okButtonPressed);
54 | }
55 |
56 |
57 | void
58 | TopicListingInputWidget::sourceButtonPressed()
59 | {
60 | const auto fileName = QFileDialog::getSaveFileName(this, "Save Bag File");
61 | if (fileName.isEmpty()) {
62 | return;
63 | }
64 |
65 | writeParameterToSettings(m_parameters.sourceDirectory, fileName, m_settings);
66 | m_sourceLineEdit->setText(fileName);
67 | }
68 |
69 |
70 | void
71 | TopicListingInputWidget::okButtonPressed() const
72 | {
73 | if (m_parameters.sourceDirectory.isEmpty()) {
74 | Utils::UI::createCriticalMessageBox("No bag name specified!", "Please specify a bag name before continuing!");
75 | return;
76 | }
77 |
78 | const auto isValid = areTopicsValid();
79 | if (isValid == std::nullopt) {
80 | return;
81 | }
82 | if (!*isValid) {
83 | Utils::UI::createCriticalMessageBox("Duplicate Topic Names Detected!", "Please make sure that no duplicate topic names are used!");
84 | return;
85 | }
86 |
87 | if (!Utils::UI::continueForExistingTarget(m_parameters.sourceDirectory, "Bagfile", "bag file")) {
88 | return;
89 | }
90 |
91 | emit okPressed();
92 | }
93 |
94 |
95 | void
96 | TopicListingInputWidget::setPixmapLabelIcon() const
97 | {
98 | const auto isDarkMode = Utils::UI::isDarkMode();
99 | m_headerPixmapLabel->setPixmap(QIcon(isDarkMode ? m_iconPath + "_white.svg" : m_iconPath + "_black.svg").pixmap(QSize(100, 45)));
100 | m_addTopicButton->setIcon(QIcon(isDarkMode ? ":/icons/plus_white.svg" : ":/icons/plus_black.svg"));
101 | }
102 |
103 |
104 | bool
105 | TopicListingInputWidget::event(QEvent *event)
106 | {
107 | [[unlikely]] if (event->type() == QEvent::ApplicationPaletteChange || event->type() == QEvent::PaletteChange) {
108 | setPixmapLabelIcon();
109 | }
110 | return QWidget::event(event);
111 | }
112 |
--------------------------------------------------------------------------------
/src/ui/HelperWidgets/TopicListingInputWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicInputWidget.hpp"
4 | #include "BasicSettings.hpp"
5 | #include "Parameters.hpp"
6 |
7 | #include
8 | #include
9 |
10 | #include
11 |
12 | class TopicWidget;
13 |
14 | class QFormLayout;
15 | class QHBoxLayout;
16 | class QLabel;
17 | class QToolButton;
18 | class QVBoxLayout;
19 |
20 | // A widget showing widgets to add and remove topics
21 | class TopicListingInputWidget : public BasicInputWidget
22 | {
23 | Q_OBJECT
24 | public:
25 | explicit
26 | TopicListingInputWidget(Parameters::BasicParameters& parameters,
27 | const QString& titleText,
28 | const QString& iconText,
29 | const QString& settingsIdentifierText,
30 | QWidget* parent = 0);
31 |
32 | protected slots:
33 | void
34 | sourceButtonPressed();
35 |
36 | void
37 | okButtonPressed() const;
38 |
39 | protected:
40 | virtual std::optional
41 | areTopicsValid() const = 0;
42 |
43 | // Have to overwrite this one because we are using more additional icons then just the top one
44 | void
45 | setPixmapLabelIcon() const;
46 |
47 | bool
48 | event(QEvent *event);
49 |
50 | protected:
51 | // A QFormLayout provides no easy access to layout labels, so we keep them
52 | // in an extra vector for renaming after a row was removed
53 | QVector > m_topicLabels;
54 | QVector > m_topicWidgets;
55 |
56 | QPointer m_addTopicButton;
57 |
58 | QPointer m_formLayout;
59 | QPointer m_topicButtonLayout;
60 | QPointer m_controlsLayout;
61 |
62 | int m_numberOfTopics = 0;
63 |
64 | private:
65 | Parameters::BasicParameters& m_parameters;
66 |
67 | BasicSettings m_settings;
68 | };
69 |
--------------------------------------------------------------------------------
/src/ui/HelperWidgets/TopicWidget.cpp:
--------------------------------------------------------------------------------
1 | #include "TopicWidget.hpp"
2 |
3 | #include "UtilsROS.hpp"
4 | #include "UtilsUI.hpp"
5 |
6 | #include
7 | #include
8 | #include
9 | #include
10 | #include
11 | #include
12 |
13 | TopicWidget::TopicWidget(bool isDummyWidget, bool addRemoveButton, const QString& topicTypeText,
14 | const QString& topicNameText, QWidget *parent) :
15 | QWidget(parent)
16 | {
17 | m_topicNameLineEdit = new QLineEdit(topicNameText);
18 | m_topicNameLineEdit->setPlaceholderText("Enter Topic Name...");
19 |
20 | m_removeTopicButton = new QToolButton;
21 | m_removeTopicButton->setToolTip("Remove the topic on the left.");
22 | auto sizePolicy = m_removeTopicButton->sizePolicy();
23 | sizePolicy.setRetainSizeWhenHidden(true);
24 | m_removeTopicButton->setSizePolicy(sizePolicy);
25 |
26 | auto* const mainLayout = new QHBoxLayout;
27 | if (isDummyWidget) {
28 | auto* const topicTypeComboBox = new QComboBox;
29 | topicTypeComboBox->addItem("String", 0);
30 | topicTypeComboBox->addItem("Integer", 1);
31 | topicTypeComboBox->addItem("Image", 2);
32 | topicTypeComboBox->addItem("Point Cloud", 3);
33 | if (!topicTypeText.isEmpty()) {
34 | topicTypeComboBox->setCurrentText(topicTypeText);
35 | }
36 |
37 | mainLayout->addWidget(topicTypeComboBox);
38 |
39 | connect(topicTypeComboBox, &QComboBox::currentTextChanged, this, [this] (const QString& text) {
40 | emit topicTypeChanged(text);
41 | });
42 | } else {
43 | const auto& currentTopicsAndTypes = Utils::ROS::getTopicInformation();
44 | QStringList wordList;
45 | for (const auto& currentTopic : currentTopicsAndTypes) {
46 | wordList.append(QString::fromStdString(currentTopic.first));
47 | }
48 |
49 | auto* const completer = new QCompleter(wordList);
50 | completer->setCaseSensitivity(Qt::CaseInsensitive);
51 | m_topicNameLineEdit->setCompleter(completer);
52 | }
53 |
54 | mainLayout->addWidget(m_topicNameLineEdit);
55 | mainLayout->addWidget(m_removeTopicButton);
56 | m_removeTopicButton->setVisible(addRemoveButton);
57 |
58 | setLayout(mainLayout);
59 | // This widget will be integrated into other widgets where extra space would look bad
60 | // So remove all space around the widget itself
61 | mainLayout->setSpacing(0);
62 | mainLayout->setContentsMargins(0, 0, 0, 0);
63 |
64 | connect(m_removeTopicButton, &QPushButton::clicked, this, [this] {
65 | emit topicRemoveButtonClicked();
66 | });
67 | connect(m_topicNameLineEdit, &QLineEdit::textChanged, this, [this] (const QString& text) {
68 | emit topicNameChanged(text);
69 | });
70 |
71 | setPixmapLabelIcon();
72 | }
73 |
74 |
75 | void
76 | TopicWidget::setPixmapLabelIcon() const
77 | {
78 | if (!m_removeTopicButton) {
79 | return;
80 | }
81 |
82 | const auto isDarkMode = Utils::UI::isDarkMode();
83 | m_removeTopicButton->setIcon(QIcon(isDarkMode ? ":/icons/minus_white.svg" : ":/icons/minus_black.svg"));
84 | }
85 |
86 |
87 | bool
88 | TopicWidget::event(QEvent *event)
89 | {
90 | [[unlikely]] if (event->type() == QEvent::ApplicationPaletteChange || event->type() == QEvent::PaletteChange) {
91 | setPixmapLabelIcon();
92 | }
93 | return QWidget::event(event);
94 | }
95 |
--------------------------------------------------------------------------------
/src/ui/HelperWidgets/TopicWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 | #include
5 | #include
6 |
7 | class QToolButton;
8 |
9 | // Small helper widget used to select a topic type for the ROS bag dummy creation
10 | class TopicWidget : public QWidget
11 | {
12 | Q_OBJECT
13 |
14 | public:
15 | TopicWidget(bool isDummyWidget,
16 | bool addRemoveButton,
17 | const QString& topicTypeText = "",
18 | const QString& topicNameText = "",
19 | QWidget* parent = 0);
20 |
21 | const QString
22 | getTopicName() const
23 | {
24 | return m_topicNameLineEdit->text();
25 | }
26 |
27 | signals:
28 | void
29 | topicTypeChanged(QString type);
30 |
31 | void
32 | topicNameChanged(QString name);
33 |
34 | void
35 | topicRemoveButtonClicked();
36 |
37 | private:
38 | void
39 | setPixmapLabelIcon() const;
40 |
41 | bool
42 | event(QEvent *event);
43 |
44 | private:
45 | QPointer m_topicNameLineEdit;
46 | QPointer m_removeTopicButton;
47 | };
48 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/AdvancedInputWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AdvancedSettings.hpp"
4 | #include "BasicInputWidget.hpp"
5 | #include "Parameters.hpp"
6 |
7 | class QComboBox;
8 | class QFormLayout;
9 | class QLineEdit;
10 | class QVBoxLayout;
11 |
12 | // Derived from basic input, provides functions to search for an input bag or a target directory
13 | class AdvancedInputWidget : public BasicInputWidget
14 | {
15 | Q_OBJECT
16 |
17 | public:
18 | AdvancedInputWidget(Parameters::AdvancedParameters& parameters,
19 | const QString& headerText,
20 | const QString& iconPath,
21 | const QString& sourceFormLayoutName,
22 | const QString& targetFormLayoutName,
23 | const QString& settingsIdentifier,
24 | int outputFormat,
25 | QWidget* parent = 0);
26 |
27 | protected slots:
28 | virtual void
29 | findSourceButtonPressed();
30 |
31 | void
32 | findTargetButtonPressed();
33 |
34 | virtual void
35 | okButtonPressed() const;
36 |
37 | void
38 | setVideoFormat(const QString& videoFormat)
39 | {
40 | m_videoFormat = videoFormat;
41 | }
42 |
43 | protected:
44 | QPointer m_topicNameComboBox;
45 | QPointer m_targetLineEdit;
46 |
47 | QPointer m_basicOptionsFormLayout;
48 | QPointer m_controlsLayout;
49 |
50 | static constexpr int OUTPUT_VIDEO = 0;
51 | static constexpr int OUTPUT_IMAGES = 1;
52 | static constexpr int OUTPUT_PCDS = 2;
53 | static constexpr int OUTPUT_BAG = 3;
54 |
55 | private:
56 | Parameters::AdvancedParameters& m_parameters;
57 |
58 | AdvancedSettings m_settings;
59 |
60 | QString m_videoFormat;
61 |
62 | const int m_outputFormat;
63 | };
64 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/BagInfoWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicInputWidget.hpp"
4 |
5 | #include
6 | #include
7 |
8 | class QTreeWidget;
9 |
10 | // The widget showing bag info data
11 | class BagInfoWidget : public BasicInputWidget
12 | {
13 | Q_OBJECT
14 | public:
15 | explicit
16 | BagInfoWidget(QWidget* parent = 0);
17 |
18 | private slots:
19 | void
20 | displayBagInfo();
21 |
22 | private:
23 | // Main tree used to display bag info
24 | QPointer m_infoTreeWidget;
25 |
26 | static constexpr int COL_DESCRIPTION = 0;
27 | static constexpr int COL_INFORMATION = 1;
28 | };
29 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/BagToImagesWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AdvancedInputWidget.hpp"
4 | #include "BagToImagesSettings.hpp"
5 | #include "Parameters.hpp"
6 |
7 | class QCheckBox;
8 | class QFormLayout;
9 | class QLineEdit;
10 | class QSlider;
11 |
12 | // The widget used to manage writing images out of a ROS bag
13 | class BagToImagesWidget : public AdvancedInputWidget
14 | {
15 | Q_OBJECT
16 |
17 | public:
18 | BagToImagesWidget(Parameters::BagToImagesParameters& parameters,
19 | QWidget* parent = 0);
20 |
21 | private slots:
22 | void
23 | adjustWidgetsToChangedFormat(const QString& text);
24 |
25 | private:
26 | QPointer m_qualitySlider;
27 | QPointer m_optimizeOrBilevelCheckBox;
28 |
29 | QPointer m_advancedOptionsFormLayout;
30 |
31 | Parameters::BagToImagesParameters& m_parameters;
32 |
33 | BagToImagesSettings m_settings;
34 | };
35 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/BagToPCDsWidget.cpp:
--------------------------------------------------------------------------------
1 | #include "BagToPCDsWidget.hpp"
2 |
3 | #include "UtilsUI.hpp"
4 |
5 | #include
6 | #include
7 | #include
8 |
9 | BagToPCDsWidget::BagToPCDsWidget(Parameters::AdvancedParameters& parameters, QWidget *parent) :
10 | AdvancedInputWidget(parameters, "Bag to PCD Files", ":/icons/bag_to_pcd", "Bag File:", "PCDs Location:", "bag_to_pcds", OUTPUT_PCDS, parent),
11 | m_parameters(parameters), m_settings(parameters, "bag_to_pcds")
12 | {
13 | m_sourceLineEdit->setToolTip("The source bag file directory.");
14 | m_topicNameComboBox->setToolTip("The point cloud bag topic.\nIf the bag contains multiple point cloud topics, you can choose one of them.");
15 | m_targetLineEdit->setToolTip("The target point cloud files directory.");
16 |
17 | m_basicOptionsFormLayout->insertRow(1, "Topic Name:", m_topicNameComboBox);
18 |
19 | m_controlsLayout->addStretch();
20 |
21 | // Generally, only enable this if the source bag, topic name and target dir line edit contain text
22 | enableOkButton(!m_parameters.sourceDirectory.isEmpty() &&
23 | !m_parameters.topicName.isEmpty() && !m_parameters.targetDirectory.isEmpty());
24 | }
25 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/BagToPCDsWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AdvancedInputWidget.hpp"
4 | #include "AdvancedSettings.hpp"
5 | #include "Parameters.hpp"
6 |
7 | class QComboBox;
8 | class QLineEdit;
9 |
10 | // The widget used to manage writing pcd files out of a ROS bag
11 | class BagToPCDsWidget : public AdvancedInputWidget
12 | {
13 | Q_OBJECT
14 |
15 | public:
16 | BagToPCDsWidget(Parameters::AdvancedParameters& parameters,
17 | QWidget* parent = 0);
18 |
19 | private:
20 | Parameters::AdvancedParameters& m_parameters;
21 |
22 | AdvancedSettings m_settings;
23 | };
24 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/BagToVideoWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AdvancedInputWidget.hpp"
4 | #include "BagToVideoSettings.hpp"
5 | #include "Parameters.hpp"
6 |
7 | #include
8 | #include
9 |
10 | class QCheckBox;
11 | class QComboBox;
12 | class QFormLayout;
13 |
14 | // Widget used to configure a video encoding out of a ros bag
15 | class BagToVideoWidget : public AdvancedInputWidget
16 | {
17 | Q_OBJECT
18 |
19 | public:
20 | BagToVideoWidget(Parameters::BagToVideoParameters& parameters,
21 | QWidget* parent = 0);
22 |
23 | private slots:
24 | void
25 | formatComboBoxTextChanged(const QString& text);
26 |
27 | private:
28 | QPointer m_formatComboBox;
29 | QPointer m_advancedOptionsFormLayout;
30 | QPointer m_useLosslessCheckBox;
31 |
32 | Parameters::BagToVideoParameters& m_parameters;
33 |
34 | BagToVideoSettings m_settings;
35 | };
36 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/BasicInputWidget.cpp:
--------------------------------------------------------------------------------
1 | #include "BasicInputWidget.hpp"
2 |
3 | #include "UtilsUI.hpp"
4 |
5 | #include
6 | #include
7 | #include
8 | #include
9 | #include
10 | #include
11 |
12 | #include
13 |
14 | BasicInputWidget::BasicInputWidget(const QString& headerText, const QString& iconPath, QWidget *parent) :
15 | QWidget(parent), m_iconPath(iconPath)
16 | {
17 | m_headerLabel = new QLabel(headerText);
18 | Utils::UI::setWidgetFontSize(m_headerLabel);
19 | m_headerLabel->setAlignment(Qt::AlignHCenter);
20 |
21 | m_headerPixmapLabel = new QLabel;
22 | m_headerPixmapLabel->setAlignment(Qt::AlignHCenter);
23 | setPixmapLabelIcon();
24 |
25 | m_sourceLineEdit = new QLineEdit;
26 | m_findSourceButton = new QToolButton;
27 |
28 | m_backButton = new QPushButton("Back", this);
29 | m_okButton = new QPushButton("Ok", this);
30 | m_okButton->setEnabled(false);
31 |
32 | m_dialogButtonBox = new QDialogButtonBox;
33 | m_dialogButtonBox->addButton(m_okButton, QDialogButtonBox::AcceptRole);
34 | // Layout can be already complete
35 | m_findSourceLayout = Utils::UI::createLineEditButtonLayout(m_sourceLineEdit, m_findSourceButton);
36 |
37 | m_buttonLayout = new QHBoxLayout;
38 | m_buttonLayout->addWidget(m_backButton);
39 | m_buttonLayout->addStretch();
40 | m_buttonLayout->addWidget(m_dialogButtonBox);
41 |
42 | connect(m_backButton, &QPushButton::clicked, this, [this] {
43 | emit back();
44 | });
45 | }
46 |
47 |
48 | void
49 | BasicInputWidget::enableOkButton(bool enable) const
50 | {
51 | m_okButton->setEnabled(enable);
52 | }
53 |
54 |
55 | void
56 | BasicInputWidget::setPixmapLabelIcon() const
57 | {
58 | const auto isDarkMode = Utils::UI::isDarkMode();
59 | // Don't need to provide full name, appendix is always the same
60 | m_headerPixmapLabel->setPixmap(QIcon(isDarkMode ? m_iconPath + "_white.svg" : m_iconPath + "_black.svg").pixmap(QSize(100, 45)));
61 | }
62 |
63 |
64 | bool
65 | BasicInputWidget::event(QEvent *event)
66 | {
67 | [[unlikely]] if (event->type() == QEvent::ApplicationPaletteChange || event->type() == QEvent::PaletteChange) {
68 | setPixmapLabelIcon();
69 | }
70 | return QWidget::event(event);
71 | }
72 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/BasicInputWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicSettings.hpp"
4 |
5 | #include
6 | #include
7 |
8 | class QDialogButtonBox;
9 | class QHBoxLayout;
10 | class QLabel;
11 | class QLineEdit;
12 | class QPushButton;
13 | class QToolButton;
14 |
15 | template
16 | concept InputParameterSetting = (std::same_as &&
17 | (std::same_as || std::same_as ||
18 | std::same_as || std::same_as));
19 |
20 | // The basic input widget all other input widgets derive from
21 | // Each input widget uses a corresponding parameter and settings member.
22 | // The parameters are used to store all input for reusing if the widget is closed and opened again,
23 | // while the settings are used to write the parameters to file in case the parameters should be
24 | // used after closing and restarting the application.
25 |
26 | // The basic widget provides a few members and functions used by all derived members.
27 | class BasicInputWidget : public QWidget
28 | {
29 | Q_OBJECT
30 |
31 | public:
32 | // Set the header text and top icon automatically
33 | BasicInputWidget(const QString& headerText,
34 | const QString& iconPath,
35 | QWidget* parent = 0);
36 |
37 | signals:
38 | void
39 | back() const;
40 |
41 | void
42 | okPressed() const;
43 |
44 | protected:
45 | void
46 | enableOkButton(bool enable) const;
47 |
48 | void
49 | setPixmapLabelIcon() const;
50 |
51 | bool
52 | event(QEvent *event) override;
53 |
54 | template
55 | requires InputParameterSetting
56 | void
57 | writeParameterToSettings(T& settingsParameter,
58 | const U& newValue,
59 | BasicSettings& inputSettings) const
60 | {
61 | settingsParameter = newValue;
62 | inputSettings.write();
63 | }
64 |
65 | protected:
66 | QPointer m_headerLabel;
67 | QPointer m_headerPixmapLabel;
68 | // All input widgets need some sort of source file, provide it here
69 | QPointer m_sourceLineEdit;
70 | QPointer m_findSourceButton;
71 | // Also need an ok and cancel button
72 | QPointer m_backButton;
73 | QPointer m_okButton;
74 |
75 | QPointer m_findSourceLayout;
76 | QPointer m_buttonLayout;
77 | QPointer m_dialogButtonBox;
78 |
79 | QString m_iconPath;
80 | };
81 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | add_library (rt_input_widgets INTERFACE)
2 |
3 | target_include_directories (rt_input_widgets
4 | INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}
5 | )
6 |
7 | target_sources(rt_input_widgets INTERFACE
8 | ${CMAKE_CURRENT_LIST_DIR}/AdvancedInputWidget.cpp
9 | ${CMAKE_CURRENT_LIST_DIR}/AdvancedInputWidget.hpp
10 | ${CMAKE_CURRENT_LIST_DIR}/BagInfoWidget.cpp
11 | ${CMAKE_CURRENT_LIST_DIR}/BagInfoWidget.hpp
12 | ${CMAKE_CURRENT_LIST_DIR}/BagToPCDsWidget.cpp
13 | ${CMAKE_CURRENT_LIST_DIR}/BagToPCDsWidget.hpp
14 | ${CMAKE_CURRENT_LIST_DIR}/BagToImagesWidget.cpp
15 | ${CMAKE_CURRENT_LIST_DIR}/BagToImagesWidget.hpp
16 | ${CMAKE_CURRENT_LIST_DIR}/BagToVideoWidget.cpp
17 | ${CMAKE_CURRENT_LIST_DIR}/BagToVideoWidget.hpp
18 | ${CMAKE_CURRENT_LIST_DIR}/BasicInputWidget.cpp
19 | ${CMAKE_CURRENT_LIST_DIR}/BasicInputWidget.hpp
20 | ${CMAKE_CURRENT_LIST_DIR}/ChangeCompressionWidget.cpp
21 | ${CMAKE_CURRENT_LIST_DIR}/ChangeCompressionWidget.hpp
22 | ${CMAKE_CURRENT_LIST_DIR}/DummyBagWidget.cpp
23 | ${CMAKE_CURRENT_LIST_DIR}/DummyBagWidget.hpp
24 | ${CMAKE_CURRENT_LIST_DIR}/EditBagWidget.cpp
25 | ${CMAKE_CURRENT_LIST_DIR}/EditBagWidget.hpp
26 | ${CMAKE_CURRENT_LIST_DIR}/MergeBagsWidget.cpp
27 | ${CMAKE_CURRENT_LIST_DIR}/MergeBagsWidget.hpp
28 | ${CMAKE_CURRENT_LIST_DIR}/PCDsToBagWidget.cpp
29 | ${CMAKE_CURRENT_LIST_DIR}/PCDsToBagWidget.hpp
30 | ${CMAKE_CURRENT_LIST_DIR}/PublishWidget.cpp
31 | ${CMAKE_CURRENT_LIST_DIR}/PublishWidget.hpp
32 | ${CMAKE_CURRENT_LIST_DIR}/RecordBagWidget.cpp
33 | ${CMAKE_CURRENT_LIST_DIR}/RecordBagWidget.hpp
34 | ${CMAKE_CURRENT_LIST_DIR}/TopicsServicesInfoWidget.cpp
35 | ${CMAKE_CURRENT_LIST_DIR}/TopicsServicesInfoWidget.hpp
36 | ${CMAKE_CURRENT_LIST_DIR}/VideoToBagWidget.cpp
37 | ${CMAKE_CURRENT_LIST_DIR}/VideoToBagWidget.hpp
38 | )
39 |
40 | target_link_libraries(rt_input_widgets
41 | INTERFACE Qt::Widgets rt_helper_widgets rt_settings_input rt_utils
42 | )
43 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/ChangeCompressionWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicInputWidget.hpp"
4 | #include "CompressBagSettings.hpp"
5 | #include "Parameters.hpp"
6 |
7 | class QComboBox;
8 | class QLineEdit;
9 |
10 | // The widget used to manage compressing a bag file
11 | class ChangeCompressionWidget : public BasicInputWidget
12 | {
13 | Q_OBJECT
14 |
15 | public:
16 | ChangeCompressionWidget(Parameters::CompressBagParameters& parameters,
17 | bool compress,
18 | QWidget* parent = 0);
19 |
20 | private slots:
21 | void
22 | sourceButtonPressed();
23 |
24 | void
25 | targetButtonPressed();
26 |
27 | void
28 | okButtonPressed() const;
29 |
30 | private:
31 | [[nodiscard]] bool
32 | isBagFileValid(const QString& bagDirectory) const;
33 |
34 | private:
35 | QPointer m_targetLineEdit;
36 |
37 | Parameters::CompressBagParameters& m_parameters;
38 |
39 | CompressBagSettings m_settings;
40 |
41 | bool m_compress;
42 | };
43 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/DummyBagWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "DummyBagSettings.hpp"
4 | #include "Parameters.hpp"
5 | #include "TopicListingInputWidget.hpp"
6 |
7 | #include
8 | #include
9 |
10 | class QSpinBox;
11 |
12 | // Widget used to manage creating a ROS bag with dummy data
13 | class DummyBagWidget : public TopicListingInputWidget
14 | {
15 | Q_OBJECT
16 |
17 | public:
18 | DummyBagWidget(Parameters::DummyBagParameters& parameters,
19 | bool checkROS2NameConform,
20 | QWidget* parent = 0);
21 |
22 | private slots:
23 | void
24 | removeDummyTopicWidget(int row);
25 |
26 | void
27 | createNewDummyTopicWidget(const Parameters::DummyBagParameters::DummyBagTopic& topics,
28 | int index);
29 |
30 | void
31 | useCustomRateCheckBoxPressed(int state);
32 |
33 | private:
34 | std::optional
35 | areTopicsValid() const override;
36 |
37 | private:
38 | QPointer m_rateSpinBox;
39 |
40 | Parameters::DummyBagParameters& m_parameters;
41 |
42 | DummyBagSettings m_settings;
43 |
44 | const bool m_checkROS2NameConform;
45 |
46 | static constexpr int MAXIMUM_NUMBER_OF_TOPICS = 4;
47 | };
48 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/EditBagWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicBagWidget.hpp"
4 | #include "EditBagSettings.hpp"
5 | #include "Parameters.hpp"
6 |
7 | #include
8 | #include
9 |
10 | class QCheckBox;
11 | class QLabel;
12 |
13 | // Widget for editing a bag file
14 | class EditBagWidget : public BasicBagWidget
15 | {
16 | Q_OBJECT
17 | public:
18 | explicit
19 | EditBagWidget(Parameters::EditBagParameters& parameters,
20 | bool checkROS2NameConform,
21 | QWidget* parent = 0);
22 |
23 | private slots:
24 | void
25 | createTopicTree(bool newTreeRequested);
26 |
27 | void
28 | itemCheckStateChanged(QTreeWidgetItem* item,
29 | int column) override;
30 |
31 | void
32 | okButtonPressed() const;
33 |
34 | private:
35 | QPointer m_editLabel;
36 | QPointer m_differentDirsLabel;
37 |
38 | QPointer m_updateTimestampsCheckBox;
39 |
40 | Parameters::EditBagParameters& m_parameters;
41 |
42 | EditBagSettings m_settings;
43 |
44 | const bool m_checkROS2NameConform;
45 |
46 | static constexpr int COL_MESSAGE_COUNT = 3;
47 | static constexpr int COL_RENAMING = 4;
48 |
49 | static constexpr int BUFFER_SPACE = 200;
50 | };
51 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/MergeBagsWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicBagWidget.hpp"
4 | #include "MergeBagsSettings.hpp"
5 | #include "Parameters.hpp"
6 |
7 | #include
8 | #include
9 | #include
10 |
11 | // Widget for editing a bag file
12 | class MergeBagsWidget : public BasicBagWidget
13 | {
14 | Q_OBJECT
15 | public:
16 | explicit
17 | MergeBagsWidget(Parameters::MergeBagsParameters& mergeBagParameters,
18 | QWidget* parent = 0);
19 |
20 | private slots:
21 | void
22 | setSourceDirectory(bool isFirstSource);
23 |
24 | void
25 | createTopicTree(bool resetTopicsParameter);
26 |
27 | void
28 | itemCheckStateChanged(QTreeWidgetItem* item,
29 | int column) override;
30 |
31 | void
32 | okButtonPressed() const;
33 |
34 | private:
35 | QPointer m_secondSourceLineEdit;
36 |
37 | QPointer m_sufficientSpaceLabel;
38 |
39 | Parameters::MergeBagsParameters& m_parameters;
40 |
41 | MergeBagsSettings m_settings;
42 | };
43 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/PCDsToBagWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AdvancedInputWidget.hpp"
4 | #include "PCDsToBagSettings.hpp"
5 | #include "Parameters.hpp"
6 |
7 | #include
8 | #include
9 |
10 | // Widget used to write pcd files to a ROS bag file
11 | class PCDsToBagWidget : public AdvancedInputWidget
12 | {
13 | Q_OBJECT
14 |
15 | public:
16 | PCDsToBagWidget(Parameters::PCDsToBagParameters& parameters,
17 | bool usePredefinedTopicName,
18 | bool checkROS2NameConform,
19 | QWidget* parent = 0);
20 |
21 | private slots:
22 | void
23 | findSourceButtonPressed() override;
24 |
25 | void
26 | okButtonPressed() const override;
27 |
28 | private:
29 | Parameters::PCDsToBagParameters& m_parameters;
30 |
31 | PCDsToBagSettings m_settings;
32 |
33 | const bool m_checkROS2NameConform;
34 | };
35 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/PublishWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicInputWidget.hpp"
4 | #include "Parameters.hpp"
5 | #include "PublishSettings.hpp"
6 |
7 | #include
8 | #include
9 |
10 | class QFormLayout;
11 | class QLineEdit;
12 | class QSpinBox;
13 |
14 | // Widget used to configure publishing a video OR image sequence as ROS messages
15 | class PublishWidget : public BasicInputWidget
16 | {
17 | Q_OBJECT
18 |
19 | public:
20 | PublishWidget(Parameters::PublishParameters& parameters,
21 | bool usePredefinedTopicName,
22 | bool checkROS2NameConform,
23 | bool publishVideo,
24 | QWidget* parent = 0);
25 |
26 | private slots:
27 | void
28 | searchButtonPressed();
29 |
30 | void
31 | scaleCheckBoxPressed(int state);
32 |
33 | void
34 | okButtonPressed() const;
35 |
36 | private:
37 | QPointer m_topicNameLineEdit;
38 | QPointer m_advancedOptionsFormLayout;
39 | QPointer m_widthSpinBox;
40 | QPointer m_heightSpinBox;
41 |
42 | Parameters::PublishParameters& m_parameters;
43 |
44 | PublishSettings m_settings;
45 |
46 | const bool m_checkROS2NameConform;
47 | const bool m_publishVideo;
48 | };
49 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/RecordBagWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "Parameters.hpp"
4 | #include "RecordBagSettings.hpp"
5 | #include "TopicListingInputWidget.hpp"
6 |
7 | #include
8 |
9 | class QLineEdit;
10 | class QWidget;
11 |
12 | // Widget used to manage recording a bag file
13 | class RecordBagWidget : public TopicListingInputWidget
14 | {
15 | Q_OBJECT
16 |
17 | public:
18 | RecordBagWidget(Parameters::RecordBagParameters& parameters,
19 | QWidget* parent = 0);
20 |
21 | private slots:
22 | void
23 | removeLineEdit(int row);
24 |
25 | void
26 | createNewTopicLineEdit(const QString& topicName,
27 | int index);
28 |
29 | private:
30 | std::optional
31 | areTopicsValid() const override;
32 |
33 | private:
34 | QVector > m_topicLineEdits;
35 |
36 | Parameters::RecordBagParameters& m_parameters;
37 |
38 | RecordBagSettings m_settings;
39 | };
40 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/TopicsServicesInfoWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicInputWidget.hpp"
4 |
5 | #include
6 | #include
7 |
8 | class QTreeWidget;
9 |
10 | // The widget showing topics and services info data
11 | class TopicsServicesInfoWidget : public BasicInputWidget
12 | {
13 | Q_OBJECT
14 | public:
15 | explicit
16 | TopicsServicesInfoWidget(QWidget* parent = 0);
17 |
18 | private:
19 | void
20 | fillTree() const;
21 |
22 | private:
23 | QPointer m_treeWidget;
24 |
25 | static constexpr int COL_NAME = 0;
26 | static constexpr int COL_TYPE = 1;
27 | };
28 |
--------------------------------------------------------------------------------
/src/ui/InputWidgets/VideoToBagWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AdvancedInputWidget.hpp"
4 | #include "Parameters.hpp"
5 | #include "VideoToBagSettings.hpp"
6 |
7 | #include
8 | #include
9 |
10 | class QFormLayout;
11 | class QSpinBox;
12 |
13 | // Widget used to write a video file to a ROS bag file
14 | class VideoToBagWidget : public AdvancedInputWidget
15 | {
16 | Q_OBJECT
17 |
18 | public:
19 | VideoToBagWidget(Parameters::VideoToBagParameters& parameters,
20 | bool usePredefinedTopicName,
21 | bool checkROS2NameConform,
22 | QWidget* parent = 0);
23 |
24 | private slots:
25 | void
26 | findSourceButtonPressed() override;
27 |
28 | void
29 | useCustomFPSCheckBoxPressed(int state);
30 |
31 | void
32 | okButtonPressed() const override;
33 |
34 | private:
35 | QPointer m_advancedOptionsFormLayout;
36 | QPointer m_fpsSpinBox;
37 |
38 | Parameters::VideoToBagParameters& m_parameters;
39 |
40 | VideoToBagSettings m_settings;
41 |
42 | const bool m_checkROS2NameConform;
43 | };
44 |
--------------------------------------------------------------------------------
/src/ui/MainWindow.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "Parameters.hpp"
4 | #include "UtilsUI.hpp"
5 |
6 | #include
7 |
8 | // Main window displaying the main user interface. The basic workflow is as follows:
9 | // The main window uses the start widget to show all availabe tools. If the start widget is called,
10 | // this will call a corresponding input widget where a user can modify all necessary parameters.
11 | // If done, the input widget will be replaced with a progress widget showing the current progress.
12 | // The progress widget calls a separate thread performing the main operation in the background.
13 | class MainWindow : public QMainWindow
14 | {
15 | Q_OBJECT
16 |
17 | public:
18 | MainWindow();
19 |
20 | private slots:
21 | // Used to switch between start, input and progress widget
22 | void
23 | setStartWidget();
24 |
25 | void
26 | setInputWidget(Utils::UI::TOOL_ID mode);
27 |
28 | void
29 | setProgressWidget(Utils::UI::TOOL_ID mode);
30 |
31 | private:
32 | void
33 | closeEvent(QCloseEvent *event) override;
34 |
35 | private:
36 | // Parameters storing all configurations done by a user in the input widgets.
37 | // The parameters are transferred to the progress widget and their thread.
38 | Parameters::BagToVideoParameters m_parametersBagToVideo;
39 | Parameters::VideoToBagParameters m_parametersVideoToBag;
40 | Parameters::AdvancedParameters m_parametersBagToPCDs;
41 | Parameters::PCDsToBagParameters m_parametersPCDsToBag;
42 | Parameters::BagToImagesParameters m_parametersBagToImages;
43 | Parameters::EditBagParameters m_parametersEditBag;
44 | Parameters::MergeBagsParameters m_parametersMergeBags;
45 | Parameters::RecordBagParameters m_parametersRecordBag;
46 | Parameters::DummyBagParameters m_parametersDummyBag;
47 | Parameters::CompressBagParameters m_parametersCompressBag;
48 | Parameters::CompressBagParameters m_parametersDecompressBag;
49 |
50 | Parameters::PublishParameters m_parametersPublishVideo;
51 | Parameters::PublishParameters m_parametersPublishImages;
52 | // Parameters for settings dialog
53 | Parameters::DialogParameters m_dialogParameters;
54 |
55 | static constexpr int DEFAULT_WIDTH = 450;
56 | static constexpr int DEFAULT_HEIGHT = 600;
57 | };
58 |
--------------------------------------------------------------------------------
/src/ui/ProgressWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "Parameters.hpp"
4 | #include "UtilsUI.hpp"
5 |
6 | #include
7 | #include
8 | #include
9 |
10 | class BasicThread;
11 |
12 | // Base widget showing overall progress
13 | // The progress widget will access the main thread used to perform the corresponding operation.
14 | // If the user presses the Cancel button, the thread will be cancelled and we'll return to the main window.
15 | class ProgressWidget : public QWidget
16 | {
17 | Q_OBJECT
18 |
19 | public:
20 | ProgressWidget(const QString& headerLabelText,
21 | Parameters::BasicParameters& parameters,
22 | const Utils::UI::TOOL_ID threadTypeId,
23 | QWidget* parent = 0);
24 |
25 | ~ProgressWidget();
26 |
27 | void
28 | startThread();
29 |
30 | signals:
31 | void
32 | progressStopped();
33 |
34 | void
35 | finished();
36 |
37 | private:
38 | bool
39 | event(QEvent *event) override;
40 |
41 | private:
42 | QPointer m_thread;
43 |
44 | QPointer m_movie;
45 | };
46 |
--------------------------------------------------------------------------------
/src/ui/SettingsDialog.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "DialogSettings.hpp"
4 | #include "Parameters.hpp"
5 |
6 | #include
7 |
8 | // Dialog used to modify settings
9 | class SettingsDialog : public QDialog {
10 | Q_OBJECT
11 |
12 | public:
13 | SettingsDialog(Parameters::DialogParameters& parameters,
14 | QWidget* parent = 0);
15 |
16 | private:
17 | void
18 | storeParametersCheckStateChanged();
19 |
20 | private:
21 | Parameters::DialogParameters& m_parameters;
22 |
23 | DialogSettings m_settings;
24 | };
25 |
--------------------------------------------------------------------------------
/src/ui/StartWidget.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "Parameters.hpp"
4 | #include "UtilsUI.hpp"
5 |
6 | #include
7 | #include
8 |
9 | class QLabel;
10 | class QPushButton;
11 | class QToolButton;
12 | class QVBoxLayout;
13 |
14 | // The starting widget showing all available ui tools
15 | class StartWidget : public QWidget
16 | {
17 | Q_OBJECT
18 | public:
19 | explicit
20 | StartWidget(Parameters::DialogParameters& dialogParameters,
21 | QWidget* parent = 0);
22 |
23 | signals:
24 | void
25 | toolRequested(Utils::UI::TOOL_ID id);
26 |
27 | private slots:
28 | void
29 | openSettingsDialog();
30 |
31 | private:
32 | void
33 | replaceWidgets(QWidget* fromWidget,
34 | QWidget* toWidget,
35 | int widgetIdentifier,
36 | bool otherItemVisibility);
37 |
38 | QPointer
39 | createToolButton(const QString& buttonText) const;
40 |
41 | void
42 | setButtonIcons();
43 |
44 | bool
45 | event(QEvent *event) override;
46 |
47 | private:
48 | QPointer m_headerLabel;
49 |
50 | // Buttons for tools
51 | QPointer m_conversionToolsButton;
52 | QPointer m_bagToolsButton;
53 | QPointer m_publishingToolsButton;
54 | QPointer m_infoToolsButton;
55 |
56 | QPointer m_bagToVideoPushButton;
57 | QPointer m_videoToBagPushButton;
58 | QPointer m_bagToPCDsPushButton;
59 | QPointer m_PCDsToBagPushButton;
60 | QPointer m_bagToImagesPushButton;
61 |
62 | QPointer m_editBagButton;
63 | QPointer m_mergeBagsButton;
64 | QPointer m_recordBagButton;
65 | QPointer m_dummyBagButton;
66 | QPointer m_compressBagButton;
67 | QPointer m_decompressBagButton;
68 |
69 | QPointer m_publishVideoButton;
70 | QPointer m_publishImagesButton;
71 |
72 | QPointer m_topicServiceInfoButton;
73 | QPointer m_bagInfoButton;
74 |
75 | // Widgets for other elements
76 | QPointer m_settingsButton;
77 | QPointer m_backButton;
78 | QPointer m_versionLabel;
79 |
80 | QPointer m_mainLayout;
81 |
82 | Parameters::DialogParameters& m_dialogParameters;
83 |
84 | // Used to remember which widget was active when we switch to the input widget, but cancel
85 | inline static int m_widgetOnInstantiation = 0;
86 |
87 | static constexpr int WIDGET_OVERALL = 0;
88 | static constexpr int WIDGET_CONVERSION = 1;
89 | static constexpr int WIDGET_BAG = 2;
90 | static constexpr int WIDGET_PUBLISHING = 3;
91 | static constexpr int WIDGET_INFO = 4;
92 | };
93 |
--------------------------------------------------------------------------------
/src/ui/settings/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | add_subdirectory(input)
2 |
3 | add_library (rt_settings INTERFACE)
4 |
5 | target_include_directories (rt_settings
6 | INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}
7 | )
8 |
9 | target_sources(rt_settings INTERFACE
10 | ${CMAKE_CURRENT_LIST_DIR}/GeneralSettings.hpp
11 | ${CMAKE_CURRENT_LIST_DIR}/DialogSettings.cpp
12 | ${CMAKE_CURRENT_LIST_DIR}/DialogSettings.hpp
13 | )
14 |
15 | target_link_libraries(rt_settings
16 | INTERFACE Qt::Widgets
17 | )
18 |
--------------------------------------------------------------------------------
/src/ui/settings/DialogSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "DialogSettings.hpp"
2 |
3 | DialogSettings::DialogSettings(Parameters::DialogParameters& parameters, const QString& groupName) :
4 | GeneralSettings(groupName), m_parameters(parameters)
5 | {
6 | read();
7 | }
8 |
9 |
10 | bool
11 | DialogSettings::write()
12 | {
13 | writeParameter(m_groupName, "max_threads", m_parameters.maxNumberOfThreads);
14 | writeParameter(m_groupName, "hw_acc", m_parameters.useHardwareAcceleration);
15 | writeParameter(m_groupName, "save_parameters", m_parameters.saveParameters);
16 | writeParameter(m_groupName, "predefined_topic_names", m_parameters.usePredefinedTopicNames);
17 | writeParameter(m_groupName, "check_ros2_naming_convention", m_parameters.checkROS2NameConform);
18 | writeParameter(m_groupName, "ask_for_target_overwrite", m_parameters.askForTargetOverwrite);
19 |
20 | return true;
21 | }
22 |
23 |
24 | bool
25 | DialogSettings::read()
26 | {
27 | m_parameters.maxNumberOfThreads = readParameter(m_groupName, "max_threads", std::thread::hardware_concurrency());
28 | m_parameters.useHardwareAcceleration = readParameter(m_groupName, "hw_acc", false);
29 | m_parameters.saveParameters = readParameter(m_groupName, "save_parameters", false);
30 | m_parameters.usePredefinedTopicNames = readParameter(m_groupName, "predefined_topic_names", true);
31 | m_parameters.checkROS2NameConform = readParameter(m_groupName, "check_ros2_naming_convention", false);
32 | m_parameters.askForTargetOverwrite = readParameter(m_groupName, "ask_for_target_overwrite", true);
33 |
34 | return true;
35 | }
36 |
--------------------------------------------------------------------------------
/src/ui/settings/DialogSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "GeneralSettings.hpp"
4 | #include "Parameters.hpp"
5 |
6 | template
7 | concept DialogSettingsParameter = std::same_as || std::same_as;
8 |
9 | // Settings modified from settings dialog
10 | class DialogSettings : public GeneralSettings {
11 | public:
12 | DialogSettings(Parameters::DialogParameters& parameters,
13 | const QString& groupName);
14 |
15 | // Make these static because we need to access and modify some values from many different places
16 | // without having to use the entire dialog parameter instance
17 | template
18 | requires DialogSettingsParameter
19 | static T
20 | getStaticParameter(const QString& identifier,
21 | T defaultValue)
22 | {
23 | QSettings settings;
24 | settings.beginGroup("dialog");
25 | T staticParameter;
26 |
27 | if constexpr (std::is_same_v) {
28 | staticParameter = settings.value(identifier).isValid() ? settings.value(identifier).toInt() : defaultValue;
29 | } else {
30 | staticParameter = settings.value(identifier).isValid() ? settings.value(identifier).toBool() : defaultValue;
31 | }
32 |
33 | settings.endGroup();
34 | return staticParameter;
35 | }
36 |
37 | template
38 | requires DialogSettingsParameter
39 | static void
40 | writeStaticParameter(const QString& identifier,
41 | T value)
42 | {
43 | QSettings settings;
44 | settings.beginGroup("dialog");
45 |
46 | if (settings.value(identifier).value() == value) {
47 | return;
48 | }
49 |
50 | settings.setValue(identifier, value);
51 | }
52 |
53 | bool
54 | write() override;
55 |
56 | private:
57 | bool
58 | read() override;
59 |
60 | private:
61 | Parameters::DialogParameters& m_parameters;
62 | };
63 |
--------------------------------------------------------------------------------
/src/ui/settings/GeneralSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | template
6 | concept GeneralSettingsParameter = std::same_as || std::same_as || std::same_as ||
7 | std::same_as || std::same_as;
8 |
9 | // Basic settings, from which all other settings derive
10 | // Each setting as write and read functions. Read functions are called automatically
11 | // in the ctor, while the writing is called every time a parameter is changed.
12 | // Settings for the input widgets follow the parameter hierarchy structure defined in Utils/UI
13 | class GeneralSettings {
14 | public:
15 | GeneralSettings(const QString& groupName) : m_groupName(groupName)
16 | {
17 | }
18 |
19 | virtual bool
20 | write() = 0;
21 |
22 | protected:
23 | virtual bool
24 | read() = 0;
25 |
26 | // Called whenever we want to write values
27 | // Variant without settings parameter
28 | template
29 | requires GeneralSettingsParameter
30 | void
31 | writeParameter(const QString& groupName,
32 | const QString& identifier,
33 | T parameter) const
34 | {
35 | QSettings settings;
36 | settings.beginGroup(groupName);
37 |
38 | writeParameter(settings, identifier, parameter);
39 | settings.endGroup();
40 | }
41 |
42 | // Use predefined settings to write
43 | template
44 | requires GeneralSettingsParameter
45 | void
46 | writeParameter(QSettings& settings,
47 | const QString& identifier,
48 | T parameter) const
49 | {
50 | if (settings.value(identifier).value() == parameter) {
51 | return;
52 | }
53 | // Simple conversion between size_t and QVariant is not possible
54 | if constexpr (std::is_same_v) {
55 | QVariant v;
56 | v.setValue(parameter);
57 | settings.setValue(identifier, v);
58 | } else {
59 | settings.setValue(identifier, parameter);
60 | }
61 | }
62 |
63 | // Read without settings parameter
64 | template
65 | requires GeneralSettingsParameter
66 | T
67 | readParameter(const QString& groupName,
68 | const QString& identifier,
69 | T defaultValue) const
70 | {
71 | QSettings settings;
72 | settings.beginGroup(groupName);
73 |
74 | const auto parameter = readParameter(settings, identifier, defaultValue);
75 | settings.endGroup();
76 |
77 | return parameter;
78 | }
79 |
80 | // Read based on stored type, using predefined settings
81 | template
82 | requires GeneralSettingsParameter
83 | T
84 | readParameter(QSettings& settings,
85 | const QString& identifier,
86 | T defaultValue) const
87 | {
88 | T value;
89 | if constexpr (std::is_same_v || std::is_same_v ) {
90 | value = settings.value(identifier).isValid() ? settings.value(identifier).toInt() : defaultValue;
91 | } else if constexpr (std::is_same_v) {
92 | value = settings.value(identifier).value();
93 | } else if constexpr (std::is_same_v) {
94 | value = settings.value(identifier).isValid() ? settings.value(identifier).toBool() : defaultValue;
95 | } else {
96 | value = settings.value(identifier).isValid() ? settings.value(identifier).toString() : defaultValue;
97 | }
98 |
99 | return value;
100 | }
101 |
102 | protected:
103 | const QString m_groupName;
104 | };
105 |
--------------------------------------------------------------------------------
/src/ui/settings/input/AdvancedSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "AdvancedSettings.hpp"
2 |
3 | AdvancedSettings::AdvancedSettings(Parameters::AdvancedParameters& parameters, const QString& groupName) :
4 | BasicSettings(parameters, groupName), m_parameters(parameters)
5 | {
6 | read();
7 | }
8 |
9 |
10 | bool
11 | AdvancedSettings::write()
12 | {
13 | if (!BasicSettings::write()) {
14 | return false;
15 | }
16 |
17 | writeParameter(m_groupName, "target_dir", m_parameters.targetDirectory);
18 | writeParameter(m_groupName, "show_advanced", m_parameters.showAdvancedOptions);
19 |
20 | return true;
21 | }
22 |
23 |
24 | bool
25 | AdvancedSettings::read()
26 | {
27 | if (!BasicSettings::read()) {
28 | return false;
29 | }
30 |
31 | m_parameters.targetDirectory = readParameter(m_groupName, "target_dir", QString(""));
32 | m_parameters.showAdvancedOptions = readParameter(m_groupName, "show_advanced", false);
33 |
34 | return true;
35 | }
36 |
--------------------------------------------------------------------------------
/src/ui/settings/input/AdvancedSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicSettings.hpp"
4 |
5 | // Store advanced settings
6 | class AdvancedSettings : public BasicSettings {
7 | public:
8 | AdvancedSettings(Parameters::AdvancedParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | protected:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::AdvancedParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/BagToImagesSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "BagToImagesSettings.hpp"
2 |
3 | BagToImagesSettings::BagToImagesSettings(Parameters::BagToImagesParameters& parameters, const QString& groupName) :
4 | RGBSettings(parameters, groupName), m_parameters(parameters)
5 | {
6 | read();
7 | }
8 |
9 |
10 | bool
11 | BagToImagesSettings::write()
12 | {
13 | if (!RGBSettings::write()) {
14 | return false;
15 | }
16 |
17 | writeParameter(m_groupName, "format", m_parameters.format);
18 | writeParameter(m_groupName, "quality", m_parameters.quality);
19 | writeParameter(m_groupName, "bw_images", m_parameters.useBWImages);
20 | writeParameter(m_groupName, "jpg_optimize", m_parameters.jpgOptimize);
21 | writeParameter(m_groupName, "png_bilevel", m_parameters.pngBilevel);
22 |
23 | return true;
24 | }
25 |
26 |
27 | bool
28 | BagToImagesSettings::read()
29 | {
30 | if (!RGBSettings::read()) {
31 | return false;
32 | }
33 |
34 | m_parameters.format = readParameter(m_groupName, "format", QString("jpg"));
35 | m_parameters.quality = readParameter(m_groupName, "quality", 8);
36 | m_parameters.useBWImages = readParameter(m_groupName, "bw_images", false);
37 | m_parameters.jpgOptimize = readParameter(m_groupName, "jpg_optimize", false);
38 | m_parameters.pngBilevel = readParameter(m_groupName, "png_bilevel", false);
39 |
40 | return true;
41 | }
42 |
--------------------------------------------------------------------------------
/src/ui/settings/input/BagToImagesSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "RGBSettings.hpp"
4 |
5 | // Store parameters for image sequence out of ROS bag creation
6 | class BagToImagesSettings : public RGBSettings {
7 | public:
8 | BagToImagesSettings(Parameters::BagToImagesParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | private:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::BagToImagesParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/BagToVideoSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "BagToVideoSettings.hpp"
2 |
3 | BagToVideoSettings::BagToVideoSettings(Parameters::BagToVideoParameters& parameters, const QString& groupName) :
4 | VideoSettings(parameters, groupName), m_parameters(parameters)
5 | {
6 | read();
7 | }
8 |
9 |
10 | bool
11 | BagToVideoSettings::write()
12 | {
13 | if (!VideoSettings::write()) {
14 | return false;
15 | }
16 |
17 | writeParameter(m_groupName, "format", m_parameters.format);
18 | writeParameter(m_groupName, "bw_images", m_parameters.useBWImages);
19 | writeParameter(m_groupName, "lossless_images", m_parameters.lossless);
20 |
21 | return true;
22 | }
23 |
24 |
25 | bool
26 | BagToVideoSettings::read()
27 | {
28 | if (!VideoSettings::read()) {
29 | return false;
30 | }
31 |
32 | m_parameters.format = readParameter(m_groupName, "format", QString("mp4"));
33 | m_parameters.useBWImages = readParameter(m_groupName, "bw_images", false);
34 | m_parameters.lossless = readParameter(m_groupName, "lossless_images", false);
35 |
36 | return true;
37 | }
38 |
--------------------------------------------------------------------------------
/src/ui/settings/input/BagToVideoSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "VideoSettings.hpp"
4 |
5 | // Store video out of ROS bag creation parameters
6 | class BagToVideoSettings : public VideoSettings {
7 | public:
8 | BagToVideoSettings(Parameters::BagToVideoParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | private:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::BagToVideoParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/BasicSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "BasicSettings.hpp"
2 |
3 | #include "DialogSettings.hpp"
4 |
5 | BasicSettings::BasicSettings(Parameters::BasicParameters& parameters, const QString& groupName) :
6 | GeneralSettings(groupName), m_parameters(parameters)
7 | {
8 | }
9 |
10 |
11 | bool
12 | BasicSettings::write()
13 | {
14 | if (!DialogSettings::getStaticParameter("save_parameters", false)) {
15 | return false;
16 | }
17 |
18 | writeParameter(m_groupName, "source_dir", m_parameters.sourceDirectory);
19 | writeParameter(m_groupName, "topic_name", m_parameters.topicName);
20 |
21 | return true;
22 | }
23 |
24 |
25 | bool
26 | BasicSettings::read()
27 | {
28 | if (!DialogSettings::getStaticParameter("save_parameters", false)) {
29 | return false;
30 | }
31 |
32 | m_parameters.sourceDirectory = readParameter(m_groupName, "source_dir", QString(""));
33 | m_parameters.topicName = readParameter(m_groupName, "topic_name", QString(""));
34 |
35 | return true;
36 | }
37 |
--------------------------------------------------------------------------------
/src/ui/settings/input/BasicSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "GeneralSettings.hpp"
4 | #include "Parameters.hpp"
5 |
6 | // Store parameters used by all input widgets
7 | class BasicSettings : public GeneralSettings {
8 | public:
9 | BasicSettings(Parameters::BasicParameters& parameters,
10 | const QString& groupName);
11 |
12 | bool
13 | write() override;
14 |
15 | protected:
16 | bool
17 | read() override;
18 |
19 | private:
20 | Parameters::BasicParameters& m_parameters;
21 | };
22 |
--------------------------------------------------------------------------------
/src/ui/settings/input/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | add_library (rt_settings_input INTERFACE)
2 |
3 | target_include_directories (rt_settings_input
4 | INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}
5 | )
6 |
7 | target_sources(rt_settings_input INTERFACE
8 | ${CMAKE_CURRENT_LIST_DIR}/AdvancedSettings.cpp
9 | ${CMAKE_CURRENT_LIST_DIR}/AdvancedSettings.hpp
10 | ${CMAKE_CURRENT_LIST_DIR}/BagToImagesSettings.cpp
11 | ${CMAKE_CURRENT_LIST_DIR}/BagToImagesSettings.hpp
12 | ${CMAKE_CURRENT_LIST_DIR}/BagToVideoSettings.cpp
13 | ${CMAKE_CURRENT_LIST_DIR}/BagToVideoSettings.hpp
14 | ${CMAKE_CURRENT_LIST_DIR}/BasicSettings.cpp
15 | ${CMAKE_CURRENT_LIST_DIR}/BasicSettings.hpp
16 | ${CMAKE_CURRENT_LIST_DIR}/CompressBagSettings.cpp
17 | ${CMAKE_CURRENT_LIST_DIR}/CompressBagSettings.hpp
18 | ${CMAKE_CURRENT_LIST_DIR}/DeleteSourceSettings.cpp
19 | ${CMAKE_CURRENT_LIST_DIR}/DeleteSourceSettings.hpp
20 | ${CMAKE_CURRENT_LIST_DIR}/DummyBagSettings.cpp
21 | ${CMAKE_CURRENT_LIST_DIR}/DummyBagSettings.hpp
22 | ${CMAKE_CURRENT_LIST_DIR}/EditBagSettings.cpp
23 | ${CMAKE_CURRENT_LIST_DIR}/EditBagSettings.hpp
24 | ${CMAKE_CURRENT_LIST_DIR}/MergeBagsSettings.cpp
25 | ${CMAKE_CURRENT_LIST_DIR}/MergeBagsSettings.hpp
26 | ${CMAKE_CURRENT_LIST_DIR}/PCDsToBagSettings.cpp
27 | ${CMAKE_CURRENT_LIST_DIR}/PCDsToBagSettings.hpp
28 | ${CMAKE_CURRENT_LIST_DIR}/PublishSettings.cpp
29 | ${CMAKE_CURRENT_LIST_DIR}/PublishSettings.hpp
30 | ${CMAKE_CURRENT_LIST_DIR}/RecordBagSettings.cpp
31 | ${CMAKE_CURRENT_LIST_DIR}/RecordBagSettings.hpp
32 | ${CMAKE_CURRENT_LIST_DIR}/RGBSettings.cpp
33 | ${CMAKE_CURRENT_LIST_DIR}/RGBSettings.hpp
34 | ${CMAKE_CURRENT_LIST_DIR}/VideoSettings.cpp
35 | ${CMAKE_CURRENT_LIST_DIR}/VideoSettings.hpp
36 | ${CMAKE_CURRENT_LIST_DIR}/VideoToBagSettings.cpp
37 | ${CMAKE_CURRENT_LIST_DIR}/VideoToBagSettings.hpp
38 | )
39 |
40 | target_link_libraries(rt_settings_input
41 | INTERFACE Qt::Widgets rt_settings
42 | )
43 |
--------------------------------------------------------------------------------
/src/ui/settings/input/CompressBagSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "CompressBagSettings.hpp"
2 |
3 | CompressBagSettings::CompressBagSettings(Parameters::CompressBagParameters& parameters,
4 | const QString& groupName) :
5 | DeleteSourceSettings(parameters, groupName), m_parameters(parameters)
6 | {
7 | setDefaultValueToTrue();
8 | read();
9 | }
10 |
11 |
12 | bool
13 | CompressBagSettings::write()
14 | {
15 | if (!DeleteSourceSettings::write()) {
16 | return false;
17 | }
18 |
19 | writeParameter(m_groupName, "compress_per_message", m_parameters.compressPerMessage);
20 |
21 | return true;
22 | }
23 |
24 |
25 | bool
26 | CompressBagSettings::read()
27 | {
28 | if (!DeleteSourceSettings::read()) {
29 | return false;
30 | }
31 |
32 | m_parameters.compressPerMessage = readParameter(m_groupName, "compress_per_message", false);
33 |
34 | return true;
35 | }
36 |
--------------------------------------------------------------------------------
/src/ui/settings/input/CompressBagSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "DeleteSourceSettings.hpp"
4 |
5 | // Store bag editing parameters
6 | class CompressBagSettings : public DeleteSourceSettings {
7 | public:
8 | CompressBagSettings(Parameters::CompressBagParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | private:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::CompressBagParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/DeleteSourceSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "DeleteSourceSettings.hpp"
2 |
3 | DeleteSourceSettings::DeleteSourceSettings(Parameters::DeleteSourceParameters& parameters,
4 | const QString& groupName) :
5 | AdvancedSettings(parameters, groupName), m_parameters(parameters)
6 | {
7 | read();
8 | }
9 |
10 |
11 | bool
12 | DeleteSourceSettings::write()
13 | {
14 | if (!AdvancedSettings::write()) {
15 | return false;
16 | }
17 |
18 | writeParameter(m_groupName, "delete_source", m_parameters.deleteSource);
19 |
20 | return true;
21 | }
22 |
23 |
24 | bool
25 | DeleteSourceSettings::read()
26 | {
27 | if (!AdvancedSettings::read()) {
28 | return false;
29 | }
30 |
31 | m_parameters.deleteSource = readParameter(m_groupName, "delete_source", m_isDefaultValueTrue);
32 |
33 | return true;
34 | }
35 |
--------------------------------------------------------------------------------
/src/ui/settings/input/DeleteSourceSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AdvancedSettings.hpp"
4 |
5 | // Store bag editing parameters
6 | class DeleteSourceSettings : public AdvancedSettings {
7 | public:
8 | DeleteSourceSettings(Parameters::DeleteSourceParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | protected:
15 | bool
16 | read() override;
17 |
18 | void
19 | setDefaultValueToTrue()
20 | {
21 | m_isDefaultValueTrue = true;
22 | }
23 |
24 | private:
25 | Parameters::DeleteSourceParameters& m_parameters;
26 |
27 | bool m_isDefaultValueTrue = false;
28 | };
29 |
--------------------------------------------------------------------------------
/src/ui/settings/input/DummyBagSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "DummyBagSettings.hpp"
2 |
3 | DummyBagSettings::DummyBagSettings(Parameters::DummyBagParameters& parameters, const QString& groupName) :
4 | BasicSettings(parameters, groupName), m_parameters(parameters)
5 | {
6 | read();
7 | }
8 |
9 |
10 | bool
11 | DummyBagSettings::write()
12 | {
13 | if (!BasicSettings::write()) {
14 | return false;
15 | }
16 |
17 | QSettings settings;
18 | settings.beginGroup(m_groupName);
19 |
20 | settings.beginWriteArray("topics");
21 | for (auto i = 0; i < m_parameters.topics.size(); ++i) {
22 | settings.setArrayIndex(i);
23 | writeParameter(settings, "type", m_parameters.topics.at(i).type);
24 | writeParameter(settings, "name", m_parameters.topics.at(i).name);
25 | }
26 | settings.endArray();
27 | settings.endGroup();
28 |
29 | writeParameter(m_groupName, "msg_count", m_parameters.messageCount);
30 | writeParameter(m_groupName, "rate", m_parameters.rate);
31 | writeParameter(m_groupName, "use_custom_rate", m_parameters.useCustomRate);
32 |
33 | return true;
34 | }
35 |
36 |
37 | bool
38 | DummyBagSettings::read()
39 | {
40 | if (!BasicSettings::read()) {
41 | return false;
42 | }
43 |
44 | QSettings settings;
45 |
46 | settings.beginGroup(m_groupName);
47 | m_parameters.topics.clear();
48 |
49 | const auto size = settings.beginReadArray("topics");
50 | for (auto i = 0; i < size; ++i) {
51 | settings.setArrayIndex(i);
52 | m_parameters.topics.append({ readParameter(settings, "type", QString("")), readParameter(settings, "name", QString("")) });
53 | }
54 | settings.endArray();
55 | settings.endGroup();
56 |
57 | m_parameters.messageCount = readParameter(m_groupName, "msg_count", 100);
58 | m_parameters.rate = readParameter(m_groupName, "rate", 10);
59 | m_parameters.useCustomRate = readParameter(m_groupName, "use_custom_rate", false);
60 |
61 | return true;
62 | }
63 |
--------------------------------------------------------------------------------
/src/ui/settings/input/DummyBagSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicSettings.hpp"
4 |
5 | // Store dummy bag creation parameters
6 | class DummyBagSettings : public BasicSettings {
7 | public:
8 | DummyBagSettings(Parameters::DummyBagParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | private:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::DummyBagParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/EditBagSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "EditBagSettings.hpp"
2 |
3 | EditBagSettings::EditBagSettings(Parameters::EditBagParameters& parameters,
4 | const QString& groupName) :
5 | DeleteSourceSettings(parameters, groupName), m_parameters(parameters)
6 | {
7 | read();
8 | }
9 |
10 |
11 | bool
12 | EditBagSettings::write()
13 | {
14 | if (!DeleteSourceSettings::write()) {
15 | return false;
16 | }
17 |
18 | QSettings settings;
19 | settings.beginGroup(m_groupName);
20 |
21 | settings.beginWriteArray("topics");
22 | for (auto i = 0; i < m_parameters.topics.size(); ++i) {
23 | settings.setArrayIndex(i);
24 | writeParameter(settings, "renamed_name", m_parameters.topics.at(i).renamedTopicName);
25 | writeParameter(settings, "original_name", m_parameters.topics.at(i).originalTopicName);
26 | writeParameter(settings, "is_selected", m_parameters.topics.at(i).isSelected);
27 | writeParameter(settings, "lower_boundary", m_parameters.topics.at(i).lowerBoundary);
28 | writeParameter(settings, "upper_boundary", m_parameters.topics.at(i).upperBoundary);
29 | }
30 | settings.endArray();
31 | settings.endGroup();
32 |
33 | writeParameter(m_groupName, "update_timestamps", m_parameters.updateTimestamps);
34 |
35 | return true;
36 | }
37 |
38 |
39 | bool
40 | EditBagSettings::read()
41 | {
42 | if (!DeleteSourceSettings::read()) {
43 | return false;
44 | }
45 |
46 | QSettings settings;
47 | settings.beginGroup(m_groupName);
48 | m_parameters.topics.clear();
49 |
50 | const auto size = settings.beginReadArray("topics");
51 | for (auto i = 0; i < size; ++i) {
52 | settings.setArrayIndex(i);
53 | m_parameters.topics.append({ readParameter(settings, "renamed_name", QString("")), readParameter(settings, "original_name", QString("")),
54 | static_cast(readParameter(settings, "lower_boundary", 0)),
55 | static_cast(readParameter(settings, "upper_boundary", 0)),
56 | readParameter(settings, "is_selected", false) });
57 | }
58 | settings.endArray();
59 | settings.endGroup();
60 |
61 | m_parameters.updateTimestamps = readParameter(m_groupName, "update_timestamps", false);
62 |
63 | return true;
64 | }
65 |
--------------------------------------------------------------------------------
/src/ui/settings/input/EditBagSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "DeleteSourceSettings.hpp"
4 |
5 | // Store bag editing parameters
6 | class EditBagSettings : public DeleteSourceSettings {
7 | public:
8 | EditBagSettings(Parameters::EditBagParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | private:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::EditBagParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/MergeBagsSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "MergeBagsSettings.hpp"
2 |
3 | MergeBagsSettings::MergeBagsSettings(Parameters::MergeBagsParameters& parameters,
4 | const QString& groupName) :
5 | DeleteSourceSettings(parameters, groupName), m_parameters(parameters)
6 | {
7 | read();
8 | }
9 |
10 |
11 | bool
12 | MergeBagsSettings::write()
13 | {
14 | if (!DeleteSourceSettings::write()) {
15 | return false;
16 | }
17 |
18 | QSettings settings;
19 | settings.beginGroup(m_groupName);
20 |
21 | settings.beginWriteArray("topics");
22 | for (auto i = 0; i < m_parameters.topics.size(); ++i) {
23 | settings.setArrayIndex(i);
24 | writeParameter(settings, "name", m_parameters.topics.at(i).name);
25 | writeParameter(settings, "dir", m_parameters.topics.at(i).bagDir);
26 | writeParameter(settings, "is_selected", m_parameters.topics.at(i).isSelected);
27 | }
28 | settings.endArray();
29 | settings.endGroup();
30 |
31 | writeParameter(m_groupName, "second_source", m_parameters.secondSourceDirectory);
32 |
33 | return true;
34 | }
35 |
36 |
37 | bool
38 | MergeBagsSettings::read()
39 | {
40 | if (!DeleteSourceSettings::read()) {
41 | return false;
42 | }
43 |
44 | QSettings settings;
45 | settings.beginGroup(m_groupName);
46 | m_parameters.topics.clear();
47 |
48 | const auto size = settings.beginReadArray("topics");
49 | for (auto i = 0; i < size; ++i) {
50 | settings.setArrayIndex(i);
51 | m_parameters.topics.append({ readParameter(settings, "name", QString("")), readParameter(settings, "dir", QString("")),
52 | readParameter(settings, "is_selected", false) });
53 | }
54 | settings.endArray();
55 | settings.endGroup();
56 |
57 | m_parameters.secondSourceDirectory = readParameter(m_groupName, "second_source", QString(""));
58 |
59 | return true;
60 | }
61 |
--------------------------------------------------------------------------------
/src/ui/settings/input/MergeBagsSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "DeleteSourceSettings.hpp"
4 |
5 | // Store bag editing parameters
6 | class MergeBagsSettings : public DeleteSourceSettings {
7 | public:
8 | MergeBagsSettings(Parameters::MergeBagsParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | private:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::MergeBagsParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/PCDsToBagSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "PCDsToBagSettings.hpp"
2 |
3 | PCDsToBagSettings::PCDsToBagSettings(Parameters::PCDsToBagParameters& parameters,
4 | const QString& groupName) :
5 | AdvancedSettings(parameters, groupName), m_parameters(parameters)
6 | {
7 | read();
8 | }
9 |
10 |
11 | bool
12 | PCDsToBagSettings::write()
13 | {
14 | if (!AdvancedSettings::write()) {
15 | return false;
16 | }
17 |
18 | writeParameter(m_groupName, "rate", m_parameters.rate);
19 |
20 | return true;
21 | }
22 |
23 |
24 | bool
25 | PCDsToBagSettings::read()
26 | {
27 | if (!AdvancedSettings::read()) {
28 | return false;
29 | }
30 |
31 | m_parameters.rate = readParameter(m_groupName, "rate", 5);
32 |
33 | return true;
34 | }
35 |
--------------------------------------------------------------------------------
/src/ui/settings/input/PCDsToBagSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AdvancedSettings.hpp"
4 |
5 | // Store bag creation parameters
6 | class PCDsToBagSettings : public AdvancedSettings {
7 | public:
8 | PCDsToBagSettings(Parameters::PCDsToBagParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | private:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::PCDsToBagParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/PublishSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "PublishSettings.hpp"
2 |
3 | PublishSettings::PublishSettings(Parameters::PublishParameters& parameters, const QString& groupName) :
4 | VideoSettings(parameters, groupName), m_parameters(parameters)
5 | {
6 | read();
7 | }
8 |
9 |
10 | bool
11 | PublishSettings::write()
12 | {
13 | if (!VideoSettings::write()) {
14 | return false;
15 | }
16 |
17 | writeParameter(m_groupName, "loop", m_parameters.loop);
18 | writeParameter(m_groupName, "scale", m_parameters.scale);
19 | writeParameter(m_groupName, "width", m_parameters.width);
20 | writeParameter(m_groupName, "height", m_parameters.height);
21 |
22 | return true;
23 | }
24 |
25 |
26 | bool
27 | PublishSettings::read()
28 | {
29 | if (!VideoSettings::read()) {
30 | return false;
31 | }
32 |
33 | m_parameters.loop = readParameter(m_groupName, "loop", false);
34 | m_parameters.scale = readParameter(m_groupName, "scale", false);
35 | m_parameters.width = readParameter(m_groupName, "width", 1280);
36 | m_parameters.height = readParameter(m_groupName, "height", 720);
37 |
38 | return true;
39 | }
40 |
--------------------------------------------------------------------------------
/src/ui/settings/input/PublishSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "VideoSettings.hpp"
4 |
5 | // Store publishing parameters
6 | class PublishSettings : public VideoSettings {
7 | public:
8 | PublishSettings(Parameters::PublishParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | private:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::PublishParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/RGBSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "RGBSettings.hpp"
2 |
3 | RGBSettings::RGBSettings(Parameters::RGBParameters& parameters, const QString& groupName) :
4 | AdvancedSettings(parameters, groupName), m_parameters(parameters)
5 | {
6 | read();
7 | }
8 |
9 |
10 | bool
11 | RGBSettings::write()
12 | {
13 | if (!AdvancedSettings::write()) {
14 | return false;
15 | }
16 |
17 | writeParameter(m_groupName, "switch_red_blue", m_parameters.exchangeRedBlueValues);
18 |
19 | return true;
20 | }
21 |
22 |
23 | bool
24 | RGBSettings::read()
25 | {
26 | if (!AdvancedSettings::read()) {
27 | return false;
28 | }
29 |
30 | m_parameters.exchangeRedBlueValues = readParameter(m_groupName, "switch_red_blue", false);
31 |
32 | return true;
33 | }
34 |
--------------------------------------------------------------------------------
/src/ui/settings/input/RGBSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AdvancedSettings.hpp"
4 |
5 | // Store rgb settings
6 | class RGBSettings : public AdvancedSettings {
7 | public:
8 | RGBSettings(Parameters::RGBParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | protected:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::RGBParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/RecordBagSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "RecordBagSettings.hpp"
2 |
3 | RecordBagSettings::RecordBagSettings(Parameters::RecordBagParameters& parameters, const QString& groupName) :
4 | BasicSettings(parameters, groupName), m_parameters(parameters)
5 | {
6 | read();
7 | }
8 |
9 |
10 | bool
11 | RecordBagSettings::write()
12 | {
13 | if (!BasicSettings::write()) {
14 | return false;
15 | }
16 |
17 | QSettings settings;
18 | settings.beginGroup(m_groupName);
19 |
20 | settings.beginWriteArray("topics");
21 | for (auto i = 0; i < m_parameters.topics.size(); ++i) {
22 | settings.setArrayIndex(i);
23 | writeParameter(settings, "name", m_parameters.topics.at(i));
24 | }
25 | settings.endArray();
26 | settings.endGroup();
27 |
28 | writeParameter(m_groupName, "all_topics", m_parameters.allTopics);
29 | writeParameter(m_groupName, "show_advanced", m_parameters.showAdvancedOptions);
30 | writeParameter(m_groupName, "include_hidden_topics", m_parameters.includeHiddenTopics);
31 | writeParameter(m_groupName, "include_unpublished_topics", m_parameters.includeUnpublishedTopics);
32 |
33 | return true;
34 | }
35 |
36 |
37 | bool
38 | RecordBagSettings::read()
39 | {
40 | if (!BasicSettings::read()) {
41 | return false;
42 | }
43 |
44 | QSettings settings;
45 |
46 | settings.beginGroup(m_groupName);
47 | m_parameters.topics.clear();
48 |
49 | const auto size = settings.beginReadArray("topics");
50 | for (auto i = 0; i < size; ++i) {
51 | settings.setArrayIndex(i);
52 | m_parameters.topics.append({ readParameter(settings, "name", QString("")) });
53 | }
54 | settings.endArray();
55 | settings.endGroup();
56 |
57 | m_parameters.allTopics = readParameter(m_groupName, "all_topics", true);
58 | m_parameters.showAdvancedOptions = readParameter(m_groupName, "show_advanced", false);
59 | m_parameters.includeHiddenTopics = readParameter(m_groupName, "include_hidden_topics", false);
60 | m_parameters.includeUnpublishedTopics = readParameter(m_groupName, "include_unpublished_topics", false);
61 |
62 | return true;
63 | }
64 |
--------------------------------------------------------------------------------
/src/ui/settings/input/RecordBagSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "BasicSettings.hpp"
4 |
5 | // Store bag recording parameters
6 | class RecordBagSettings : public BasicSettings {
7 | public:
8 | RecordBagSettings(Parameters::RecordBagParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | private:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::RecordBagParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/VideoSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "VideoSettings.hpp"
2 |
3 | VideoSettings::VideoSettings(Parameters::VideoParameters& parameters, const QString& groupName) :
4 | RGBSettings(parameters, groupName), m_parameters(parameters)
5 | {
6 | read();
7 | }
8 |
9 |
10 | bool
11 | VideoSettings::write()
12 | {
13 | if (!RGBSettings::write()) {
14 | return false;
15 | }
16 |
17 | writeParameter(m_groupName, "fps", m_parameters.fps);
18 |
19 | return true;
20 | }
21 |
22 |
23 | bool
24 | VideoSettings::read()
25 | {
26 | if (!RGBSettings::read()) {
27 | return false;
28 | }
29 |
30 | m_parameters.fps = readParameter(m_groupName, "fps", 30);
31 |
32 | return true;
33 | }
34 |
--------------------------------------------------------------------------------
/src/ui/settings/input/VideoSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "RGBSettings.hpp"
4 |
5 | // Store video settings
6 | class VideoSettings : public RGBSettings {
7 | public:
8 | VideoSettings(Parameters::VideoParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | protected:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::VideoParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/ui/settings/input/VideoToBagSettings.cpp:
--------------------------------------------------------------------------------
1 | #include "VideoToBagSettings.hpp"
2 |
3 | VideoToBagSettings::VideoToBagSettings(Parameters::VideoToBagParameters& parameters,
4 | const QString& groupName) :
5 | VideoSettings(parameters, groupName), m_parameters(parameters)
6 | {
7 | read();
8 | }
9 |
10 |
11 | bool
12 | VideoToBagSettings::write()
13 | {
14 | if (!VideoSettings::write()) {
15 | return false;
16 | }
17 |
18 | writeParameter(m_groupName, "custom_fps", m_parameters.useCustomFPS);
19 |
20 | return true;
21 | }
22 |
23 |
24 | bool
25 | VideoToBagSettings::read()
26 | {
27 | if (!VideoSettings::read()) {
28 | return false;
29 | }
30 |
31 | m_parameters.useCustomFPS = readParameter(m_groupName, "custom_fps", false);
32 |
33 | return true;
34 | }
35 |
--------------------------------------------------------------------------------
/src/ui/settings/input/VideoToBagSettings.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "VideoSettings.hpp"
4 |
5 | // Store bag creation parameters
6 | class VideoToBagSettings : public VideoSettings {
7 | public:
8 | VideoToBagSettings(Parameters::VideoToBagParameters& parameters,
9 | const QString& groupName);
10 |
11 | bool
12 | write() override;
13 |
14 | private:
15 | bool
16 | read() override;
17 |
18 | private:
19 | Parameters::VideoToBagParameters& m_parameters;
20 | };
21 |
--------------------------------------------------------------------------------
/src/utils/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | add_library (rt_utils INTERFACE)
2 |
3 | target_include_directories (rt_utils
4 | INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}
5 | )
6 |
7 | target_sources(rt_utils INTERFACE
8 | ${CMAKE_CURRENT_LIST_DIR}/Parameters.hpp
9 | ${CMAKE_CURRENT_LIST_DIR}/UtilsCLI.cpp
10 | ${CMAKE_CURRENT_LIST_DIR}/UtilsCLI.hpp
11 | ${CMAKE_CURRENT_LIST_DIR}/UtilsROS.cpp
12 | ${CMAKE_CURRENT_LIST_DIR}/UtilsROS.hpp
13 | ${CMAKE_CURRENT_LIST_DIR}/UtilsUI.cpp
14 | ${CMAKE_CURRENT_LIST_DIR}/UtilsUI.hpp
15 | ${CMAKE_CURRENT_LIST_DIR}/VideoEncoder.cpp
16 | ${CMAKE_CURRENT_LIST_DIR}/VideoEncoder.hpp
17 | )
18 |
19 | target_link_libraries(rt_utils
20 | INTERFACE ${OpenCV_LIBS} Qt::Widgets rt_settings
21 | )
22 |
--------------------------------------------------------------------------------
/src/utils/Parameters.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 | #include
5 |
6 | #include
7 |
8 | // Parameters used to configure the threads and
9 | // store information in case an input widget is closed and reopened
10 | namespace Parameters
11 | {
12 | struct BasicParameters {
13 | virtual
14 | ~BasicParameters() = default;
15 |
16 | QString sourceDirectory = "";
17 | QString topicName = "";
18 | };
19 | struct RecordBagParameters : BasicParameters {
20 | QVector topics = {};
21 | bool allTopics = true;
22 | bool showAdvancedOptions = false;
23 | bool includeHiddenTopics = false;
24 | bool includeUnpublishedTopics = false;
25 | };
26 | struct DummyBagParameters : BasicParameters {
27 | struct DummyBagTopic {
28 | QString type;
29 | QString name;
30 | };
31 |
32 | QVector topics = {};
33 | int messageCount = 100;
34 | int rate = 10;
35 | bool useCustomRate = false;
36 | };
37 |
38 | struct AdvancedParameters : BasicParameters {
39 | QString targetDirectory = "";
40 | bool showAdvancedOptions = false;
41 | };
42 | struct PCDsToBagParameters : AdvancedParameters {
43 | int rate = 5;
44 | };
45 |
46 | struct DeleteSourceParameters : AdvancedParameters {
47 | bool deleteSource = false;
48 | };
49 | struct EditBagParameters : DeleteSourceParameters {
50 | struct EditBagTopic {
51 | QString renamedTopicName = "";
52 | QString originalTopicName;
53 | size_t lowerBoundary = 0;
54 | size_t upperBoundary;
55 | bool isSelected = true;
56 | };
57 |
58 | QVector topics = {};
59 | bool updateTimestamps = false;
60 | };
61 | struct MergeBagsParameters : DeleteSourceParameters {
62 | struct MergeBagTopic {
63 | QString name = "";
64 | // Topic names might be identical across bags, but cannot be identical in the same bag.
65 | // So store the bag directory as an additional identifier
66 | QString bagDir = "";
67 | bool isSelected = true;
68 | };
69 |
70 | QVector topics = {};
71 | QString secondSourceDirectory = "";
72 | };
73 | struct CompressBagParameters : DeleteSourceParameters {
74 | bool compressPerMessage = false;
75 | };
76 |
77 | struct RGBParameters : AdvancedParameters {
78 | bool exchangeRedBlueValues = false;
79 | };
80 | struct BagToImagesParameters : RGBParameters {
81 | QString format = "jpg";
82 | int quality = 8;
83 | bool useBWImages = false;
84 | bool jpgOptimize = false;
85 | bool pngBilevel = false;
86 | };
87 |
88 | struct VideoParameters : RGBParameters {
89 | int fps = 30;
90 | };
91 | struct BagToVideoParameters : VideoParameters {
92 | QString format = "mp4";
93 | bool useBWImages = false;
94 | bool lossless = false;
95 | };
96 | struct VideoToBagParameters : VideoParameters {
97 | bool useCustomFPS = false;
98 | };
99 | struct PublishParameters : VideoParameters {
100 | int width = 1280;
101 | int height = 720;
102 | bool loop = false;
103 | bool scale = false;
104 | };
105 |
106 | struct DialogParameters {
107 | unsigned int maxNumberOfThreads = std::thread::hardware_concurrency();
108 | bool useHardwareAcceleration = false;
109 | bool saveParameters = false;
110 | bool usePredefinedTopicNames = true;
111 | bool checkROS2NameConform = false;
112 | bool askForTargetOverwrite = true;
113 | };
114 | }
115 |
--------------------------------------------------------------------------------
/src/utils/UtilsCLI.hpp:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 | #include
5 | #include
6 |
7 | #include