Skip to content
Snippets Groups Projects
Commit 5d5a20b6 authored by Jeremie Deray's avatar Jeremie Deray
Browse files

serialization for a bunch of base class and simple derived + gtest

parent fc08ddb8
No related branches found
No related tags found
1 merge request!122Serialization
Showing
with 1879 additions and 1 deletion
INCLUDE_DIRECTORIES(${CMAKE_CURRENT_SOURCE_DIR}) INCLUDE_DIRECTORIES(${CMAKE_CURRENT_SOURCE_DIR})
SET(HDRS_SERIALIZATION ${HDRS_SERIALIZATION} SET(HDRS_SERIALIZATION ${HDRS_SERIALIZATION}
${CMAKE_CURRENT_SOURCE_DIR}/serialization_local_parametrization_base.h
${CMAKE_CURRENT_SOURCE_DIR}/serialization_local_parametrization_homogeneous.h
${CMAKE_CURRENT_SOURCE_DIR}/serialization_local_parametrization_quaternion.h
${CMAKE_CURRENT_SOURCE_DIR}/serialization_node_base.h
${CMAKE_CURRENT_SOURCE_DIR}/serialization_sensor_intrinsic_base.h
${CMAKE_CURRENT_SOURCE_DIR}/serialization_sensor_odom2d_intrinsic.h
${CMAKE_CURRENT_SOURCE_DIR}/serialization_processor_params_base.h
${CMAKE_CURRENT_SOURCE_DIR}/serialization_processor_odom2d_params.h
${CMAKE_CURRENT_SOURCE_DIR}/serialization_processor_odom3d_params.h
${CMAKE_CURRENT_SOURCE_DIR}/archives.h ${CMAKE_CURRENT_SOURCE_DIR}/archives.h
${CMAKE_CURRENT_SOURCE_DIR}/io.h ${CMAKE_CURRENT_SOURCE_DIR}/io.h
......
#ifndef _WOLF_IO_CEREAL_LOCAL_PARAMETRIZATION_BASE_H_
#define _WOLF_IO_CEREAL_LOCAL_PARAMETRIZATION_BASE_H_
#include "../../local_parametrization_base.h"
#include <cereal/cereal.hpp>
#include <cereal/types/polymorphic.hpp>
namespace cereal {
// Since classes deriving from LocalParametrizationBase
// have default constructor calling the non-default
// LocalParametrizationBase constructor with pre-defined
// arguments, there is nothing to save here.
template<class Archive>
inline void serialize(
Archive& /*ar*/,
wolf::LocalParametrizationBase& /*lpb*/,
std::uint32_t const /*file_version*/)
{
//
}
} //namespace cereal
#endif /* _WOLF_IO_CEREAL_LOCAL_PARAMETRIZATION_BASE_H_ */
#ifndef _WOLF_IO_CEREAL_LOCAL_PARAMETRIZATION_BASE_HOMOGENEOUS_H_
#define _WOLF_IO_CEREAL_LOCAL_PARAMETRIZATION_BASE_HOMOGENEOUS_H_
#include "../../local_parametrization_homogeneous.h"
#include "serialization_local_parametrization_base.h"
#include <cereal/cereal.hpp>
CEREAL_REGISTER_TYPE_WITH_NAME(wolf::LocalParametrizationHomogeneous,
"LocalParametrizationHomogeneous");
namespace cereal {
template<class Archive>
inline void serialize(
Archive& ar,
wolf::LocalParametrizationHomogeneous& lp,
std::uint32_t const /*file_version*/)
{
ar( cereal::make_nvp("LocalParametrizationBase",
cereal::base_class<wolf::LocalParametrizationBase>(&lp)) );
}
} //namespace cereal
#endif /* _WOLF_IO_CEREAL_LOCAL_PARAMETRIZATION_BASE_HOMOGENEOUS_H_ */
#ifndef WOLF_IO_SERIALIZATION_LOCAL_PARAMETRIZATION_QUATERNION_H_
#define WOLF_IO_SERIALIZATION_LOCAL_PARAMETRIZATION_QUATERNION_H_
#include "../../local_parametrization_quaternion.h"
#include "serialization_local_parametrization_base.h"
#include <cereal/cereal.hpp>
CEREAL_REGISTER_TYPE_WITH_NAME(wolf::LocalParametrizationQuaternion<wolf::DQ_LOCAL>,
"wolf_LocalParametrizationQuaternion_DQ_LOCAL")
CEREAL_REGISTER_TYPE_WITH_NAME(wolf::LocalParametrizationQuaternion<wolf::DQ_GLOBAL>,
"wolf_LocalParametrizationQuaternion_DQ_GLOBAL")
namespace cereal {
template<class Archive, unsigned int DeltaReference>
inline void serialize(
Archive &ar,
wolf::LocalParametrizationQuaternion<DeltaReference> &lp,
const unsigned int /*file_version*/)
{
ar( cereal::make_nvp("LocalParametrizationBase",
cereal::base_class<wolf::LocalParametrizationBase>(&lp)) );
}
} //namespace boost
#endif /* WOLF_IO_SERIALIZATION_LOCAL_PARAMETRIZATION_QUATERNION_H_ */
#ifndef _WOLF_SERIALIZATION_CEREAL_PROCESSOR_ODOM2D_PARAMS_H_
#define _WOLF_SERIALIZATION_CEREAL_PROCESSOR_ODOM2D_PARAMS_H_
// Wolf includes
#include "../../processor_odom_2D.h"
#include "serialization_processor_params_base.h"
namespace cereal {
template <class Archive>
void serialize(Archive& ar, wolf::ProcessorParamsOdom2D& o,
std::uint32_t const /*version*/)
{
ar( cereal::make_nvp("ProcessorParamsBase",
cereal::base_class<wolf::ProcessorParamsBase>(&o)) );
ar( cereal::make_nvp("cov_det_th_", o.cov_det_th_) );
ar( cereal::make_nvp("dist_traveled_th_", o.dist_traveled_th_) );
ar( cereal::make_nvp("elapsed_time_th_", o.elapsed_time_th_) );
ar( cereal::make_nvp("theta_traveled_th_", o.theta_traveled_th_) );
ar( cereal::make_nvp("unmeasured_perturbation_std_",
o.unmeasured_perturbation_std_) );
}
} // namespace cereal
CEREAL_REGISTER_TYPE_WITH_NAME(wolf::ProcessorParamsOdom2D, "ProcessorParamsOdom2D")
#endif /* _WOLF_SERIALIZATION_CEREAL_PROCESSOR_ODOM3D_PARAMS_H_ */
#ifndef _WOLF_SERIALIZATION_CEREAL_PROCESSOR_ODOM3D_PARAMS_H_
#define _WOLF_SERIALIZATION_CEREAL_PROCESSOR_ODOM3D_PARAMS_H_
// Wolf includes
#include "../../processor_odom_3D.h"
#include "serialization_processor_params_base.h"
namespace cereal {
template <class Archive>
void serialize(Archive& ar, wolf::ProcessorOdom3DParams& o,
std::uint32_t const /*version*/)
{
ar( cereal::make_nvp("ProcessorParamsBase",
cereal::base_class<wolf::ProcessorParamsBase>(&o)) );
ar( cereal::make_nvp("angle_turned", o.angle_turned) );
ar( cereal::make_nvp("dist_traveled", o.dist_traveled) );
ar( cereal::make_nvp("max_buff_length", o.max_buff_length) );
ar( cereal::make_nvp("max_time_span", o.max_time_span) );
}
} // namespace cereal
CEREAL_REGISTER_TYPE_WITH_NAME(wolf::ProcessorOdom3DParams, "ProcessorOdom3DParams")
#endif /* _WOLF_SERIALIZATION_CEREAL_PROCESSOR_ODOM3D_PARAMS_H_ */
#ifndef _WOLF_SERIALIZATION_CEREAL_PROCESSOR_PARAM_BASE_H_
#define _WOLF_SERIALIZATION_CEREAL_PROCESSOR_PARAM_BASE_H_
// Wolf includes
#include "../../processor_base.h"
#include <cereal/cereal.hpp>
#include <cereal/types/polymorphic.hpp>
namespace cereal {
template <class Archive>
void serialize(Archive& ar, wolf::ProcessorParamsBase& o,
std::uint32_t const /*version*/)
{
ar( cereal::make_nvp("type", o.type) );
ar( cereal::make_nvp("name", o.name) );
}
} // namespace cereal
#endif /* _WOLF_SERIALIZATION_CEREAL_SENSOR_INTRINSIC_BASE_H_ */
#ifndef _WOLF_SERIALIZATION_CEREAL_SENSOR_INTRINSIC_BASE_H_
#define _WOLF_SERIALIZATION_CEREAL_SENSOR_INTRINSIC_BASE_H_
// Wolf includes
#include "../../sensor_base.h"
#include <cereal/cereal.hpp>
#include <cereal/types/polymorphic.hpp>
namespace cereal {
template <class Archive>
void serialize(Archive& ar, wolf::IntrinsicsBase& o,
std::uint32_t const /*version*/)
{
ar( cereal::make_nvp("type", o.type) );
ar( cereal::make_nvp("name", o.name) );
}
} // namespace cereal
// No need to register base
//CEREAL_REGISTER_TYPE_WITH_NAME(wolf::IntrinsicsBase, "IntrinsicsBase");
#endif /* _WOLF_SERIALIZATION_CEREAL_SENSOR_INTRINSIC_BASE_H_ */
#ifndef _WOLF_SERIALIZATION_CEREAL_SENSOR_ODOM2D_INTRINSIC_H_
#define _WOLF_SERIALIZATION_CEREAL_SENSOR_ODOM2D_INTRINSIC_H_
// Wolf includes
#include "../../sensor_odom_2D.h"
#include "serialization_sensor_intrinsic_base.h"
namespace cereal {
template <class Archive>
void serialize(Archive& ar, wolf::IntrinsicsOdom2D& o,
std::uint32_t const /*version*/)
{
ar( cereal::make_nvp("IntrinsicsBase",
cereal::base_class<wolf::IntrinsicsBase>(&o)) );
ar( cereal::make_nvp("k_disp_to_disp", o.k_disp_to_disp) );
ar( cereal::make_nvp("k_rot_to_rot", o.k_rot_to_rot) );
}
} // namespace cereal
CEREAL_REGISTER_TYPE_WITH_NAME(wolf::IntrinsicsOdom2D, "IntrinsicsOdom2D")
#endif /* _WOLF_SERIALIZATION_CEREAL_SENSOR_ODOM2D_INTRINSIC_H_ */
...@@ -146,4 +146,8 @@ IF(OpenCV_FOUND) ...@@ -146,4 +146,8 @@ IF(OpenCV_FOUND)
wolf_add_gtest(gtest_roi_ORB gtest_roi_ORB.cpp) wolf_add_gtest(gtest_roi_ORB gtest_roi_ORB.cpp)
target_link_libraries(gtest_roi_ORB ${PROJECT_NAME}) target_link_libraries(gtest_roi_ORB ${PROJECT_NAME})
ENDIF(OpenCV_FOUND) ENDIF(OpenCV_FOUND)
\ No newline at end of file
# ------- Now Core classes Serialization ----------
add_subdirectory(serialization)
# cereal
IF(cereal_FOUND)
add_subdirectory(cereal)
ENDIF(cereal_FOUND)
# NodeBase serialization class test
wolf_add_gtest(gtest_cereal_serialization_node_base gtest_serialization_node_base.cpp)
target_link_libraries(gtest_cereal_serialization_node_base ${PROJECT_NAME})
wolf_add_gtest(gtest_cereal_serialization_local_parametrization
gtest_serialization_local_parametrization.cpp)
target_link_libraries(gtest_cereal_serialization_local_parametrization ${PROJECT_NAME})
wolf_add_gtest(gtest_cereal_serialization_sensor_intrinsic_base
gtest_serialization_sensor_intrinsic_base.cpp)
target_link_libraries(gtest_cereal_serialization_sensor_intrinsic_base ${PROJECT_NAME})
wolf_add_gtest(gtest_cereal_serialization_sensor_odom2d_intrinsic
gtest_serialization_sensor_odom2d_intrinsic.cpp)
target_link_libraries(gtest_cereal_serialization_sensor_odom2d_intrinsic ${PROJECT_NAME})
wolf_add_gtest(gtest_cereal_serialization_save_load
gtest_serialization_save_load.cpp)
target_link_libraries(gtest_cereal_serialization_save_load ${PROJECT_NAME})
wolf_add_gtest(gtest_cereal_serialization_processor_odom3d_params
gtest_serialization_processor_odom3d_params.cpp)
target_link_libraries(gtest_cereal_serialization_processor_odom3d_params ${PROJECT_NAME})
wolf_add_gtest(gtest_cereal_serialization_processor_odom2d_params
gtest_serialization_processor_odom2d_params.cpp)
target_link_libraries(gtest_cereal_serialization_processor_odom2d_params ${PROJECT_NAME})
/*
* gtest_node_base_serialization.cpp
*
* Created on: Jul 16, 2017
* Author: Jeremie Deray
*/
#include "../../utils_gtest.h"
#include "../../../serialization/cereal/serialization_local_parametrization_quaternion.h"
#include "../../../serialization/cereal/serialization_local_parametrization_homogeneous.h"
#include "../../../serialization/cereal/archives.h"
#include <cereal/types/memory.hpp>
#include <fstream>
///////////////////////////////////////
/// LocalParametrizationHomogeneous ///
///////////////////////////////////////
const std::string path_to_io = "/tmp/";
TEST(TestSerialization, SerializationLocalParametrizationHomogeneousXML)
{
{
std::ofstream os(path_to_io + "local_parametrization_serialization.xml");
cereal::XMLOutputArchive archive(os);
wolf::LocalParametrizationHomogeneous local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_serialization.xml");
cereal::XMLInputArchive archive(is);
wolf::LocalParametrizationHomogeneous local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h.getGlobalSize(), 4);
ASSERT_EQ(local_param_h.getLocalSize(), 3);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationHomogeneousXML !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationHomogeneousPtrXML)
{
using LocalParametrizationPtr = std::shared_ptr<wolf::LocalParametrizationBase> ;
{
std::ofstream os(path_to_io + "local_parametrization_ptr_serialization.xml");
cereal::XMLOutputArchive archive(os);
LocalParametrizationPtr local_param_h =
std::make_shared<wolf::LocalParametrizationHomogeneous>();
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_ptr_serialization.xml");
cereal::XMLInputArchive archive(is);
LocalParametrizationPtr local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h->getGlobalSize(), 4);
ASSERT_EQ(local_param_h->getLocalSize(), 3);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::LocalParametrizationHomogeneous>(local_param_h) != nullptr);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationHomogeneousPtrXML !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationHomogeneousJSON)
{
{
std::ofstream os(path_to_io + "local_parametrization_serialization.json");
cereal::JSONOutputArchive archive(os);
wolf::LocalParametrizationHomogeneous local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_serialization.json");
cereal::JSONInputArchive archive(is);
wolf::LocalParametrizationHomogeneous local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h.getGlobalSize(), 4);
ASSERT_EQ(local_param_h.getLocalSize(), 3);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationHomogeneousJSON !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationHomogeneousPtrJSON)
{
using LocalParametrizationPtr = std::shared_ptr<wolf::LocalParametrizationBase> ;
{
std::ofstream os(path_to_io + "local_parametrization_ptr_serialization.json");
cereal::JSONOutputArchive archive(os);
LocalParametrizationPtr local_param_h =
std::make_shared<wolf::LocalParametrizationHomogeneous>();
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_ptr_serialization.json");
cereal::JSONInputArchive archive(is);
LocalParametrizationPtr local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h->getGlobalSize(), 4);
ASSERT_EQ(local_param_h->getLocalSize(), 3);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::LocalParametrizationHomogeneous>(local_param_h) != nullptr);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationHomogeneousPtrJSON !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationHomogeneousBIN)
{
{
std::ofstream os(path_to_io + "local_parametrization_serialization.bin");
cereal::BinaryOutputArchive archive(os);
wolf::LocalParametrizationHomogeneous local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_serialization.bin");
cereal::BinaryInputArchive archive(is);
wolf::LocalParametrizationHomogeneous local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h.getGlobalSize(), 4);
ASSERT_EQ(local_param_h.getLocalSize(), 3);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationHomogeneousBIN !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationHomogeneousPtrBIN)
{
using LocalParametrizationPtr = std::shared_ptr<wolf::LocalParametrizationBase> ;
{
std::ofstream os(path_to_io + "local_parametrization_ptr_serialization.bin");
cereal::BinaryOutputArchive archive(os);
LocalParametrizationPtr local_param_h =
std::make_shared<wolf::LocalParametrizationHomogeneous>();
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_ptr_serialization.bin");
cereal::BinaryInputArchive archive(is);
LocalParametrizationPtr local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h->getGlobalSize(), 4);
ASSERT_EQ(local_param_h->getLocalSize(), 3);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::LocalParametrizationHomogeneous>(local_param_h) != nullptr);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationHomogeneousPtrBIN !\n");
}
//////////////////////////////////////
/// LocalParametrizationQuaternion ///
//////////////////////////////////////
//////////////////////////////////////
/// LOCAL ///
//////////////////////////////////////
TEST(TestSerialization, SerializationLocalParametrizationQuaternionXML)
{
{
std::ofstream os(path_to_io + "local_parametrization_quat_serialization.xml");
cereal::XMLOutputArchive archive(os);
wolf::LocalParametrizationQuaternionLocal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quat_serialization.xml");
cereal::XMLInputArchive archive(is);
wolf::LocalParametrizationQuaternionLocal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h.getGlobalSize(), 4);
ASSERT_EQ(local_param_h.getLocalSize(), 3);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionXML !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationQuaternionPtrXML)
{
using LocalParametrizationPtr = std::shared_ptr<wolf::LocalParametrizationBase> ;
{
std::ofstream os(path_to_io + "local_parametrization_quat_ptr_serialization.xml");
cereal::XMLOutputArchive archive(os);
LocalParametrizationPtr local_param_h =
std::make_shared<wolf::LocalParametrizationQuaternionLocal>();
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quat_ptr_serialization.xml");
cereal::XMLInputArchive archive(is);
LocalParametrizationPtr local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h->getGlobalSize(), 4);
ASSERT_EQ(local_param_h->getLocalSize(), 3);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::LocalParametrizationQuaternionLocal>(local_param_h) != nullptr);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionPtrXML !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationQuaternionJSON)
{
{
std::ofstream os(path_to_io + "local_parametrization_quat_serialization.json");
cereal::JSONOutputArchive archive(os);
wolf::LocalParametrizationQuaternionLocal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quat_serialization.json");
cereal::JSONInputArchive archive(is);
wolf::LocalParametrizationQuaternionLocal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h.getGlobalSize(), 4);
ASSERT_EQ(local_param_h.getLocalSize(), 3);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionJSON !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationQuaternionPtrJSON)
{
using LocalParametrizationPtr = std::shared_ptr<wolf::LocalParametrizationBase> ;
{
std::ofstream os(path_to_io + "local_parametrization_quat_ptr_serialization.json");
cereal::JSONOutputArchive archive(os);
LocalParametrizationPtr local_param_h =
std::make_shared<wolf::LocalParametrizationQuaternionLocal>();
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quat_ptr_serialization.json");
cereal::JSONInputArchive archive(is);
LocalParametrizationPtr local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h->getGlobalSize(), 4);
ASSERT_EQ(local_param_h->getLocalSize(), 3);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::LocalParametrizationQuaternionLocal>(local_param_h) != nullptr);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionPtrJSON !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationQuaternionBIN)
{
{
std::ofstream os(path_to_io + "local_parametrization_quat_serialization.bin");
cereal::BinaryOutputArchive archive(os);
wolf::LocalParametrizationQuaternionLocal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quat_serialization.bin");
cereal::BinaryInputArchive archive(is);
wolf::LocalParametrizationQuaternionLocal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h.getGlobalSize(), 4);
ASSERT_EQ(local_param_h.getLocalSize(), 3);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionBIN !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationQuaternionPtrBIN)
{
using LocalParametrizationPtr = std::shared_ptr<wolf::LocalParametrizationBase> ;
{
std::ofstream os(path_to_io + "local_parametrization_quat_ptr_serialization.bin");
cereal::BinaryOutputArchive archive(os);
LocalParametrizationPtr local_param_h =
std::make_shared<wolf::LocalParametrizationQuaternionLocal>();
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quat_ptr_serialization.bin");
cereal::BinaryInputArchive archive(is);
LocalParametrizationPtr local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h->getGlobalSize(), 4);
ASSERT_EQ(local_param_h->getLocalSize(), 3);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::LocalParametrizationQuaternionLocal>(local_param_h) != nullptr);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionPtrBIN !\n");
}
//////////////////////////////////////
/// GLOBAL ///
//////////////////////////////////////
TEST(TestSerialization, SerializationLocalParametrizationQuaternionGlobalXML)
{
{
std::ofstream os(path_to_io + "local_parametrization_quatg_serialization.xml");
cereal::XMLOutputArchive archive(os);
wolf::LocalParametrizationQuaternionGlobal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quatg_serialization.xml");
cereal::XMLInputArchive archive(is);
wolf::LocalParametrizationQuaternionGlobal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h.getGlobalSize(), 4);
ASSERT_EQ(local_param_h.getLocalSize(), 3);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionGlobalXML !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationQuaternionGlobalPtrXML)
{
using LocalParametrizationPtr = std::shared_ptr<wolf::LocalParametrizationBase> ;
{
std::ofstream os(path_to_io + "local_parametrization_quatg_ptr_serialization.xml");
cereal::XMLOutputArchive archive(os);
LocalParametrizationPtr local_param_h =
std::make_shared<wolf::LocalParametrizationQuaternionGlobal>();
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quatg_ptr_serialization.xml");
cereal::XMLInputArchive archive(is);
LocalParametrizationPtr local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h->getGlobalSize(), 4);
ASSERT_EQ(local_param_h->getLocalSize(), 3);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::LocalParametrizationQuaternionGlobal>(local_param_h) != nullptr);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionGlobalPtrXML !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationQuaternionGlobalJSON)
{
{
std::ofstream os(path_to_io + "local_parametrization_quatg_serialization.json");
cereal::JSONOutputArchive archive(os);
wolf::LocalParametrizationQuaternionGlobal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quatg_serialization.json");
cereal::JSONInputArchive archive(is);
wolf::LocalParametrizationQuaternionGlobal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h.getGlobalSize(), 4);
ASSERT_EQ(local_param_h.getLocalSize(), 3);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionGlobalJSON !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationQuaternionGlobalPtrJSON)
{
using LocalParametrizationPtr = std::shared_ptr<wolf::LocalParametrizationBase> ;
{
std::ofstream os(path_to_io + "local_parametrization_quatg_ptr_serialization.json");
cereal::JSONOutputArchive archive(os);
LocalParametrizationPtr local_param_h =
std::make_shared<wolf::LocalParametrizationQuaternionGlobal>();
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quatg_ptr_serialization.json");
cereal::JSONInputArchive archive(is);
LocalParametrizationPtr local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h->getGlobalSize(), 4);
ASSERT_EQ(local_param_h->getLocalSize(), 3);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::LocalParametrizationQuaternionGlobal>(local_param_h) != nullptr);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionGlobalPtrJSON !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationQuaternionGlobalBIN)
{
{
std::ofstream os(path_to_io + "local_parametrization_quatg_serialization.bin");
cereal::BinaryOutputArchive archive(os);
wolf::LocalParametrizationQuaternionGlobal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quatg_serialization.bin");
cereal::BinaryInputArchive archive(is);
wolf::LocalParametrizationQuaternionGlobal local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h.getGlobalSize(), 4);
ASSERT_EQ(local_param_h.getLocalSize(), 3);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionGlobalBIN !\n");
}
TEST(TestSerialization, SerializationLocalParametrizationQuaternionGlobalPtrBIN)
{
using LocalParametrizationPtr = std::shared_ptr<wolf::LocalParametrizationBase> ;
{
std::ofstream os(path_to_io + "local_parametrization_quatg_ptr_serialization.bin");
cereal::BinaryOutputArchive archive(os);
LocalParametrizationPtr local_param_h =
std::make_shared<wolf::LocalParametrizationQuaternionGlobal>();
ASSERT_NO_THROW( archive( local_param_h ) );
}
{
std::ifstream is(path_to_io + "local_parametrization_quatg_ptr_serialization.bin");
cereal::BinaryInputArchive archive(is);
LocalParametrizationPtr local_param_h;
ASSERT_NO_THROW( archive( local_param_h ) );
ASSERT_EQ(local_param_h->getGlobalSize(), 4);
ASSERT_EQ(local_param_h->getLocalSize(), 3);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::LocalParametrizationQuaternionGlobal>(local_param_h) != nullptr);
}
PRINTF("All good at TestSerialization::SerializationLocalParametrizationQuaternionGlobalPtrBIN !\n");
}
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
/*
* gtest_intrinsics_odom2d_serialization.cpp
*
* Created on: Jul 16, 2017
* Author: Jeremie Deray
*/
#include "../../utils_gtest.h"
#include "../../../serialization/cereal/serialization_processor_odom2d_params.h"
#include "../../../serialization/cereal/io.h"
#include <cereal/types/memory.hpp>
#include <fstream>
class WolfTestCerealSerializationProcessorParamsOdom2D : public testing::Test
{
public:
WolfTestCerealSerializationProcessorParamsOdom2D()
{
nb_.name = "NAME";
nb_.type = "ODOM 2D";
nb_.dist_traveled_th_ = 0.17;
nb_.theta_traveled_th_ = 0.3;
nb_.cov_det_th_ = 0.4;
nb_.elapsed_time_th_ = 1.5;
nb_.unmeasured_perturbation_std_ = 1e-5;
}
const std::string path_to_io = "/tmp/";
const std::string filename = "serialization_processor_odom2d_params";
const std::string ptr_ext = "_ptr";
const std::vector<std::string> exts = {".bin", ".xml", ".json"};
wolf::ProcessorParamsOdom2D nb_;
};
TEST_F(WolfTestCerealSerializationProcessorParamsOdom2D,
CerealSerializationProcessorParamsOdom2D)
{
for (const auto ext : exts)
{
const std::string full_path = path_to_io + filename + ext;
ASSERT_NO_THROW( wolf::save( full_path, nb_ ) )
<< "Failed on saving " << full_path;
wolf::ProcessorParamsOdom2D nb_load;
ASSERT_NO_THROW( wolf::load( full_path, nb_load ) )
<< "Failed on loading " << full_path;
ASSERT_EQ(nb_load.type, nb_.type) << full_path;
ASSERT_EQ(nb_load.name, nb_.name) << full_path;
ASSERT_EQ(nb_load.dist_traveled_th_, nb_.dist_traveled_th_) << full_path;
ASSERT_EQ(nb_load.theta_traveled_th_, nb_.theta_traveled_th_) << full_path;
ASSERT_EQ(nb_load.cov_det_th_, nb_.cov_det_th_) << full_path;
ASSERT_EQ(nb_load.unmeasured_perturbation_std_,
nb_.unmeasured_perturbation_std_) << full_path;
/// Testing BasePtr
const std::string ptr_full_path = path_to_io + filename + ptr_ext + ext;
{
wolf::ProcessorParamsBasePtr nb =
std::make_shared<wolf::ProcessorParamsOdom2D>(nb_);
ASSERT_NO_THROW( wolf::save( ptr_full_path, nb ) )
<< "Failed on saving " << ptr_full_path;
}
{
wolf::ProcessorParamsBasePtr nb;
ASSERT_NO_THROW( wolf::load( ptr_full_path, nb ) )
<< "Failed on loading " << ptr_full_path;
wolf::ProcessorParamsOdom2DPtr nb_cast =
std::dynamic_pointer_cast<wolf::ProcessorParamsOdom2D>(nb);
ASSERT_TRUE(nb_cast != nullptr)
<< "Failed on casting " << ptr_full_path;
ASSERT_EQ(nb_cast->type, nb_.type) << full_path;
ASSERT_EQ(nb_cast->name, nb_.name) << full_path;
ASSERT_EQ(nb_cast->dist_traveled_th_, nb_.dist_traveled_th_) << full_path;
ASSERT_EQ(nb_cast->theta_traveled_th_, nb_.theta_traveled_th_) << full_path;
ASSERT_EQ(nb_cast->cov_det_th_, nb_.cov_det_th_) << full_path;
ASSERT_EQ(nb_cast->unmeasured_perturbation_std_,
nb_.unmeasured_perturbation_std_) << full_path;
}
}
PRINTF("All good at "
"WolfTestCerealSerializationProcessorParamsOdom2D::"
"CerealSerializationProcessorParamsOdom2D !\n");
}
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
/*
* gtest_intrinsics_odom2d_serialization.cpp
*
* Created on: Jul 16, 2017
* Author: Jeremie Deray
*/
#include "../../utils_gtest.h"
#include "../../../serialization/cereal/serialization_processor_odom3d_params.h"
#include "../../../serialization/cereal/io.h"
#include <cereal/types/memory.hpp>
#include <fstream>
class WolfTestCerealSerializationProcessorOdom3DParams : public testing::Test
{
public:
WolfTestCerealSerializationProcessorOdom3DParams()
{
nb_.name = "NAME";
//nb_.type = "ODOM 3D";
nb_.max_time_span = 1.5;
nb_.max_buff_length = 55.;
nb_.dist_traveled = .25;
nb_.angle_turned = .17;
}
const std::string path_to_io = "/tmp/";
wolf::ProcessorOdom3DParams nb_;
};
TEST_F(WolfTestCerealSerializationProcessorOdom3DParams,
CerealSerializationProcessorOdom3DParamsXML)
{
const std::string filename(path_to_io + "params_odom3d_serialization.xml");
wolf::ProcessorOdom3DParams nb_save;
nb_save.name = "NAME2";
//nb_.type = "ODOM 3D";
nb_save.max_time_span = 2.5;
nb_save.max_buff_length = 52.;
nb_save.dist_traveled = .24;
nb_save.angle_turned = .18;
ASSERT_NO_THROW( wolf::save( filename, nb_, nb_save, 10 ) );
{
wolf::ProcessorOdom3DParams nb_load;
ASSERT_NO_THROW( wolf::load( filename, nb_load ) );
ASSERT_EQ(nb_load.type, nb_.type);
ASSERT_EQ(nb_load.name, nb_.name);
ASSERT_EQ(nb_load.max_time_span, nb_.max_time_span);
ASSERT_EQ(nb_load.max_buff_length, nb_.max_buff_length);
ASSERT_EQ(nb_load.dist_traveled, nb_.dist_traveled);
ASSERT_EQ(nb_load.angle_turned, nb_.angle_turned);
wolf::ProcessorOdom3DParams nb_load0, nb_load1;
int myint;
ASSERT_NO_THROW( wolf::load( filename, nb_load0, nb_load1, myint ) );
ASSERT_EQ(nb_load0.type, nb_.type);
ASSERT_EQ(nb_load0.name, nb_.name);
ASSERT_EQ(nb_load0.max_time_span, nb_.max_time_span);
ASSERT_EQ(nb_load0.max_buff_length, nb_.max_buff_length);
ASSERT_EQ(nb_load0.dist_traveled, nb_.dist_traveled);
ASSERT_EQ(nb_load0.angle_turned, nb_.angle_turned);
ASSERT_EQ(nb_load1.type, nb_save.type);
ASSERT_EQ(nb_load1.name, nb_save.name);
ASSERT_EQ(nb_load1.max_time_span, nb_save.max_time_span);
ASSERT_EQ(nb_load1.max_buff_length, nb_save.max_buff_length);
ASSERT_EQ(nb_load1.dist_traveled, nb_save.dist_traveled);
ASSERT_EQ(nb_load1.angle_turned, nb_save.angle_turned);
ASSERT_EQ(myint, 10);
}
PRINTF("All good at "
"WolfTestCerealSerializationProcessorOdom3DParams::"
"CerealSerializationProcessorOdom3DParamsXML !\n");
}
TEST_F(WolfTestCerealSerializationProcessorOdom3DParams,
CerealSerializationProcessorOdom3DParamsPtrXML)
{
const std::string filename(path_to_io + "params_odom3d_ptr_serialization.xml");
{
wolf::ProcessorParamsBasePtr nb =
std::make_shared<wolf::ProcessorOdom3DParams>(nb_);
ASSERT_NO_THROW( wolf::save( filename, nb ) );
}
{
wolf::ProcessorParamsBasePtr nb;
ASSERT_NO_THROW( wolf::load( filename, nb ) );
wolf::ProcessorOdom3DParamsPtr nb_cast =
std::dynamic_pointer_cast<wolf::ProcessorOdom3DParams>(nb);
ASSERT_TRUE(nb_cast != nullptr);
ASSERT_EQ(nb_cast->type, nb_.type);
ASSERT_EQ(nb_cast->name, nb_.name);
ASSERT_EQ(nb_cast->max_time_span, nb_.max_time_span);
ASSERT_EQ(nb_cast->max_buff_length, nb_.max_buff_length);
ASSERT_EQ(nb_cast->dist_traveled, nb_.dist_traveled);
ASSERT_EQ(nb_cast->angle_turned, nb_.angle_turned);
}
PRINTF("All good at "
"WolfTestCerealSerializationProcessorOdom3DParams::"
"CerealSerializationProcessorOdom3DParamsPtrXML !\n");
}
TEST_F(WolfTestCerealSerializationProcessorOdom3DParams,
CerealSerializationProcessorOdom3DParamsJSON)
{
const std::string filename(path_to_io + "params_odom3d_serialization.json");
ASSERT_NO_THROW( wolf::save( filename, nb_ ) );
wolf::ProcessorOdom3DParams nb_load;
ASSERT_NO_THROW( wolf::load( filename, nb_load ) );
ASSERT_EQ(nb_load.type, nb_.type);
ASSERT_EQ(nb_load.name, nb_.name);
ASSERT_EQ(nb_load.max_time_span, nb_.max_time_span);
ASSERT_EQ(nb_load.max_buff_length, nb_.max_buff_length);
ASSERT_EQ(nb_load.dist_traveled, nb_.dist_traveled);
ASSERT_EQ(nb_load.angle_turned, nb_.angle_turned);
PRINTF("All good at "
"WolfTestCerealSerializationProcessorOdom3DParams::"
"CerealSerializationProcessorOdom3DParamsJSON !\n");
}
TEST_F(WolfTestCerealSerializationProcessorOdom3DParams,
CerealSerializationProcessorOdom3DParamsPtrJSON)
{
const std::string filename(path_to_io + "params_odom3d_ptr_serialization.json");
{
wolf::ProcessorParamsBasePtr nb =
std::make_shared<wolf::ProcessorOdom3DParams>(nb_);
ASSERT_NO_THROW( wolf::save( filename, nb ) );
}
{
wolf::ProcessorParamsBasePtr nb;
ASSERT_NO_THROW( wolf::load( filename, nb ) );
wolf::ProcessorOdom3DParamsPtr nb_cast =
std::dynamic_pointer_cast<wolf::ProcessorOdom3DParams>(nb);
ASSERT_TRUE(nb_cast != nullptr);
ASSERT_EQ(nb_cast->type, nb_.type);
ASSERT_EQ(nb_cast->name, nb_.name);
ASSERT_EQ(nb_cast->max_time_span, nb_.max_time_span);
ASSERT_EQ(nb_cast->max_buff_length, nb_.max_buff_length);
ASSERT_EQ(nb_cast->dist_traveled, nb_.dist_traveled);
ASSERT_EQ(nb_cast->angle_turned, nb_.angle_turned);
}
PRINTF("All good at "
"WolfTestCerealSerializationProcessorOdom3DParams::"
"CerealSerializationProcessorOdom3DParamsPtrJSON !\n");
}
TEST_F(WolfTestCerealSerializationProcessorOdom3DParams,
CerealSerializationProcessorOdom3DParamsBinary)
{
const std::string filename(path_to_io + "params_odom3d_serialization.bin");
ASSERT_NO_THROW( wolf::save( filename, nb_ ) );
wolf::ProcessorOdom3DParams nb_load;
ASSERT_NO_THROW( wolf::load( filename, nb_load ) );
ASSERT_EQ(nb_load.type, nb_.type);
ASSERT_EQ(nb_load.name, nb_.name);
ASSERT_EQ(nb_load.max_time_span, nb_.max_time_span);
ASSERT_EQ(nb_load.max_buff_length, nb_.max_buff_length);
ASSERT_EQ(nb_load.dist_traveled, nb_.dist_traveled);
ASSERT_EQ(nb_load.angle_turned, nb_.angle_turned);
PRINTF("All good at "
"WolfTestCerealSerializationProcessorOdom3DParams::"
"CerealSerializationProcessorOdom3DParamsBinary !\n");
}
TEST_F(WolfTestCerealSerializationProcessorOdom3DParams,
CerealSerializationProcessorOdom3DParamsPtrBinary)
{
const std::string filename(path_to_io + "params_odom3d_ptr_serialization.bin");
{
wolf::ProcessorParamsBasePtr nb =
std::make_shared<wolf::ProcessorOdom3DParams>(nb_);
ASSERT_NO_THROW( wolf::save( filename, nb ) );
}
{
wolf::ProcessorParamsBasePtr nb;
ASSERT_NO_THROW( wolf::load( filename, nb ) );
wolf::ProcessorOdom3DParamsPtr nb_cast =
std::dynamic_pointer_cast<wolf::ProcessorOdom3DParams>(nb);
ASSERT_TRUE(nb_cast != nullptr);
ASSERT_EQ(nb_cast->type, nb_.type);
ASSERT_EQ(nb_cast->name, nb_.name);
ASSERT_EQ(nb_cast->max_time_span, nb_.max_time_span);
ASSERT_EQ(nb_cast->max_buff_length, nb_.max_buff_length);
ASSERT_EQ(nb_cast->dist_traveled, nb_.dist_traveled);
ASSERT_EQ(nb_cast->angle_turned, nb_.angle_turned);
}
PRINTF("All good at "
"WolfTestCerealSerializationProcessorOdom3DParams::"
"CerealSerializationProcessorOdom3DParamsPtrBinary !\n");
}
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
/*
* gtest_intrinsics_odom2d_serialization.cpp
*
* Created on: Jul 16, 2017
* Author: Jeremie Deray
*/
#include "../../utils_gtest.h"
#include "../../../serialization/cereal/io.h"
#include "../../../serialization/cereal/serialization_sensor_odom2d_intrinsic.h"
#include "../../../serialization/cereal/archives.h"
#include <cereal/types/memory.hpp>
#include <fstream>
namespace wolf {
using IntrinsicsOdom2DPtr = std::shared_ptr<IntrinsicsOdom2D>;
}
class WolfTestCerealSerializationSaveLoad : public testing::Test
{
public:
WolfTestCerealSerializationSaveLoad()
{
//
}
const std::string path_to_io = "/tmp/";
decltype(std::declval<wolf::IntrinsicsOdom2D>().type) nb_type = "TYPE";
decltype(std::declval<wolf::IntrinsicsOdom2D>().name) nb_name = "NAME";
decltype(std::declval<wolf::IntrinsicsOdom2D>().k_disp_to_disp) nb_k_disp_to_disp = 0.54;
decltype(std::declval<wolf::IntrinsicsOdom2D>().k_rot_to_rot) nb_k_rot_to_rot = 0.18;
};
TEST_F(WolfTestCerealSerializationSaveLoad, CerealSerializationSaveLoadExtension)
{
const std::string xml = "/test/filename.xml";
const std::string bin = "/test/filename.bin";
const std::string json = "/test/filename.json";
ASSERT_EQ(wolf::serialization::extension(xml), ".xml");
ASSERT_EQ(wolf::serialization::extension(bin), ".bin");
ASSERT_EQ(wolf::serialization::extension(json), ".json");
}
TEST_F(WolfTestCerealSerializationSaveLoad,
CerealSerializationSaveLoadXML)
{
const std::string filename = path_to_io + "save_load_serialization.xml";
{
wolf::IntrinsicsOdom2D nb;
nb.type = nb_type;
nb.name = nb_name;
nb.k_disp_to_disp = nb_k_disp_to_disp;
nb.k_rot_to_rot = nb_k_rot_to_rot;
ASSERT_NO_THROW( wolf::save( filename, nb ) );
}
{
wolf::IntrinsicsOdom2D nb;
ASSERT_NO_THROW( wolf::load( filename, nb ) );
ASSERT_EQ(nb.type, nb_type);
ASSERT_EQ(nb.name, nb_name);
ASSERT_EQ(nb.k_disp_to_disp, nb_k_disp_to_disp);
ASSERT_EQ(nb.k_rot_to_rot, nb_k_rot_to_rot);
}
PRINTF("All good at "
"WolfTestCerealSerializationSaveLoad::"
"CerealSerializationSaveLoadXML !\n");
}
TEST_F(WolfTestCerealSerializationSaveLoad,
CerealSerializationSaveLoadJSON)
{
const std::string filename = path_to_io + "save_load_serialization.json";
{
wolf::IntrinsicsOdom2D nb;
nb.type = nb_type;
nb.name = nb_name;
nb.k_disp_to_disp = nb_k_disp_to_disp;
nb.k_rot_to_rot = nb_k_rot_to_rot;
ASSERT_NO_THROW( wolf::save( filename, nb ) );
}
{
wolf::IntrinsicsOdom2D nb;
ASSERT_NO_THROW( wolf::load( filename, nb ) );
ASSERT_EQ(nb.type, nb_type);
ASSERT_EQ(nb.name, nb_name);
ASSERT_EQ(nb.k_disp_to_disp, nb_k_disp_to_disp);
ASSERT_EQ(nb.k_rot_to_rot, nb_k_rot_to_rot);
}
PRINTF("All good at "
"WolfTestCerealSerializationSaveLoad::"
"CerealSerializationSaveLoadJSON !\n");
}
TEST_F(WolfTestCerealSerializationSaveLoad,
CerealSerializationSaveLoadBinary)
{
const std::string filename = path_to_io + "save_load_serialization.bin";
{
wolf::IntrinsicsOdom2D nb;
nb.type = nb_type;
nb.name = nb_name;
nb.k_disp_to_disp = nb_k_disp_to_disp;
nb.k_rot_to_rot = nb_k_rot_to_rot;
ASSERT_NO_THROW( wolf::save( filename, nb ) );
}
{
wolf::IntrinsicsOdom2D nb;
ASSERT_NO_THROW( wolf::load( filename, nb ) );
ASSERT_EQ(nb.type, nb_type);
ASSERT_EQ(nb.name, nb_name);
ASSERT_EQ(nb.k_disp_to_disp, nb_k_disp_to_disp);
ASSERT_EQ(nb.k_rot_to_rot, nb_k_rot_to_rot);
}
PRINTF("All good at "
"WolfTestCerealSerializationSaveLoad::"
"CerealSerializationSaveLoadBinary !\n");
}
TEST_F(WolfTestCerealSerializationSaveLoad,
CerealSerializationSaveLoadNoExt)
{
const std::string filename = path_to_io + "save_load_serialization_no_ext";
{
wolf::IntrinsicsOdom2D nb;
nb.type = nb_type;
nb.name = nb_name;
nb.k_disp_to_disp = nb_k_disp_to_disp;
nb.k_rot_to_rot = nb_k_rot_to_rot;
ASSERT_NO_THROW( wolf::save( filename, nb ) );
}
{
wolf::IntrinsicsOdom2D nb;
ASSERT_NO_THROW( wolf::load( filename, nb ) );
ASSERT_EQ(nb.type, nb_type);
ASSERT_EQ(nb.name, nb_name);
ASSERT_EQ(nb.k_disp_to_disp, nb_k_disp_to_disp);
ASSERT_EQ(nb.k_rot_to_rot, nb_k_rot_to_rot);
}
PRINTF("All good at "
"WolfTestCerealSerializationSaveLoad::"
"CerealSerializationSaveLoadNoExt !\n");
}
TEST_F(WolfTestCerealSerializationSaveLoad,
CerealSerializationSaveLoadUnknownExt)
{
const std::string filename = path_to_io + "save_load_serialization.foo";
{
wolf::IntrinsicsOdom2D nb;
ASSERT_THROW( wolf::save( filename, nb ), std::runtime_error );
}
{
wolf::IntrinsicsOdom2D nb;
ASSERT_THROW( wolf::load( filename, nb ), std::runtime_error );
}
PRINTF("All good at "
"WolfTestCerealSerializationSaveLoad::"
"CerealSerializationSaveLoadUnknownExt !\n");
}
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
/*
* gtest_intrinsics_base_serialization.cpp
*
* Created on: Jul 16, 2017
* Author: Jeremie Deray
*/
#include "../../utils_gtest.h"
#include "../../../serialization/cereal/serialization_sensor_intrinsic_base.h"
#include "../../../serialization/cereal/archives.h"
#include <cereal/types/memory.hpp>
#include <fstream>
class WolfTestCerealSerializationIntrinsicsBase : public testing::Test
{
public:
WolfTestCerealSerializationIntrinsicsBase()
{
//
}
const std::string path_to_io = "/tmp/";
decltype(std::declval<wolf::IntrinsicsBase>().type) nb_type = "TYPE";
decltype(std::declval<wolf::IntrinsicsBase>().name) nb_name = "NAME";
};
TEST_F(WolfTestCerealSerializationIntrinsicsBase,
CerealSerializationIntrinsicsBaseXML)
{
{
wolf::IntrinsicsBase nb;
nb.type = nb_type;
nb.name = nb_name;
std::ofstream os(path_to_io + "intrinsics_base_serialization.xml");
cereal::XMLOutputArchive xml_archive(os);
ASSERT_NO_THROW( xml_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_base_serialization.xml");
cereal::XMLInputArchive xml_archive(is);
wolf::IntrinsicsBase nb;
ASSERT_NO_THROW( xml_archive( nb ) );
ASSERT_EQ(nb.type, nb_type);
ASSERT_EQ(nb.name, nb_name);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsBase::"
"CerealSerializationIntrinsicsBaseXML !\n");
}
TEST_F(WolfTestCerealSerializationIntrinsicsBase,
CerealSerializationIntrinsicsBasePtrXML)
{
{
wolf::IntrinsicsBasePtr nb = std::make_shared<wolf::IntrinsicsBase>();
nb->name = nb_name;
nb->type = nb_type;
std::ofstream os(path_to_io + "intrinsics_base_ptr_serialization.xml");
cereal::XMLOutputArchive xml_archive(os);
ASSERT_NO_THROW( xml_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_base_ptr_serialization.xml");
cereal::XMLInputArchive xml_archive(is);
wolf::IntrinsicsBasePtr nb;
ASSERT_NO_THROW( xml_archive( nb ) );
ASSERT_EQ(nb->type, nb_type);
ASSERT_EQ(nb->name, nb_name);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::IntrinsicsBase>(nb) != nullptr);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsBase::"
"CerealSerializationIntrinsicsBasePtrXML !\n");
}
TEST_F(WolfTestCerealSerializationIntrinsicsBase,
CerealSerializationIntrinsicsBaseJSON)
{
{
wolf::IntrinsicsBase nb;
nb.type = nb_type;
nb.name = nb_name;
std::ofstream os(path_to_io + "intrinsics_base_serialization.json");
cereal::JSONOutputArchive json_archive(os);
ASSERT_NO_THROW( json_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_base_serialization.json");
cereal::JSONInputArchive json_archive(is);
wolf::IntrinsicsBase nb;
ASSERT_NO_THROW( json_archive( nb ) );
ASSERT_EQ(nb.type, nb_type);
ASSERT_EQ(nb.name, nb_name);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsBase::"
"CerealSerializationIntrinsicsBaseJSON !\n");
}
TEST_F(WolfTestCerealSerializationIntrinsicsBase,
CerealSerializationIntrinsicsBasePtrJSON)
{
{
wolf::IntrinsicsBasePtr nb = std::make_shared<wolf::IntrinsicsBase>();
nb->name = nb_name;
nb->type = nb_type;
std::ofstream os(path_to_io + "intrinsics_base_ptr_serialization.json");
cereal::JSONOutputArchive json_archive(os);
ASSERT_NO_THROW( json_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_base_ptr_serialization.json");
cereal::JSONInputArchive json_archive(is);
wolf::IntrinsicsBasePtr nb;
ASSERT_NO_THROW( json_archive( nb ) );
ASSERT_EQ(nb->type, nb_type);
ASSERT_EQ(nb->name, nb_name);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::IntrinsicsBase>(nb) != nullptr);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsBase::"
"CerealSerializationIntrinsicsBasePtrJSON !\n");
}
TEST_F(WolfTestCerealSerializationIntrinsicsBase,
CerealSerializationIntrinsicsBaseBinary)
{
{
wolf::IntrinsicsBase nb;
nb.type = nb_type;
nb.name = nb_name;
std::ofstream os(path_to_io + "intrinsics_base_serialization.bin");
cereal::BinaryOutputArchive bin_archive(os);
ASSERT_NO_THROW( bin_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_base_serialization.bin");
cereal::BinaryInputArchive bin_archive(is);
wolf::IntrinsicsBase nb;
ASSERT_NO_THROW( bin_archive( nb ) );
ASSERT_EQ(nb.type, nb_type);
ASSERT_EQ(nb.name, nb_name);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsBase::"
"CerealSerializationIntrinsicsBaseBinary !\n");
}
TEST_F(WolfTestCerealSerializationIntrinsicsBase, CerealSerializationIntrinsicsBasePtrBinary)
{
{
wolf::IntrinsicsBasePtr nb = std::make_shared<wolf::IntrinsicsBase>();
nb->name = nb_name;
nb->type = nb_type;
std::ofstream os(path_to_io + "intrinsics_base_ptr_serialization.bin");
cereal::BinaryOutputArchive bin_archive(os);
ASSERT_NO_THROW( bin_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_base_ptr_serialization.bin");
cereal::BinaryInputArchive bin_archive(is);
wolf::IntrinsicsBasePtr nb;
ASSERT_NO_THROW( bin_archive( nb ) );
ASSERT_EQ(nb->type, nb_type);
ASSERT_EQ(nb->name, nb_name);
ASSERT_TRUE(
std::dynamic_pointer_cast<
wolf::IntrinsicsBase>(nb) != nullptr);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsBase::"
"CerealSerializationIntrinsicsBasePtrBinary !\n");
}
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
/*
* gtest_intrinsics_odom2d_serialization.cpp
*
* Created on: Jul 16, 2017
* Author: Jeremie Deray
*/
#include "../../utils_gtest.h"
#include "../../../serialization/cereal/serialization_sensor_odom2d_intrinsic.h"
#include "../../../serialization/cereal/archives.h"
#include <cereal/types/memory.hpp>
#include <fstream>
namespace wolf {
using IntrinsicsOdom2DPtr = std::shared_ptr<IntrinsicsOdom2D>;
}
class WolfTestCerealSerializationIntrinsicsOdom2D : public testing::Test
{
public:
WolfTestCerealSerializationIntrinsicsOdom2D()
{
nb_.k_disp_to_disp = 0.54;
nb_.k_rot_to_rot = 0.18;
nb_.name = "NAME";
nb_.type = "TYPE";
}
const std::string path_to_io = "/tmp/";
wolf::IntrinsicsOdom2D nb_;
};
TEST_F(WolfTestCerealSerializationIntrinsicsOdom2D,
CerealSerializationIntrinsicsOdom2DXML)
{
{
wolf::IntrinsicsOdom2D nb;
nb.type = nb_.type;
nb.name = nb_.name;
nb.k_disp_to_disp = nb_.k_disp_to_disp;
nb.k_rot_to_rot = nb_.k_rot_to_rot;
std::ofstream os(path_to_io + "intrinsics_odom2d_serialization.xml");
cereal::XMLOutputArchive xml_archive(os);
ASSERT_NO_THROW( xml_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_odom2d_serialization.xml");
cereal::XMLInputArchive xml_archive(is);
wolf::IntrinsicsOdom2D nb;
ASSERT_NO_THROW( xml_archive( nb ) );
ASSERT_EQ(nb.type, nb_.type);
ASSERT_EQ(nb.name, nb_.name);
ASSERT_EQ(nb.k_disp_to_disp, nb_.k_disp_to_disp);
ASSERT_EQ(nb.k_rot_to_rot, nb_.k_rot_to_rot);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsOdom2D::"
"CerealSerializationIntrinsicsOdom2DXML !\n");
}
TEST_F(WolfTestCerealSerializationIntrinsicsOdom2D,
CerealSerializationIntrinsicsOdom2DPtrXML)
{
{
wolf::IntrinsicsBasePtr nb = std::make_shared<wolf::IntrinsicsOdom2D>(nb_);
std::ofstream os(path_to_io + "intrinsics_odom2d_ptr_serialization.xml");
cereal::XMLOutputArchive xml_archive(os);
ASSERT_NO_THROW( xml_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_odom2d_ptr_serialization.xml");
cereal::XMLInputArchive xml_archive(is);
wolf::IntrinsicsBasePtr nb;
ASSERT_NO_THROW( xml_archive( nb ) );
wolf::IntrinsicsOdom2DPtr nb_cast =
std::dynamic_pointer_cast<wolf::IntrinsicsOdom2D>(nb);
ASSERT_TRUE(nb_cast != nullptr);
ASSERT_EQ(nb_cast->type, nb_.type);
ASSERT_EQ(nb_cast->name, nb_.name);
ASSERT_EQ(nb_cast->k_disp_to_disp, nb_.k_disp_to_disp);
ASSERT_EQ(nb_cast->k_rot_to_rot, nb_.k_rot_to_rot);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsOdom2D::"
"CerealSerializationIntrinsicsOdom2DPtrXML !\n");
}
TEST_F(WolfTestCerealSerializationIntrinsicsOdom2D,
CerealSerializationIntrinsicsOdom2DJSON)
{
{
wolf::IntrinsicsOdom2D nb;
nb.type = nb_.type;
nb.name = nb_.name;
nb.k_disp_to_disp = nb_.k_disp_to_disp;
nb.k_rot_to_rot = nb_.k_rot_to_rot;
std::ofstream os(path_to_io + "intrinsics_odom2d_serialization.json");
cereal::JSONOutputArchive json_archive(os);
ASSERT_NO_THROW( json_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_odom2d_serialization.json");
cereal::JSONInputArchive json_archive(is);
wolf::IntrinsicsOdom2D nb;
ASSERT_NO_THROW( json_archive( nb ) );
ASSERT_EQ(nb.type, nb_.type);
ASSERT_EQ(nb.name, nb_.name);
ASSERT_EQ(nb.k_disp_to_disp, nb_.k_disp_to_disp);
ASSERT_EQ(nb.k_rot_to_rot, nb_.k_rot_to_rot);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsOdom2D::"
"CerealSerializationIntrinsicsOdom2DJSON !\n");
}
TEST_F(WolfTestCerealSerializationIntrinsicsOdom2D,
CerealSerializationIntrinsicsOdom2DPtrJSON)
{
{
wolf::IntrinsicsBasePtr nb = std::make_shared<wolf::IntrinsicsOdom2D>(nb_);
std::ofstream os(path_to_io + "intrinsics_odom2d_ptr_serialization.json");
cereal::JSONOutputArchive json_archive(os);
ASSERT_NO_THROW( json_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_odom2d_ptr_serialization.json");
cereal::JSONInputArchive json_archive(is);
wolf::IntrinsicsBasePtr nb;
ASSERT_NO_THROW( json_archive( nb ) );
wolf::IntrinsicsOdom2DPtr nb_cast =
std::dynamic_pointer_cast<wolf::IntrinsicsOdom2D>(nb);
ASSERT_TRUE(nb_cast != nullptr);
ASSERT_EQ(nb_cast->type, nb_.type);
ASSERT_EQ(nb_cast->name, nb_.name);
ASSERT_EQ(nb_cast->k_disp_to_disp, nb_.k_disp_to_disp);
ASSERT_EQ(nb_cast->k_rot_to_rot, nb_.k_rot_to_rot);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsOdom2D::"
"CerealSerializationIntrinsicsOdom2DPtrJSON !\n");
}
TEST_F(WolfTestCerealSerializationIntrinsicsOdom2D,
CerealSerializationIntrinsicsOdom2DBinary)
{
{
wolf::IntrinsicsOdom2D nb;
nb.type = nb_.type;
nb.name = nb_.name;
nb.k_disp_to_disp = nb_.k_disp_to_disp;
nb.k_rot_to_rot = nb_.k_rot_to_rot;
std::ofstream os(path_to_io + "intrinsics_odom2d_serialization.bin");
cereal::BinaryOutputArchive bin_archive(os);
ASSERT_NO_THROW( bin_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_odom2d_serialization.bin");
cereal::BinaryInputArchive bin_archive(is);
wolf::IntrinsicsOdom2D nb;
ASSERT_NO_THROW( bin_archive( nb ) );
ASSERT_EQ(nb.type, nb_.type);
ASSERT_EQ(nb.name, nb_.name);
ASSERT_EQ(nb.k_disp_to_disp, nb_.k_disp_to_disp);
ASSERT_EQ(nb.k_rot_to_rot, nb_.k_rot_to_rot);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsOdom2D::"
"CerealSerializationIntrinsicsOdom2DBinary !\n");
}
TEST_F(WolfTestCerealSerializationIntrinsicsOdom2D, CerealSerializationIntrinsicsOdom2DPtrBinary)
{
{
wolf::IntrinsicsBasePtr nb = std::make_shared<wolf::IntrinsicsOdom2D>(nb_);
std::ofstream os(path_to_io + "intrinsics_odom2d_ptr_serialization.bin");
cereal::BinaryOutputArchive bin_archive(os);
ASSERT_NO_THROW( bin_archive( nb ) );
}
{
std::ifstream is(path_to_io + "intrinsics_odom2d_ptr_serialization.bin");
cereal::BinaryInputArchive bin_archive(is);
wolf::IntrinsicsBasePtr nb;
ASSERT_NO_THROW( bin_archive( nb ) );
wolf::IntrinsicsOdom2DPtr nb_cast =
std::dynamic_pointer_cast<wolf::IntrinsicsOdom2D>(nb);
ASSERT_TRUE(nb_cast != nullptr);
ASSERT_EQ(nb_cast->type, nb_.type);
ASSERT_EQ(nb_cast->name, nb_.name);
ASSERT_EQ(nb_cast->k_disp_to_disp, nb_.k_disp_to_disp);
ASSERT_EQ(nb_cast->k_rot_to_rot, nb_.k_rot_to_rot);
}
PRINTF("All good at "
"WolfTestCerealSerializationIntrinsicsOdom2D::"
"CerealSerializationIntrinsicsOdom2DPtrBinary !\n");
}
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment