Skip to content

Commit

Permalink
initial changes
Browse files Browse the repository at this point in the history
  • Loading branch information
mmeijerdfki committed Nov 3, 2024
1 parent c698c7f commit 7a15fb9
Show file tree
Hide file tree
Showing 12 changed files with 75 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,9 @@

namespace seerep_hdf5_core
{
typedef std::optional<std::pair<std::string, std::vector<seerep_core_msgs::Point>>>
frame_to_points_mapping;

class Hdf5CoreDatatypeInterface
{
public:
Expand All @@ -19,6 +22,16 @@ class Hdf5CoreDatatypeInterface
readDataset(const std::string& uuid) = 0;

virtual std::vector<std::string> getDatasetUuids() = 0;

/**
* @brief a option to pass points down to check for spatially, the first
* return value are the points which should get checked, the second in which
* frame they should be checked
*
* @return the points which should get checked (if empty this should be a
* noop) and the frame_id in which they need to get transformed from
*/
virtual frame_to_points_mapping getPolygonConstraintPoints() = 0;
};

} // namespace seerep_hdf5_core
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,15 @@ class Hdf5CoreImage : public virtual Hdf5CoreGeneral,
*/
std::vector<std::string> getDatasetUuids();

/**
* @brief Get points which should get constraint by the query polygon,
* otherwise the data is not fullyEncapsulated by the polygon
*
* @return the points which should get checked and the frame as a string in
* which they should be checked
*/
frame_to_points_mapping getPolygonConstraintPoints();

/**
* @brief Write generals labels based on C++ data structures to HdF5
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,13 @@ class Hdf5CorePoint : public Hdf5CoreGeneral, public Hdf5CoreDatatypeInterface

std::vector<std::string> getDatasetUuids();

/**
* @brief THIS IS CURRENTLY A NOOP
*
* @return a empty vector and string
*/
frame_to_points_mapping getPolygonConstraintPoints();

public:
inline static const std::string RAWDATA = "rawdata";

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,13 @@ class Hdf5CorePointCloud : public Hdf5CoreGeneral,

std::vector<std::string> getDatasetUuids();

/**
* @brief THIS IS CURRENTLY A NOOP
*
* @return a empty vector and string
*/
frame_to_points_mapping getPolygonConstraintPoints();

public:
// image / pointcloud attribute keys
inline static const std::string HEIGHT = "height";
Expand Down
5 changes: 5 additions & 0 deletions seerep_hdf5/seerep_hdf5_core/src/hdf5_core_image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,11 @@ std::vector<std::string> Hdf5CoreImage::getDatasetUuids()
return getGroupDatasets(HDF5_GROUP_IMAGE);
}

frame_to_points_mapping Hdf5CoreImage::getPolygonConstraintPoints()
{
return std::nullopt;
}

void Hdf5CoreImage::writeLabels(
const std::string& uuid,
const std::vector<seerep_core_msgs::LabelCategory>& labelCategory)
Expand Down
5 changes: 5 additions & 0 deletions seerep_hdf5/seerep_hdf5_core/src/hdf5_core_point.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,4 +64,9 @@ std::vector<std::string> Hdf5CorePoint::getDatasetUuids()
return getGroupDatasets(HDF5_GROUP_POINT);
}

frame_to_points_mapping Hdf5CorePoint::getPolygonConstraintPoints()
{
return std::nullopt;
}

} // namespace seerep_hdf5_core
5 changes: 5 additions & 0 deletions seerep_hdf5/seerep_hdf5_core/src/hdf5_core_point_cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,4 +61,9 @@ std::vector<std::string> Hdf5CorePointCloud::getDatasetUuids()
return getGroupDatasets(HDF5_GROUP_POINTCLOUD);
}

frame_to_points_mapping Hdf5CorePointCloud::getPolygonConstraintPoints()
{
return std::nullopt;
}

} // namespace seerep_hdf5_core
5 changes: 3 additions & 2 deletions seerep_msgs/core/dataset_indexable.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,16 @@

#include "aabb.h"
#include "header.h"
#include "label_datumaro.h"
#include "label_with_instance.h"

namespace seerep_core_msgs
{
struct DatasetIndexable
{
Header header;
AABB boundingbox;
std::unordered_map<std::string, LabelDatumaro> labelsCategory;
std::unordered_map<std::string, std::vector<LabelWithInstance>>
labelsWithInstancesWithCategory;
};

} /* namespace seerep_core_msgs */
Expand Down
4 changes: 2 additions & 2 deletions seerep_msgs/core/polygon2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@ namespace seerep_core_msgs
struct Polygon2D
{
std::vector<Point2D> vertices;
double z;
double height;
int z;
int height;
};
} // namespace seerep_core_msgs

Expand Down
3 changes: 0 additions & 3 deletions seerep_msgs/core/query.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,6 @@ struct Query
projects; ///< search all projects if not set
std::optional<Polygon2D>
polygon; // query dataset in the region defined by this polygon
std::optional<Polygon2D>
polygonSensorPos; // query dataset with the sensor position in the region
// defined by this polygon
bool fullyEncapsulated; // if true, only return results fully inside the
// polygon defined above
bool inMapFrame; // if false the query polygon is in geodetic coordinates,
Expand Down
9 changes: 5 additions & 4 deletions seerep_srv/seerep_core/include/seerep_core/core_dataset.h
Original file line number Diff line number Diff line change
Expand Up @@ -352,10 +352,11 @@ class CoreDataset
* @param queryFullyEncapsulated
* @return std::optional<std::vector<seerep_core_msgs::AabbIdPair>>
*/
std::optional<std::vector<seerep_core_msgs::AabbIdPair>>
queryRtree(const seerep_core_msgs::rtree& rt,
const seerep_core_msgs::Polygon2D& polygon,
const bool queryFullyEncapsulated);
std::optional<std::vector<seerep_core_msgs::AabbIdPair>> queryRtree(
const seerep_core_msgs::rtree& rt,
const seerep_core_msgs::Polygon2D& polygon,
// const seerep_hdf5_core::frame_to_points_mapping frame_and_points,
const bool queryFullyEncapsulated);

/**
* @brief queries the temporal index and returns a vector of temporal bounding
Expand Down
14 changes: 14 additions & 0 deletions seerep_srv/seerep_core/src/core_dataset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -283,6 +283,7 @@ CoreDataset::querySpatialSensorPos(
std::optional<std::vector<seerep_core_msgs::AabbIdPair>>
CoreDataset::queryRtree(const seerep_core_msgs::rtree& rt,
const seerep_core_msgs::Polygon2D& polygon,
// const seerep_hdf5_core::frame_to_points_mapping,
const bool queryFullyEncapsulated)
{
// generate rtree result container
Expand All @@ -307,6 +308,19 @@ CoreDataset::queryRtree(const seerep_core_msgs::rtree& rt,
intersectionDegree(it->first, polygon, fullyEncapsulated,
partiallyEncapsulated);

// check thoroughly if a image has been passed and check whether the
// corresponding Frustum is in the polygon
// partial encapsulation is pre-condition for the case
// if the aabb of the data, which is a upper bound for the check, is
// already encapsulated we can skip the check
// if (partialEncapsulation && !fullEncapsulation)
// {
// if (isPreciselyFullEncapsulated())
// {
// fullEncapsulation = true;
// }
// }

// if there is no intersection between the result and the user's
// request, remove it from the iterator
if (!partiallyEncapsulated && !fullyEncapsulated)
Expand Down

0 comments on commit 7a15fb9

Please sign in to comment.