diff --git a/examples/cpp/ROS/launch/hdf5-node.launch b/examples/cpp/ROS/launch/hdf5-node.launch
index 4c02a0b14..b25e36b94 100644
--- a/examples/cpp/ROS/launch/hdf5-node.launch
+++ b/examples/cpp/ROS/launch/hdf5-node.launch
@@ -3,9 +3,13 @@
+
+
$(arg topics)
$(arg path)
$(arg filename)
+ $(arg project_root_frame)
+ $(arg project_name)
diff --git a/examples/cpp/ROS/src/hdf5-node.cpp b/examples/cpp/ROS/src/hdf5-node.cpp
index 5410ba9f3..54c18af6c 100644
--- a/examples/cpp/ROS/src/hdf5-node.cpp
+++ b/examples/cpp/ROS/src/hdf5-node.cpp
@@ -25,7 +25,19 @@ Hdf5Node::Hdf5Node(const ros::NodeHandle& nodeHandle, const ros::NodeHandle& pri
ROS_WARN_STREAM("Filename is an invalid UUID, using generated UUID instead");
}
- hdf5Access_ = std::make_unique(path, filename);
+ std::string projectName;
+ if (!privateNodeHandle_.getParam("project_name", projectName))
+ {
+ throw std::runtime_error("No project name specified");
+ }
+
+ std::string rootFrameId;
+ if (!privateNodeHandle_.getParam("project_root_frame", rootFrameId))
+ {
+ throw std::runtime_error("No root frame specified");
+ }
+
+ hdf5Access_ = std::make_unique(path, filename, rootFrameId, projectName);
std::vector topics;
if (!privateNodeHandle_.getParam("topics", topics))
diff --git a/seerep-hdf5/seerep-hdf5-ros/CMakeLists.txt b/seerep-hdf5/seerep-hdf5-ros/CMakeLists.txt
index edc3e82c1..432228437 100644
--- a/seerep-hdf5/seerep-hdf5-ros/CMakeLists.txt
+++ b/seerep-hdf5/seerep-hdf5-ros/CMakeLists.txt
@@ -14,19 +14,28 @@ find_package(catkin REQUIRED
sensor_msgs
)
+find_package(SeerepHdf5Core REQUIRED)
+
include(cmake/FindHighFive.cmake)
find_package(HighFive REQUIRED)
+set(Boost_USE_STATIC_LIBS OFF)
+set(Boost_USE_MULTITHREADED ON)
+set(Boost_USE_STATIC_RUNTIME OFF)
+add_definitions(-DBOOST_LOG_DYN_LINK)
+
catkin_package(
INCLUDE_DIRS include
LIBRARIES seerep_hdf5_ros
CATKIN_DEPENDS std_msgs geometry_msgs sensor_msgs
- DEPENDS HighFive
+ DEPENDS HighFive SeerepHdf5Core
)
include_directories(
include
${HighFive_INCLUDE_DIRS}
+ ${SeerepHdf5Core_INCLUDE_DIRS}
+ ${Boost_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)
@@ -34,6 +43,13 @@ add_library(${PROJECT_NAME}
src/hdf5-ros.cpp
)
+target_link_libraries(${PROJECT_NAME}
+ ${HighFive_LIBRARIES}
+ ${Boost_LIBRARIES}
+ ${SeerepHdf5Core_LIBRARIES}
+ ${catkin_LIBRARIES}
+)
+
add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
install(TARGETS ${PROJECT_NAME}
diff --git a/seerep-hdf5/seerep-hdf5-ros/include/seerep-hdf5-ros/hdf5-ros.h b/seerep-hdf5/seerep-hdf5-ros/include/seerep-hdf5-ros/hdf5-ros.h
index 212c4cd79..b2a0c6799 100644
--- a/seerep-hdf5/seerep-hdf5-ros/include/seerep-hdf5-ros/hdf5-ros.h
+++ b/seerep-hdf5/seerep-hdf5-ros/include/seerep-hdf5-ros/hdf5-ros.h
@@ -1,7 +1,8 @@
#ifndef SEEREP_HDF5_ROS_H_
#define SEEREP_HDF5_ROS_H_
-// std
+// Std
+#include
#include
// HighFive
@@ -17,13 +18,17 @@
#include "sensor_msgs/Image.h"
#include "std_msgs/Header.h"
+// Seerep
+#include "seerep-hdf5-core/hdf5-core-general.h"
+
namespace seerep_hdf5_ros
{
class Hdf5Ros
{
public:
Hdf5Ros() = delete;
- Hdf5Ros(const std::string& path, const std::string& filename);
+ Hdf5Ros(const std::string& path, const std::string& filename, const std::string& projectFrameId,
+ const std::string& projectName);
bool dumpImage(const sensor_msgs::Image& image) const;
bool dumpHeader(const std_msgs::Header& header, const std::string& datasetPath) const;
diff --git a/seerep-hdf5/seerep-hdf5-ros/package.xml b/seerep-hdf5/seerep-hdf5-ros/package.xml
index 537d8fd41..cb06645f2 100644
--- a/seerep-hdf5/seerep-hdf5-ros/package.xml
+++ b/seerep-hdf5/seerep-hdf5-ros/package.xml
@@ -14,6 +14,7 @@
sensor_msgs
std_msgs
geometry_msgs
+ seerep-hdf5-core
catkin
diff --git a/seerep-hdf5/seerep-hdf5-ros/src/hdf5-ros.cpp b/seerep-hdf5/seerep-hdf5-ros/src/hdf5-ros.cpp
index d9fd2f501..69ebc2974 100644
--- a/seerep-hdf5/seerep-hdf5-ros/src/hdf5-ros.cpp
+++ b/seerep-hdf5/seerep-hdf5-ros/src/hdf5-ros.cpp
@@ -2,10 +2,16 @@
namespace seerep_hdf5_ros
{
-Hdf5Ros::Hdf5Ros(const std::string& path, const std::string& filename) : path_{ path }, filename_{ filename }
+Hdf5Ros::Hdf5Ros(const std::string& path, const std::string& filename, const std::string& projectFrameId,
+ const std::string& projectName)
+ : path_{ path }, filename_{ filename }
{
+ auto write_mtx = std::make_shared();
hdf5File_ =
std::make_shared(path_ + filename_ + ".h5", HighFive::File::ReadWrite | HighFive::File::Create);
+ auto ioGeneral = seerep_hdf5_core::Hdf5CoreGeneral(hdf5File_, write_mtx);
+ ioGeneral.writeProjectFrameId(projectFrameId);
+ ioGeneral.writeProjectname(projectName);
}
bool Hdf5Ros::dumpImage(const sensor_msgs::Image& image) const