Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ set(msg_files
"msg/Action.msg"
"msg/ActionParameter.msg"
"msg/ActionParameterFactsheet.msg"
"msg/ActionParameterValue.msg"
"msg/ActionState.msg"
"msg/AGVAction.msg"
"msg/AGVGeometry.msg"
Expand Down
3 changes: 1 addition & 2 deletions include/vda5050_interfaces/json_utils/action_parameter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@

#include <nlohmann/json.hpp>

#include "vda5050_interfaces/json_utils/action_parameter_value.hpp"
#include "vda5050_interfaces/msg/action_parameter.hpp"

namespace vda5050_interfaces {
Expand All @@ -48,7 +47,7 @@ inline void to_json(nlohmann::json& j, const ActionParameter& msg)
inline void from_json(const nlohmann::json& j, ActionParameter& msg)
{
msg.key = j.at("key").get<std::string>();
msg.value = j.at("value").get<ActionParameterValue>();
msg.value = j.at("value").get<std::string>();
}

} // namespace msg
Expand Down
2 changes: 1 addition & 1 deletion msg/ActionParameter.msg
Original file line number Diff line number Diff line change
Expand Up @@ -9,5 +9,5 @@ string key
# The value of the parameter that belongs to the key
#
# Field Type: Required
ActionParameterValue value
string value

21 changes: 0 additions & 21 deletions msg/ActionParameterValue.msg

This file was deleted.

30 changes: 1 addition & 29 deletions test/generator/generator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
#include "vda5050_interfaces/msg/action.hpp"
#include "vda5050_interfaces/msg/action_parameter.hpp"
#include "vda5050_interfaces/msg/action_parameter_factsheet.hpp"
#include "vda5050_interfaces/msg/action_parameter_value.hpp"
#include "vda5050_interfaces/msg/action_state.hpp"
#include "vda5050_interfaces/msg/agv_action.hpp"
#include "vda5050_interfaces/msg/agv_geometry.hpp"
Expand Down Expand Up @@ -78,7 +77,6 @@
using vda5050_interfaces::msg::Action;
using vda5050_interfaces::msg::ActionParameter;
using vda5050_interfaces::msg::ActionParameterFactsheet;
using vda5050_interfaces::msg::ActionParameterValue;
using vda5050_interfaces::msg::ActionState;
using vda5050_interfaces::msg::AGVAction;
using vda5050_interfaces::msg::AGVGeometry;
Expand Down Expand Up @@ -324,17 +322,6 @@ class RandomDataGenerator
return states[state_idx];
}

/// \brief Generate a random ActionParameterValue type
uint8_t generate_random_action_parameter_value_type()
{
std::vector<uint8_t> states = {
ActionParameterValue::TYPE_ARRAY, ActionParameterValue::TYPE_BOOL,
ActionParameterValue::TYPE_NUMBER, ActionParameterValue::TYPE_STRING,
ActionParameterValue::TYPE_OBJECT};
auto state_idx = generate_random_index(states.size());
return states[state_idx];
}

/// \brief Generate a random scope value for actionScopes
std::string generate_random_scope()
{
Expand Down Expand Up @@ -843,15 +830,10 @@ class RandomDataGenerator
msg.agv_position.push_back(generate<AGVPosition>());
msg.velocity.push_back(generate<Velocity>());
}
else if constexpr (std::is_same_v<T, ActionParameterValue>)
{
msg.type = generate_random_action_parameter_value_type();
msg.value = generate_random_string();
}
else if constexpr (std::is_same_v<T, ActionParameter>)
{
msg.key = generate_random_string();
msg.value = generate<ActionParameterValue>();
msg.value = generate_random_string();
}
else if constexpr (std::is_same_v<T, Action>)
{
Expand All @@ -867,16 +849,6 @@ class RandomDataGenerator
msg.header = generate<Header>();
msg.actions = generate_random_vector<Action>(generate_random_size());
}
else if constexpr (std::is_same_v<T, ActionParameterValue>)
{
msg.type = generate_random_action_parameter_value_type();
msg.value = generate_random_string();
}
else if constexpr (std::is_same_v<T, ActionParameter>)
{
msg.key = generate_random_string();
msg.value = generate<ActionParameterValue>();
}
else if constexpr (std::is_same_v<T, Action>)
{
msg.action_type = generate_random_string();
Expand Down
21 changes: 9 additions & 12 deletions test/test_json_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
#include "vda5050_interfaces/json_utils/action.hpp"
#include "vda5050_interfaces/json_utils/action_parameter.hpp"
#include "vda5050_interfaces/json_utils/action_parameter_factsheet.hpp"
#include "vda5050_interfaces/json_utils/action_parameter_value.hpp"
#include "vda5050_interfaces/json_utils/action_state.hpp"
#include "vda5050_interfaces/json_utils/agv_action.hpp"
#include "vda5050_interfaces/json_utils/agv_geometry.hpp"
Expand Down Expand Up @@ -75,7 +74,6 @@
using vda5050_interfaces::msg::Action;
using vda5050_interfaces::msg::ActionParameter;
using vda5050_interfaces::msg::ActionParameterFactsheet;
using vda5050_interfaces::msg::ActionParameterValue;
using vda5050_interfaces::msg::ActionState;
using vda5050_interfaces::msg::AGVAction;
using vda5050_interfaces::msg::AGVGeometry;
Expand Down Expand Up @@ -125,16 +123,15 @@ using vda5050_interfaces::msg::WheelDefinition;

// List of types to be tested for serialization round-trip
using SerializableTypes = ::testing::Types<
Action, ActionParameter, ActionParameterFactsheet, ActionParameterValue,
ActionState, AGVAction, AGVGeometry, AGVPosition, BatteryState,
BoundingBoxReference, Connection, ControlPoint, EdgeState, Envelope2d,
Envelope3d, Error, ErrorReference, Factsheet, Header, Info, InfoReference,
InstantActions, Load, LoadDimensions, LoadSet, LoadSpecification,
MaxArrayLens, MaxStringLens, Network, Node, NodePosition, NodeState,
OptionalParameters, Order, PhysicalParameters, PolygonPoint, Position,
ProtocolFeatures, ProtocolLimits, SafetyState, State, Timing, Trajectory,
TypeSpecification, VehicleConfig, Velocity, VersionInfo, Visualization,
WheelDefinition>;
Action, ActionParameter, ActionParameterFactsheet, ActionState, AGVAction,
AGVGeometry, AGVPosition, BatteryState, BoundingBoxReference, Connection,
ControlPoint, EdgeState, Envelope2d, Envelope3d, Error, ErrorReference,
Factsheet, Header, Info, InfoReference, InstantActions, Load, LoadDimensions,
LoadSet, LoadSpecification, MaxArrayLens, MaxStringLens, Network, Node,
NodePosition, NodeState, OptionalParameters, Order, PhysicalParameters,
PolygonPoint, Position, ProtocolFeatures, ProtocolLimits, SafetyState, State,
Timing, Trajectory, TypeSpecification, VehicleConfig, Velocity, VersionInfo,
Visualization, WheelDefinition>;

template <typename T>
class SerializationTest : public ::testing::Test
Expand Down