Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Add option to compress images #11

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 9 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,11 @@ The tool is a normal ROS package. Place it under a workspace and build it with c
## Usage

**Command-line arguments:**
`--dataroot`: The path to the directory that contains the 'maps', 'samples' and 'sweeps'.
`--dataroot,-s`: The path to the directory that contains the 'maps', 'samples' and 'sweeps'.
`--version`: (optional) The sub-directory that contains the metadata .json files. Default = "v1.0-mini"
`--scene_number,-n`: (optional) Only convert a given scene
`--compress,-c`: (optional) whether to use compressed images to reduce file size



**Converting the 'mini' dataset:**
Expand All @@ -40,6 +43,10 @@ This processes 4 scenes simultaneously, however the scene numbers are not proces
rosrun nuscenes2bag nuscenes2bag --dataroot /path/to/nuscenes_mini_meta_v1.0/ --out nuscenes_bags/ --jobs 4
```

Convert one scene to a bag file with compressed images:
```
rosrun nuscenes2bag nuscenes2bag -c --scene_number 0061 --dataroot /path/to/nuscenes_mini_meta_v1.0/ --out nuscenes_bags/
```

**Converting other datasets:**

Expand Down Expand Up @@ -72,4 +79,4 @@ Built using:
## Authors

- [clynamen](https://github.com/clynamen/)
- [ChernoA](https://github.com/ChernoA)
- [ChernoA](https://github.com/ChernoA)
2 changes: 2 additions & 0 deletions include/nuscenes2bag/ImageDirectoryConverter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,6 @@ namespace nuscenes2bag {

boost::optional<sensor_msgs::Image> readImageFile(const fs::path& filePath) noexcept;

boost::optional<sensor_msgs::CompressedImage> readImageFileCompressed(const fs::path& filePath) noexcept;

}
3 changes: 2 additions & 1 deletion include/nuscenes2bag/NuScenes2Bag.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@ struct NuScenes2Bag {
const std::string& version,
const fs::path &outputRosbagPath,
int32_t threadNumber,
boost::optional<int32_t> sceneNumberOpt
boost::optional<int32_t> sceneNumberOpt,
bool compressImgs
);

private:
Expand Down
3 changes: 2 additions & 1 deletion include/nuscenes2bag/SceneConverter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ namespace nuscenes2bag {

class SceneConverter {
public:
SceneConverter(const MetaDataProvider& metaDataProvider);
SceneConverter(const MetaDataProvider& metaDataProvider, bool compressImgs);

void submit(const Token& sceneToken, FileProgress& fileProgress);

Expand All @@ -25,6 +25,7 @@ class SceneConverter {
std::vector<EgoPoseInfo> egoPoseInfos;
SceneId sceneId;
Token sceneToken;
bool compressImgs;
};

}
18 changes: 18 additions & 0 deletions src/ImageDirectoryConverter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,4 +22,22 @@ readImageFile(const fs::path& filePath) noexcept
return boost::none;
}

boost::optional<sensor_msgs::CompressedImage>
readImageFileCompressed(const fs::path& filePath) noexcept
{
cv::Mat image;
try {
image = imread(filePath.string().c_str(), cv::IMREAD_COLOR);
sensor_msgs::CompressedImagePtr msg =
cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toCompressedImageMsg();

return boost::optional<sensor_msgs::CompressedImage>(*msg);

} catch (const std::exception& e) {
PRINT_EXCEPTION(e);
}

return boost::none;
}

}
7 changes: 4 additions & 3 deletions src/NuScenes2Bag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@ NuScenes2Bag::convertDirectory(const fs::path& inDatasetPath,
const std::string& version,
const fs::path& outputRosbagPath,
int threadNumber,
boost::optional<int32_t> sceneNumberOpt)
boost::optional<int32_t> sceneNumberOpt,
bool compressImgs)
{
if ((threadNumber < 1) || (threadNumber > 64)) {
std::cout << "Forcing at least one job number (-j1)" << std::endl;
Expand Down Expand Up @@ -91,7 +92,7 @@ NuScenes2Bag::convertDirectory(const fs::path& inDatasetPath,

for (const auto& sceneToken : chosenSceneTokens) {
std::unique_ptr<SceneConverter> sceneConverter =
std::make_unique<SceneConverter>(metaDataReader);
std::make_unique<SceneConverter>(metaDataReader, compressImgs);
sceneConverter->submit(sceneToken, fileProgress);
SceneConverter* sceneConverterPtr = sceneConverter.get();
sceneConverters.push_back(std::move(sceneConverter));
Expand Down Expand Up @@ -136,7 +137,7 @@ NuScenes2Bag::convertDirectory(const fs::path& inDatasetPath,

for (const auto& sceneToken : chosenSceneTokens) {
boost::shared_ptr<SceneConverter> sceneConverter =
boost::make_shared<SceneConverter>(SceneConverter(metaDataReader));
boost::make_shared<SceneConverter>(SceneConverter(metaDataReader, compressImgs));
sceneConverter->submit(sceneToken, fileProgress);
sceneConverters.push_back(std::move(sceneConverter));

Expand Down
17 changes: 12 additions & 5 deletions src/SceneConverter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@ using namespace std;

namespace nuscenes2bag {

SceneConverter::SceneConverter(const MetaDataProvider& metaDataProvider)
: metaDataProvider(metaDataProvider)
SceneConverter::SceneConverter(const MetaDataProvider& metaDataProvider, bool compressImgs)
: metaDataProvider(metaDataProvider), compressImgs(compressImgs)
{}

boost::optional<SampleType>
Expand Down Expand Up @@ -121,9 +121,16 @@ SceneConverter::convertSampleDatas(rosbag::Bag& outBag,
std::string sensorName = toLower(calibratedSensorName.name);

if (sampleType == SampleType::CAMERA) {
auto topicName = sensorName + "/raw";
auto msg = readImageFile(sampleFilePath);
writeMsg(topicName, sensorName, sampleData.timeStamp, outBag, msg);
if (compressImgs) {
auto topicName = sensorName + "/compressed";
auto msg = readImageFileCompressed(sampleFilePath);
writeMsg(topicName, sensorName, sampleData.timeStamp, outBag, msg);
}
else {
auto topicName = sensorName + "/raw";
auto msg = readImageFile(sampleFilePath);
writeMsg(topicName, sensorName, sampleData.timeStamp, outBag, msg);
}

} else if (sampleType == SampleType::LIDAR) {
auto topicName = sensorName;
Expand Down
8 changes: 6 additions & 2 deletions src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ main(const int argc, const char* argv[])
std::string outputBagName;
int32_t threadNumber = -1;
int32_t sceneNumber = -1;
bool compressImgs = false;

options_description desc{ "Options" };
desc.add_options()("help,h", "show help");
Expand All @@ -32,7 +33,10 @@ main(const int argc, const char* argv[])
"out,o", value<std::string>(&outputBagName), "output bag name")(
"jobs,j",
value<int32_t>(&threadNumber),
"number of jobs (thread number)");
"number of jobs (thread number)")(
"compress,c",
bool_switch(&compressImgs),
"whether to use compressed images to reduce file size");
variables_map vm;

desc.add(inputDesc);
Expand All @@ -52,7 +56,7 @@ main(const int argc, const char* argv[])
sceneNumberOpt = sceneNumber;
}
converter.convertDirectory(
sampleDirPath, version, outputBagName, threadNumber, sceneNumberOpt);
sampleDirPath, version, outputBagName, threadNumber, sceneNumberOpt, compressImgs);
}
} catch (const error& ex) {
std::cerr << ex.what() << '\n';
Expand Down