Skip to content

Commit

Permalink
add checks for empty flatbuffers message fields inside write function
Browse files Browse the repository at this point in the history
stop using references here so that the arguments can be null and checked inside the function
  • Loading branch information
Julian Arkenau committed Oct 13, 2022
1 parent b0089bc commit 254529f
Show file tree
Hide file tree
Showing 6 changed files with 79 additions and 80 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -37,13 +37,13 @@ class Hdf5FbGeneral : public seerep_hdf5_core::Hdf5CoreGeneral
// Attributes
//################
void writeAttributeMap(const std::shared_ptr<HighFive::DataSet> dataSetPtr,
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::UnionMapEntry>>& attributes);
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::UnionMapEntry>>* attributes);
template <class T>
flatbuffers::Offset<flatbuffers::Vector<flatbuffers::Offset<seerep::fb::UnionMapEntry>>>
readAttributeMap(HighFive::AnnotateTraits<T>& object, flatbuffers::grpc::MessageBuilder& builder);

template <class T>
void writeHeaderAttributes(HighFive::AnnotateTraits<T>& object, const seerep::fb::Header& header);
void writeHeaderAttributes(HighFive::AnnotateTraits<T>& object, const seerep::fb::Header* header);

template <class T>
flatbuffers::Offset<seerep::fb::Header> readHeaderAttributes(flatbuffers::grpc::MessageBuilder& builder,
Expand All @@ -55,17 +55,17 @@ class Hdf5FbGeneral : public seerep_hdf5_core::Hdf5CoreGeneral
//################
void writeBoundingBoxLabeled(
const std::string& datatypeGroup, const std::string& uuid,
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::BoundingBoxLabeled>>& boundingboxLabeled);
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::BoundingBoxLabeled>>* boundingboxLabeled);

void writeBoundingBox2DLabeled(
const std::string& datatypeGroup, const std::string& uuid,
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::BoundingBox2DLabeled>>& boundingbox2DLabeled);
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::BoundingBox2DLabeled>>* boundingbox2DLabeled);

//################
// Labels General
//################
void writeLabelsGeneral(const std::string& datatypeGroup, const std::string& uuid,
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::LabelWithInstance>>& labelsGeneral);
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::LabelWithInstance>>* labelsGeneral);
};

} // namespace seerep_hdf5_fb
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,27 +35,30 @@ Hdf5FbGeneral::readAttributeMap(HighFive::AnnotateTraits<T>& object, flatbuffers
}

template <class T>
void Hdf5FbGeneral::writeHeaderAttributes(HighFive::AnnotateTraits<T>& object, const seerep::fb::Header& header)
void Hdf5FbGeneral::writeHeaderAttributes(HighFive::AnnotateTraits<T>& 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 <class T>
Expand Down
77 changes: 40 additions & 37 deletions seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-general.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,53 +11,56 @@ Hdf5FbGeneral::Hdf5FbGeneral(std::shared_ptr<HighFive::File>& file, std::shared_

void Hdf5FbGeneral::writeAttributeMap(
const std::shared_ptr<HighFive::DataSet> dataSetPtr,
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::UnionMapEntry>>& attributes)
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::UnionMapEntry>>* 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<const seerep::fb::Boolean*>(attribute->value())->data());
}
else if (attribute->value_type() == seerep::fb::Datatypes_Integer)
{
writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(),
static_cast<const seerep::fb::Integer*>(attribute->value())->data());
}
else if (attribute->value_type() == seerep::fb::Datatypes_Double)
{
writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(),
static_cast<const seerep::fb::Double*>(attribute->value())->data());
}
else if (attribute->value_type() == seerep::fb::Datatypes_String)
{
writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(),
static_cast<const seerep::fb::String*>(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<const seerep::fb::Boolean*>(attribute->value())->data());
}
else if (attribute->value_type() == seerep::fb::Datatypes_Integer)
{
writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(),
static_cast<const seerep::fb::Integer*>(attribute->value())->data());
}
else if (attribute->value_type() == seerep::fb::Datatypes_Double)
{
writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(),
static_cast<const seerep::fb::Double*>(attribute->value())->data());
}
else if (attribute->value_type() == seerep::fb::Datatypes_String)
{
writeAttributeToHdf5(*dataSetPtr, attribute->key()->str(),
static_cast<const seerep::fb::String*>(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<flatbuffers::Offset<seerep::fb::BoundingBoxLabeled>>& boundingboxLabeled)
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::BoundingBoxLabeled>>* boundingboxLabeled)
{
if (!boundingboxLabeled.size() == 0)
if (boundingboxLabeled && boundingboxLabeled->size() != 0)
{
std::string id = datatypeGroup + "/" + uuid;

std::vector<std::string> labels;
std::vector<std::vector<double>> boundingBoxes;
std::vector<std::string> instances;
for (auto label : boundingboxLabeled)
for (auto label : *boundingboxLabeled)
{
labels.push_back(label->labelWithInstance()->label()->str());
std::vector<double> box{ label->bounding_box()->point_min()->x(), label->bounding_box()->point_min()->y(),
Expand Down Expand Up @@ -86,16 +89,16 @@ void Hdf5FbGeneral::writeBoundingBoxLabeled(

void Hdf5FbGeneral::writeBoundingBox2DLabeled(
const std::string& datatypeGroup, const std::string& uuid,
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::BoundingBox2DLabeled>>& boundingbox2DLabeled)
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::BoundingBox2DLabeled>>* boundingbox2DLabeled)
{
std::string id = datatypeGroup + "/" + uuid;

if (!boundingbox2DLabeled.size() == 0)
if (boundingbox2DLabeled && boundingbox2DLabeled->size() != 0)
{
std::vector<std::string> labels;
std::vector<std::vector<double>> boundingBoxes;
std::vector<std::string> instances;
for (auto label : boundingbox2DLabeled)
for (auto label : *boundingbox2DLabeled)
{
labels.push_back(label->labelWithInstance()->label()->str());
std::vector<double> box{ label->bounding_box()->point_min()->x(), label->bounding_box()->point_min()->y(),
Expand Down Expand Up @@ -123,15 +126,15 @@ void Hdf5FbGeneral::writeBoundingBox2DLabeled(

void Hdf5FbGeneral::writeLabelsGeneral(
const std::string& datatypeGroup, const std::string& uuid,
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::LabelWithInstance>>& labelsGeneral)
const flatbuffers::Vector<flatbuffers::Offset<seerep::fb::LabelWithInstance>>* labelsGeneral)
{
std::string id = datatypeGroup + "/" + uuid;

if (labelsGeneral.size() != 0)
if (labelsGeneral && labelsGeneral->size() != 0)
{
std::vector<std::string> labels;
std::vector<std::string> instances;
for (auto label : labelsGeneral)
for (auto label : *labelsGeneral)
{
labels.push_back(label->label()->str());

Expand Down
8 changes: 4 additions & 4 deletions seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Expand All @@ -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<flatbuffers::grpc::Message<seerep::fb::Image>> Hdf5FbImage::readImage(const std::string& id,
Expand Down
8 changes: 4 additions & 4 deletions seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-point.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Expand All @@ -60,7 +60,7 @@ void Hdf5FbPoint::writeAdditionalPointAttributes(const seerep::fb::AttributesSta
std::shared_ptr<HighFive::DataSet> data_set_ptr =
std::make_shared<HighFive::DataSet>(m_file->getDataSet(hdf5DatasetRawDataPath));

writeAttributeMap(data_set_ptr, *attributeStamped.attribute());
writeAttributeMap(data_set_ptr, attributeStamped.attribute());
}
catch (const std::exception& e)
{
Expand Down
13 changes: 3 additions & 10 deletions seerep-hdf5/seerep-hdf5-fb/src/hdf5-fb-pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,19 +43,12 @@ void Hdf5FbPointCloud::writePointCloud2(const std::string& id, const seerep::fb:
writeAttributeToHdf5<uint32_t>(*dataGroupPtr, seerep_hdf5_core::Hdf5CorePointCloud::ROW_STEP, cloud.row_step());
writeAttributeToHdf5<bool>(*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);

Expand Down

0 comments on commit 254529f

Please sign in to comment.