|
1 |
| -#include "AzCore/Component/Entity.h" |
2 |
| -#include "AzCore/RTTI/ReflectContext.h" |
3 |
| -#include "AzCore/Serialization/Json/BaseJsonSerializer.h" |
4 |
| -#include "AzCore/Serialization/Json/JsonSerialization.h" |
5 |
| -#include "AzCore/Serialization/SerializeContext.h" |
6 |
| -#include "Odometry/ROS2WheelOdometry.h" |
7 |
| -#include <AzCore/IO/Streamer/Streamer.h> |
8 |
| -#include <AzCore/IO/Streamer/StreamerComponent.h> |
9 |
| -#include <AzCore/Memory/Memory.h> |
10 |
| -#include <AzCore/Memory/SystemAllocator.h> |
| 1 | +#include <Odometry/ROS2WheelOdometry.h> |
11 | 2 | #include <AzCore/UnitTest/TestTypes.h>
|
12 | 3 | #include <AzTest/AzTest.h>
|
13 |
| - |
14 |
| -#include <AzCore/Serialization/Json/JsonSystemComponent.h> |
15 |
| -#include <AzCore/UserSettings/UserSettingsComponent.h> |
16 |
| -#include <AzTest/GemTestEnvironment.h> |
17 |
| -#include <AzToolsFramework/UnitTest/ToolsTestApplication.h> |
| 4 | +#include <rapidjson/stringbuffer.h> |
| 5 | +#include <rapidjson/writer.h> |
18 | 6 |
|
19 | 7 | namespace UnitTest
|
20 | 8 | {
|
21 |
| - class ROS2SensorsTestEnvironment : public AZ::Test::GemTestEnvironment |
22 |
| - { |
23 |
| - // AZ::Test::GemTestEnvironment overrides ... |
24 |
| - void AddGemsAndComponents() override; |
25 |
| - AZ::ComponentApplication* CreateApplicationInstance() override; |
26 |
| - void PostSystemEntityActivate() override; |
27 |
| - |
28 |
| - public: |
29 |
| - ROS2SensorsTestEnvironment() = default; |
30 |
| - ~ROS2SensorsTestEnvironment() override = default; |
31 |
| - }; |
32 |
| - |
33 |
| - void ROS2SensorsTestEnvironment::AddGemsAndComponents() |
34 |
| - { |
35 |
| - AddActiveGems(AZStd::to_array<AZStd::string_view>({ "ROS2", "ROS2Sensors"})); |
36 |
| - AddDynamicModulePaths({ "ROS2" }); |
37 |
| - // AddComponentDescriptors(AZStd::initializer_list<AZ::ComponentDescriptor*>{ ROS2::ROS2WheelOdometryComponent::CreateDescriptor(), |
38 |
| - // AZ::JsonSystemComponent::CreateDescriptor() }); |
39 |
| - // AddRequiredComponents(AZStd::to_array<AZ::TypeId const>({ AZ::JsonSystemComponent::TYPEINFO_Uuid() })); |
40 |
| - } |
41 |
| - |
42 |
| - AZ::ComponentApplication* ROS2SensorsTestEnvironment::CreateApplicationInstance() |
43 |
| - { |
44 |
| - // Using ToolsTestApplication to have AzFramework and AzToolsFramework components. |
45 |
| - return aznew UnitTest::ToolsTestApplication("ROS2SensorsTestEnvironment"); |
46 |
| - } |
47 |
| - |
48 |
| - void ROS2SensorsTestEnvironment::PostSystemEntityActivate() |
49 |
| - { |
50 |
| - AZ::UserSettingsComponentRequestBus::Broadcast(&AZ::UserSettingsComponentRequests::DisableSaveOnFinalize); |
51 |
| - } |
52 |
| - |
53 | 9 | class ROS2SensorsTestFixture : public ::testing::Test
|
54 | 10 | {
|
55 | 11 | };
|
56 | 12 |
|
57 |
| - // Smoke test |
58 |
| - TEST_F(ROS2SensorsTestFixture, WheelOdometryComponent) |
| 13 | + // Store test for the old schema, where there is no configuration class. |
| 14 | + TEST_F(ROS2SensorsTestFixture, Deserialize_WhenOldSchemaProvided_StoresSuccessfully) |
59 | 15 | {
|
60 |
| - // Create a WheelOdometryComponent and check if it is created successfully |
61 |
| - // ROS2::ROS2WheelOdometryComponent wheelOdometryComponent; |
62 |
| - // EXPECT_NE(wheelOdometryComponent, nullptr); |
| 16 | + ROS2::ROS2WheelOdometryComponent wheelOdometryComponent; |
| 17 | + |
| 18 | + rapidjson::Document jsonDocument(rapidjson::kObjectType); |
| 19 | + jsonDocument.Parse(R"({ |
| 20 | + "Twist covariance": { |
| 21 | + "Linear covariance": [ |
| 22 | + 123.0, |
| 23 | + 456.0, |
| 24 | + 789.0 |
| 25 | + ], |
| 26 | + "Angular covariance": [ |
| 27 | + 987.0, |
| 28 | + 654.0, |
| 29 | + 321.0 |
| 30 | + ] |
| 31 | + }, |
| 32 | + "Pose covariance": { |
| 33 | + "Linear covariance": [ |
| 34 | + 321.0, |
| 35 | + 654.0, |
| 36 | + 987.0 |
| 37 | + ], |
| 38 | + "Angular covariance": [ |
| 39 | + 789.0, |
| 40 | + 456.0, |
| 41 | + 123.0 |
| 42 | + ] |
| 43 | + } |
| 44 | + })"); |
| 45 | + |
| 46 | + AZ::JsonDeserializerSettings settings; |
| 47 | + auto storeResult = AZ::JsonSerialization::Load(wheelOdometryComponent, jsonDocument, settings); |
| 48 | + |
| 49 | + EXPECT_EQ(storeResult.GetOutcome(), AZ::JsonSerializationResult::Outcomes::PartialDefaults); |
| 50 | + |
| 51 | + rapidjson::Document document(rapidjson::kObjectType); |
| 52 | + document.Parse("{}"); |
| 53 | + |
| 54 | + AZ::JsonSerializerSettings serializerSettings; |
| 55 | + serializerSettings.m_keepDefaults = true; |
| 56 | + |
| 57 | + AZ::JsonSerializationResult::ResultCode resultCode = |
| 58 | + AZ::JsonSerialization::Store(document, document.GetAllocator(), wheelOdometryComponent, serializerSettings); |
| 59 | + |
| 60 | + EXPECT_EQ(resultCode.GetOutcome(), AZ::JsonSerializationResult::Outcomes::Success); |
| 61 | + |
| 62 | + rapidjson::StringBuffer buffer; |
| 63 | + rapidjson::Writer<rapidjson::StringBuffer> writer(buffer); |
| 64 | + document.Accept(writer); |
| 65 | + |
| 66 | + const char* expectedOutput = |
| 67 | + R"~({"Id":0,"SensorConfiguration":{"Visualize":true,"Publishing Enabled":true,"Frequency (HZ)":10.0,"Publishers":{"nav_msgs::msg::Odometry":{"Type":"nav_msgs::msg::Odometry","Topic":"odom","QoS":{"Reliability":2,"Durability":2,"Depth":5}}}},"Odometry configuration":{"Pose covariance":{"Linear covariance":[321.0,654.0,987.0],"Angular covariance":[789.0,456.0,123.0]},"Twist covariance":{"Linear covariance":[123.0,456.0,789.0],"Angular covariance":[987.0,654.0,321.0]}}})~"; |
| 68 | + EXPECT_STREQ(buffer.GetString(), expectedOutput); |
63 | 69 | }
|
64 | 70 |
|
65 |
| - // Store test |
66 |
| - TEST_F(ROS2SensorsTestFixture, WheelOdometryComponentStore) |
| 71 | + // Store test for the new schema, where there is a configuration class. |
| 72 | + TEST_F(ROS2SensorsTestFixture, Deserialize_WhenNewSchemaProvided_StoresSuccessfully) |
67 | 73 | {
|
68 |
| - // // Create a WheelOdometryComponent and check if it is created successfully |
69 |
| - // ROS2::ROS2WheelOdometryComponent wheelOdometryComponent; |
70 |
| - // // EXPECT_NE(wheelOdometryComponent, nullptr); |
71 |
| - |
72 |
| - // // Create a JSON object to store the component's configuration |
73 |
| - // rapidjson::Document document; |
74 |
| - // document.SetObject(); |
75 |
| - |
76 |
| - // AZ::Entity entity; |
77 |
| - // // auto* wheelOdometryComponent |
78 |
| - |
79 |
| - // auto jsonDocument = AZStd::make_unique<rapidjson::Document>(); |
80 |
| - |
81 |
| - // AZ::JsonDeserializerSettings settings; |
82 |
| - // auto storeResult = AZ::JsonSerialization::Load(wheelOdometryComponent, *jsonDocument, settings); |
83 |
| - |
84 |
| - // // Check if the store operation was successful |
85 |
| - // EXPECT_EQ(storeResult.GetOutcome(), AZ::JsonSerializationResult::Outcomes::Success); |
| 74 | + ROS2::ROS2WheelOdometryComponent wheelOdometryComponent; |
| 75 | + |
| 76 | + rapidjson::Document jsonDocument(rapidjson::kObjectType); |
| 77 | + jsonDocument.Parse(R"({ |
| 78 | + "Odometry configuration": { |
| 79 | + "Twist covariance": { |
| 80 | + "Linear covariance": [ |
| 81 | + 123.0, |
| 82 | + 456.0, |
| 83 | + 789.0 |
| 84 | + ], |
| 85 | + "Angular covariance": [ |
| 86 | + 987.0, |
| 87 | + 654.0, |
| 88 | + 321.0 |
| 89 | + ] |
| 90 | + }, |
| 91 | + "Pose covariance": { |
| 92 | + "Linear covariance": [ |
| 93 | + 321.0, |
| 94 | + 654.0, |
| 95 | + 987.0 |
| 96 | + ], |
| 97 | + "Angular covariance": [ |
| 98 | + 789.0, |
| 99 | + 456.0, |
| 100 | + 123.0 |
| 101 | + ] |
| 102 | + } |
| 103 | + } |
| 104 | + })"); |
| 105 | + |
| 106 | + AZ::JsonDeserializerSettings settings; |
| 107 | + auto storeResult = AZ::JsonSerialization::Load(wheelOdometryComponent, jsonDocument, settings); |
| 108 | + |
| 109 | + EXPECT_EQ(storeResult.GetOutcome(), AZ::JsonSerializationResult::Outcomes::PartialDefaults); |
| 110 | + |
| 111 | + rapidjson::Document document(rapidjson::kObjectType); |
| 112 | + document.Parse("{}"); |
| 113 | + |
| 114 | + AZ::JsonSerializerSettings serializerSettings; |
| 115 | + serializerSettings.m_keepDefaults = true; |
| 116 | + |
| 117 | + AZ::JsonSerializationResult::ResultCode resultCode = |
| 118 | + AZ::JsonSerialization::Store(document, document.GetAllocator(), wheelOdometryComponent, serializerSettings); |
| 119 | + |
| 120 | + EXPECT_EQ(resultCode.GetOutcome(), AZ::JsonSerializationResult::Outcomes::Success); |
| 121 | + |
| 122 | + rapidjson::StringBuffer buffer; |
| 123 | + rapidjson::Writer<rapidjson::StringBuffer> writer(buffer); |
| 124 | + document.Accept(writer); |
| 125 | + |
| 126 | + const char* expectedOutput = |
| 127 | + R"~({"Id":0,"SensorConfiguration":{"Visualize":true,"Publishing Enabled":true,"Frequency (HZ)":10.0,"Publishers":{"nav_msgs::msg::Odometry":{"Type":"nav_msgs::msg::Odometry","Topic":"odom","QoS":{"Reliability":2,"Durability":2,"Depth":5}}}},"Odometry configuration":{"Pose covariance":{"Linear covariance":[321.0,654.0,987.0],"Angular covariance":[789.0,456.0,123.0]},"Twist covariance":{"Linear covariance":[123.0,456.0,789.0],"Angular covariance":[987.0,654.0,321.0]}}})~"; |
| 128 | + EXPECT_STREQ(buffer.GetString(), expectedOutput); |
86 | 129 | }
|
87 | 130 | } // namespace UnitTest
|
88 |
| - |
89 |
| -// required to support running integration tests with Qt and PhysX |
90 |
| -AZTEST_EXPORT int AZ_UNIT_TEST_HOOK_NAME(int argc, char** argv) |
91 |
| -{ |
92 |
| - ::testing::InitGoogleMock(&argc, argv); |
93 |
| - AZ::Test::printUnusedParametersWarning(argc, argv); |
94 |
| - AZ::Test::addTestEnvironments({ new UnitTest::ROS2SensorsTestEnvironment() }); |
95 |
| - int result = RUN_ALL_TESTS(); |
96 |
| - return result; |
97 |
| -} |
98 |
| - |
99 |
| -IMPLEMENT_TEST_EXECUTABLE_MAIN(); |
|
0 commit comments