diff --git a/seerep-hdf5/seerep-hdf5-fb/include/seerep-hdf5-fb/hdf5-fb-general.h b/seerep-hdf5/seerep-hdf5-fb/include/seerep-hdf5-fb/hdf5-fb-general.h index 8f2a02442..94f5d6bfb 100644 --- a/seerep-hdf5/seerep-hdf5-fb/include/seerep-hdf5-fb/hdf5-fb-general.h +++ b/seerep-hdf5/seerep-hdf5-fb/include/seerep-hdf5-fb/hdf5-fb-general.h @@ -37,13 +37,13 @@ class Hdf5FbGeneral : public seerep_hdf5_core::Hdf5CoreGeneral // Attributes //################ void writeAttributeMap(const std::shared_ptr dataSetPtr, - const flatbuffers::Vector>& attributes); + const flatbuffers::Vector>* attributes); template flatbuffers::Offset>> readAttributeMap(HighFive::AnnotateTraits& object, flatbuffers::grpc::MessageBuilder& builder); template - void writeHeaderAttributes(HighFive::AnnotateTraits& object, const seerep::fb::Header& header); + void writeHeaderAttributes(HighFive::AnnotateTraits& object, const seerep::fb::Header* header); template flatbuffers::Offset readHeaderAttributes(flatbuffers::grpc::MessageBuilder& builder, @@ -55,17 +55,17 @@ class Hdf5FbGeneral : public seerep_hdf5_core::Hdf5CoreGeneral //################ void writeBoundingBoxLabeled( const std::string& datatypeGroup, const std::string& uuid, - const flatbuffers::Vector>& boundingboxLabeled); + const flatbuffers::Vector>* boundingboxLabeled); void writeBoundingBox2DLabeled( const std::string& datatypeGroup, const std::string& uuid, - const flatbuffers::Vector>& boundingbox2DLabeled); + const flatbuffers::Vector>* boundingbox2DLabeled); //################ // Labels General //################ void writeLabelsGeneral(const std::string& datatypeGroup, const std::string& uuid, - const flatbuffers::Vector>& labelsGeneral); + const flatbuffers::Vector>* labelsGeneral); }; } // namespace seerep_hdf5_fb diff --git a/seerep-hdf5/seerep-hdf5-fb/include/seerep-hdf5-fb/impl/hdf5-fb-general.hpp b/seerep-hdf5/seerep-hdf5-fb/include/seerep-hdf5-fb/impl/hdf5-fb-general.hpp index e64587589..7476f6a2e 100644 --- a/seerep-hdf5/seerep-hdf5-fb/include/seerep-hdf5-fb/impl/hdf5-fb-general.hpp +++ b/seerep-hdf5/seerep-hdf5-fb/include/seerep-hdf5-fb/impl/hdf5-fb-general.hpp @@ -35,27 +35,30 @@ Hdf5FbGeneral::readAttributeMap(HighFive::AnnotateTraits& object, flatbuffers } template -void Hdf5FbGeneral::writeHeaderAttributes(HighFive::AnnotateTraits& object, const seerep::fb::Header& header) +void Hdf5FbGeneral::writeHeaderAttributes(HighFive::AnnotateTraits& object, const seerep::fb::Header* header) { - if (!object.hasAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_SECONDS)) - object.createAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_SECONDS, header.stamp()->seconds()); - else - object.getAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_SECONDS).write(header.stamp()->seconds()); - - if (!object.hasAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_NANOS)) - object.createAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_NANOS, header.stamp()->nanos()); - else - object.getAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_NANOS).write(header.stamp()->nanos()); - - if (!object.hasAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_FRAME_ID)) - object.createAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_FRAME_ID, header.frame_id()->str()); - else - object.getAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_FRAME_ID).write(header.frame_id()->str()); - - if (!object.hasAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_SEQ)) - object.createAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_SEQ, header.seq()); - else - object.getAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_SEQ).write(header.seq()); + if (header) + { + if (!object.hasAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_SECONDS)) + object.createAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_SECONDS, header->stamp()->seconds()); + else + object.getAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_SECONDS).write(header->stamp()->seconds()); + + if (!object.hasAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_NANOS)) + object.createAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_NANOS, header->stamp()->nanos()); + else + object.getAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_STAMP_NANOS).write(header->stamp()->nanos()); + + if (!object.hasAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_FRAME_ID)) + object.createAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_FRAME_ID, header->frame_id()->str()); + else + object.getAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_FRAME_ID).write(header->frame_id()->str()); + + if (!object.hasAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_SEQ)) + object.createAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_SEQ, header->seq()); + else + object.getAttribute(seerep_hdf5_core::Hdf5CoreGeneral::HEADER_SEQ).write(header->seq()); + } } template diff --git a/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-general.cpp b/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-general.cpp index 25e37271b..76552a642 100644 --- a/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-general.cpp +++ b/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-general.cpp @@ -11,53 +11,56 @@ Hdf5FbGeneral::Hdf5FbGeneral(std::shared_ptr& file, std::shared_ void Hdf5FbGeneral::writeAttributeMap( const std::shared_ptr dataSetPtr, - const flatbuffers::Vector>& attributes) + const flatbuffers::Vector>* attributes) { - for (auto attribute : attributes) + if (attributes) { - if (attribute->value_type() == seerep::fb::Datatypes_Boolean) + for (auto attribute : *attributes) { - writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(), - static_cast(attribute->value())->data()); - } - else if (attribute->value_type() == seerep::fb::Datatypes_Integer) - { - writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(), - static_cast(attribute->value())->data()); - } - else if (attribute->value_type() == seerep::fb::Datatypes_Double) - { - writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(), - static_cast(attribute->value())->data()); - } - else if (attribute->value_type() == seerep::fb::Datatypes_String) - { - writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(), - static_cast(attribute->value())->data()->str()); - } - else - { - std::stringstream errorMsg; - errorMsg << "type " << attribute->value_type() << " of attribute " << attribute->key()->c_str() - << " not implemented in hdf5-io."; - BOOST_LOG_SEV(m_logger, boost::log::trivial::severity_level::error) << errorMsg.str(); - throw std::invalid_argument(errorMsg.str()); + if (attribute->value_type() == seerep::fb::Datatypes_Boolean) + { + writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(), + static_cast(attribute->value())->data()); + } + else if (attribute->value_type() == seerep::fb::Datatypes_Integer) + { + writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(), + static_cast(attribute->value())->data()); + } + else if (attribute->value_type() == seerep::fb::Datatypes_Double) + { + writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(), + static_cast(attribute->value())->data()); + } + else if (attribute->value_type() == seerep::fb::Datatypes_String) + { + writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(), + static_cast(attribute->value())->data()->str()); + } + else + { + std::stringstream errorMsg; + errorMsg << "type " << attribute->value_type() << " of attribute " << attribute->key()->c_str() + << " not implemented in hdf5-io."; + BOOST_LOG_SEV(m_logger, boost::log::trivial::severity_level::error) << errorMsg.str(); + throw std::invalid_argument(errorMsg.str()); + } } } } void Hdf5FbGeneral::writeBoundingBoxLabeled( const std::string& datatypeGroup, const std::string& uuid, - const flatbuffers::Vector>& boundingboxLabeled) + const flatbuffers::Vector>* boundingboxLabeled) { - if (!boundingboxLabeled.size() == 0) + if (boundingboxLabeled && boundingboxLabeled->size() != 0) { std::string id = datatypeGroup + "/" + uuid; std::vector labels; std::vector> boundingBoxes; std::vector instances; - for (auto label : boundingboxLabeled) + for (auto label : *boundingboxLabeled) { labels.push_back(label->labelWithInstance()->label()->str()); std::vector box{ label->bounding_box()->point_min()->x(), label->bounding_box()->point_min()->y(), @@ -86,16 +89,16 @@ void Hdf5FbGeneral::writeBoundingBoxLabeled( void Hdf5FbGeneral::writeBoundingBox2DLabeled( const std::string& datatypeGroup, const std::string& uuid, - const flatbuffers::Vector>& boundingbox2DLabeled) + const flatbuffers::Vector>* boundingbox2DLabeled) { std::string id = datatypeGroup + "/" + uuid; - if (!boundingbox2DLabeled.size() == 0) + if (boundingbox2DLabeled && boundingbox2DLabeled->size() != 0) { std::vector labels; std::vector> boundingBoxes; std::vector instances; - for (auto label : boundingbox2DLabeled) + for (auto label : *boundingbox2DLabeled) { labels.push_back(label->labelWithInstance()->label()->str()); std::vector box{ label->bounding_box()->point_min()->x(), label->bounding_box()->point_min()->y(), @@ -123,15 +126,15 @@ void Hdf5FbGeneral::writeBoundingBox2DLabeled( void Hdf5FbGeneral::writeLabelsGeneral( const std::string& datatypeGroup, const std::string& uuid, - const flatbuffers::Vector>& labelsGeneral) + const flatbuffers::Vector>* labelsGeneral) { std::string id = datatypeGroup + "/" + uuid; - if (labelsGeneral.size() != 0) + if (labelsGeneral && labelsGeneral->size() != 0) { std::vector labels; std::vector instances; - for (auto label : labelsGeneral) + for (auto label : *labelsGeneral) { labels.push_back(label->label()->str()); diff --git a/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-image.cpp b/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-image.cpp index eb8d2db51..4e5e49e0d 100644 --- a/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-image.cpp +++ b/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-image.cpp @@ -73,10 +73,10 @@ void Hdf5FbImage::writeImage(const std::string& id, const seerep::fb::Image& ima } data_set_ptr->write(tmp); - writeHeaderAttributes(*data_set_ptr, *image.header()); + writeHeaderAttributes(*data_set_ptr, image.header()); - writeBoundingBox2DLabeled(seerep_hdf5_core::Hdf5CoreImage::HDF5_GROUP_IMAGE, id, *image.labels_bb()); - writeLabelsGeneral(seerep_hdf5_core::Hdf5CoreImage::HDF5_GROUP_IMAGE, id, *image.labels_general()); + writeBoundingBox2DLabeled(seerep_hdf5_core::Hdf5CoreImage::HDF5_GROUP_IMAGE, id, image.labels_bb()); + writeLabelsGeneral(seerep_hdf5_core::Hdf5CoreImage::HDF5_GROUP_IMAGE, id, image.labels_general()); m_file->flush(); } @@ -86,7 +86,7 @@ void Hdf5FbImage::writeImageBoundingBox2DLabeled(const std::string& id, { const std::scoped_lock lock(*m_write_mtx); - writeBoundingBox2DLabeled(seerep_hdf5_core::Hdf5CoreImage::HDF5_GROUP_IMAGE, id, *bb2dLabeledStamped.labels_bb()); + writeBoundingBox2DLabeled(seerep_hdf5_core::Hdf5CoreImage::HDF5_GROUP_IMAGE, id, bb2dLabeledStamped.labels_bb()); } std::optional> Hdf5FbImage::readImage(const std::string& id, diff --git a/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-point.cpp b/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-point.cpp index eb87a5e83..4cb2a853b 100644 --- a/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-point.cpp +++ b/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-point.cpp @@ -39,11 +39,11 @@ void Hdf5FbPoint::writePoint(const std::string& id, const seerep::fb::PointStamp } data_set_ptr->write(data); - writeHeaderAttributes(*data_set_ptr, *point->header()); + writeHeaderAttributes(*data_set_ptr, point->header()); - writeAttributeMap(data_set_ptr, *point->attribute()); + writeAttributeMap(data_set_ptr, point->attribute()); - writeLabelsGeneral(seerep_hdf5_core::Hdf5CorePoint::HDF5_GROUP_POINT, id, *point->labels_general()); + writeLabelsGeneral(seerep_hdf5_core::Hdf5CorePoint::HDF5_GROUP_POINT, id, point->labels_general()); m_file->flush(); } @@ -60,7 +60,7 @@ void Hdf5FbPoint::writeAdditionalPointAttributes(const seerep::fb::AttributesSta std::shared_ptr data_set_ptr = std::make_shared(m_file->getDataSet(hdf5DatasetRawDataPath)); - writeAttributeMap(data_set_ptr, *attributeStamped.attribute()); + writeAttributeMap(data_set_ptr, attributeStamped.attribute()); } catch (const std::exception& e) { diff --git a/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-pointcloud.cpp b/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-pointcloud.cpp index 5dcd10db2..427d4474c 100644 --- a/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-pointcloud.cpp +++ b/seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-pointcloud.cpp @@ -43,19 +43,12 @@ void Hdf5FbPointCloud::writePointCloud2(const std::string& id, const seerep::fb: writeAttributeToHdf5(*dataGroupPtr, seerep_hdf5_core::Hdf5CorePointCloud::ROW_STEP, cloud.row_step()); writeAttributeToHdf5(*dataGroupPtr, seerep_hdf5_core::Hdf5CorePointCloud::IS_DENSE, cloud.is_dense()); - writeHeaderAttributes(*dataGroupPtr, *cloud.header()); + writeHeaderAttributes(*dataGroupPtr, cloud.header()); writePointFieldAttributes(*dataGroupPtr, *cloud.fields()); - if (cloud.labels_bb() != nullptr) - { - writeBoundingBoxLabeled(seerep_hdf5_core::Hdf5CorePointCloud::HDF5_GROUP_POINTCLOUD, id, *cloud.labels_bb()); - } - - if (cloud.labels_general() != nullptr) - { - writeLabelsGeneral(seerep_hdf5_core::Hdf5CorePointCloud::HDF5_GROUP_POINTCLOUD, id, *cloud.labels_general()); - } + writeBoundingBoxLabeled(seerep_hdf5_core::Hdf5CorePointCloud::HDF5_GROUP_POINTCLOUD, id, cloud.labels_bb()); + writeLabelsGeneral(seerep_hdf5_core::Hdf5CorePointCloud::HDF5_GROUP_POINTCLOUD, id, cloud.labels_general()); CloudInfo info = getCloudInfo(cloud);